Cleanup various compiler warnings that were appearing since the

additional compiler flags were added.
This commit is contained in:
Dominic Clifton 2014-08-01 20:02:10 +01:00
parent 2d6a61c8c7
commit 9a9ff9b1ad
25 changed files with 102 additions and 37 deletions

View File

@ -34,6 +34,7 @@
#include <stdarg.h>
#include <stdlib.h>
#include "build_config.h"
#include "drivers/serial.h"
#include "io/serial.h"
@ -176,6 +177,7 @@ void tfp_sprintf(char *s, char *fmt, ...)
static void _putc(void *p, char c)
{
UNUSED(p);
serialWrite(printfSerialPort, c);
}

View File

@ -28,6 +28,8 @@
#include "drivers/accgyro.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "sensors/sensors.h"

View File

@ -102,7 +102,7 @@ typedef struct {
#define SMD500_PARAM_MH -7357 //calibration parameter
#define SMD500_PARAM_MI 3791 //calibration parameter
static bmp085_t bmp085 = { { 0, } };
static bmp085_t bmp085;
static bool bmp085InitDone = false;
static uint16_t bmp085_ut; // static result of temperature measurement
static uint32_t bmp085_up; // static result of pressure measurement

View File

@ -265,6 +265,8 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (setup[i] == 0xFFFF) // terminator
break;
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
if (timerIndex == PWM2)
@ -310,7 +312,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#ifdef LED_STRIP_TIMER
// skip LED Strip output
if (init->useLEDStrip && timerHardware[timerIndex].tim == LED_STRIP_TIMER)
if (init->useLEDStrip && timerHardwarePtr->tim == LED_STRIP_TIMER)
continue;
#endif
@ -353,19 +355,19 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
}
if (type == TYPE_IP) {
ppmInConfig(timerIndex);
ppmInConfig(timerHardwarePtr);
} else if (type == TYPE_IW) {
pwmInConfig(timerIndex, channelIndex);
pwmInConfig(timerHardwarePtr, channelIndex);
channelIndex++;
} else if (type == TYPE_M) {
if (init->motorPwmRate > 500) {
pwmBrushedMotorConfig(&timerHardware[timerIndex], pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
} else {
pwmBrushlessMotorConfig(&timerHardware[timerIndex], pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
}
pwmOutputConfiguration.motorCount++;
} else if (type == TYPE_S) {
pwmServoConfig(&timerHardware[timerIndex], pwmOutputConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse);
pwmServoConfig(timerHardwarePtr, pwmOutputConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse);
pwmOutputConfiguration.servoCount++;
}
}

View File

@ -21,6 +21,7 @@
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "gpio.h"
#include "timer.h"
@ -129,11 +130,13 @@ static void ppmInit(void)
static void ppmOverflowCallback(uint8_t port, captureCompare_t capture)
{
UNUSED(port);
ppmDev.largeCounter += capture;
}
static void ppmEdgeCallback(uint8_t port, captureCompare_t capture)
{
UNUSED(port);
int32_t i;
/* Shift the last measurement out */
@ -212,12 +215,12 @@ static void ppmEdgeCallback(uint8_t port, captureCompare_t capture)
static void pwmEdgeCallback(uint8_t port, captureCompare_t capture)
{
pwmInputPort_t *pwmInputPort = &pwmInputPorts[port];
const timerHardware_t *timerHardware = pwmInputPort->timerHardware;
const timerHardware_t *timerHardwarePtr = pwmInputPort->timerHardware;
if (pwmInputPort->state == 0) {
pwmInputPort->rise = capture;
pwmInputPort->state = 1;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
} else {
pwmInputPort->fall = capture;
@ -227,7 +230,7 @@ static void pwmEdgeCallback(uint8_t port, captureCompare_t capture)
// switch state
pwmInputPort->state = 0;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
}
}
@ -260,12 +263,10 @@ void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
TIM_ICInit(tim, &TIM_ICInitStructure);
}
void pwmInConfig(uint8_t timerIndex, uint8_t channel)
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
{
pwmInputPort_t *p = &pwmInputPorts[channel];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->channel = channel;
p->mode = INPUT_MODE_PWM;
p->timerHardware = timerHardwarePtr;
@ -280,14 +281,12 @@ void pwmInConfig(uint8_t timerIndex, uint8_t channel)
#define UNUSED_PPM_TIMER_REFERENCE 0
#define FIRST_PWM_PORT 0
void ppmInConfig(uint8_t timerIndex)
void ppmInConfig(const timerHardware_t *timerHardwarePtr)
{
ppmInit();
pwmInputPort_t *p = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->mode = INPUT_MODE_PPM;
p->timerHardware = timerHardwarePtr;

View File

@ -22,8 +22,8 @@ typedef enum {
INPUT_FILTERING_ENABLED
} inputFilteringMode_e;
void ppmInConfig(uint8_t timerIndex);
void pwmInConfig(uint8_t timerIndex, uint8_t channel);
void ppmInConfig(const timerHardware_t *timerHardwarePtr);
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel);
uint16_t pwmRead(uint8_t channel);

View File

@ -21,6 +21,8 @@
#include "platform.h"
#include "build_config.h"
#include "system.h"
#include "gpio.h"
#include "timer.h"
@ -312,6 +314,7 @@ void processRxState(softSerial_t *softSerial)
void onSerialTimer(uint8_t portIndex, captureCompare_t capture)
{
UNUSED(capture);
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
processTxState(softSerial);
@ -320,6 +323,8 @@ void onSerialTimer(uint8_t portIndex, captureCompare_t capture)
void onSerialRxPinChange(uint8_t portIndex, captureCompare_t capture)
{
UNUSED(capture);
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
if ((softSerial->port.mode & MODE_RX) == 0) {

View File

@ -26,6 +26,8 @@
#include "platform.h"
#include "build_config.h"
#include "serial.h"
#include "serial_uart.h"
@ -57,6 +59,7 @@ static void uartReconfigure(uartPort_t *uartPort)
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
{
UNUSED(inversion);
DMA_InitTypeDef DMA_InitStructure;
uartPort_t *s = NULL;

View File

@ -26,6 +26,8 @@
#include "drivers/accgyro.h"
#include "drivers/serial.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
// FIXME remove dependency on currentProfile and masterConfig globals and clean up include file list.

View File

@ -19,6 +19,8 @@
#include <stdint.h>
#include <math.h>
#include "build_config.h"
#include "common/axis.h"
#include "common/maths.h"
@ -178,6 +180,8 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
int32_t deltaSum;
int32_t delta;
UNUSED(controlRateConfig);
// **** PITCH & ROLL & YAW PID ****
prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500]
for (axis = 0; axis < 3; axis++) {

View File

@ -79,7 +79,7 @@ typedef struct airplaneConfig_t {
uint8_t flaps_speed; // airplane mode flaps, 0 = no flaps, > 0 = flap speed, larger = faster
} airplaneConfig_t;
#define CHANNEL_FORWARDING_DISABLED 0xFF
#define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF
typedef struct servoParam_t {
int16_t min; // servo min

View File

@ -412,10 +412,10 @@ static void GPS_calc_longitude_scaling(int32_t lat);
static void GPS_calc_velocity(void);
static void GPS_calc_location_error(int32_t * target_lat, int32_t * target_lng, int32_t * gps_lat, int32_t * gps_lng);
static void GPS_calc_poshold(void);
static void GPS_calc_nav_rate(int max_speed);
static void GPS_calc_nav_rate(uint16_t max_speed);
static void GPS_update_crosstrack(void);
static bool UBLOX_parse_gps(void);
static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow);
static uint16_t GPS_calc_desired_speed(uint16_t max_speed, bool _slow);
static int32_t wrap_18000(int32_t error);
static int32_t wrap_36000(int32_t angle);
@ -554,7 +554,7 @@ static void gpsNewData(uint16_t c)
static uint32_t nav_loopTimer;
uint32_t dist;
int32_t dir;
int16_t speed;
uint16_t speed;
if (gpsNewFrame(c)) {
// new data received and parsed, we're in business
@ -884,7 +884,7 @@ static void GPS_calc_poshold(void)
////////////////////////////////////////////////////////////////////////////////////
// Calculate the desired nav_lat and nav_lon for distance flying such as RTH
//
static void GPS_calc_nav_rate(int max_speed)
static void GPS_calc_nav_rate(uint16_t max_speed)
{
float trig[2];
float temp;
@ -938,7 +938,7 @@ static void GPS_update_crosstrack(void)
// | +|+
// |< we should slow to 1.5 m/s as we hit the target
//
static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow)
static uint16_t GPS_calc_desired_speed(uint16_t max_speed, bool _slow)
{
// max_speed is default 400 or 4m/s
if (_slow) {

View File

@ -22,6 +22,8 @@
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
@ -88,7 +90,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
};
const static serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE },
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE},
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
@ -319,6 +321,7 @@ void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function)
{
UNUSED(function);
serialPortFunction_t *serialPortFunction = findSerialPortFunctionByPort(port);
serialPortFunction->currentFunction = FUNCTION_NONE;
@ -410,7 +413,7 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
return true;
}
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier)
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier)
{
serialPortSearchResult_t *searchResult;
const functionConstraint_t *functionConstraint;

View File

@ -152,7 +152,7 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig);
bool isSerialConfigValid(serialConfig_t *serialConfig);
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier);
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask);
const serialPortFunctionList_t *getSerialPortFunctionList(void);

View File

@ -25,6 +25,8 @@
#include "platform.h"
#include "build_config.h"
#include "common/axis.h"
#include "common/typeconversion.h"
@ -32,6 +34,8 @@
#include "drivers/accgyro.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "flight/flight.h"
#include "flight/mixer.h"
@ -480,12 +484,14 @@ static void cliCMix(char *cmdline)
static void cliDump(char *cmdline)
{
int i;
unsigned int i;
char buf[16];
float thr, roll, pitch, yaw;
uint32_t mask;
const clivalue_t *setval;
UNUSED(cmdline);
printf("Current Config: Copy everything below here...\r\n");
// print out aux switches
@ -648,6 +654,8 @@ static void cliFeature(char *cmdline)
#ifdef GPS
static void cliGpsPassthrough(char *cmdline)
{
UNUSED(cmdline);
gpsEnablePassthroughResult_e result = gpsEnablePassthrough();
switch (result) {
@ -669,6 +677,8 @@ static void cliHelp(char *cmdline)
{
uint32_t i = 0;
UNUSED(cmdline);
cliPrint("Available commands:\r\n");
for (i = 0; i < CMD_COUNT; i++)
printf("%s\t%s\r\n", cmdTable[i].name, cmdTable[i].param);
@ -809,6 +819,8 @@ static void cliReboot(void) {
static void cliSave(char *cmdline)
{
UNUSED(cmdline);
cliPrint("Saving...");
copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
writeEEPROM();
@ -817,6 +829,8 @@ static void cliSave(char *cmdline)
static void cliDefaults(char *cmdline)
{
UNUSED(cmdline);
cliPrint("Resetting to defaults...");
resetEEPROM();
cliReboot();
@ -964,6 +978,8 @@ static void cliStatus(char *cmdline)
uint8_t i;
uint32_t mask;
UNUSED(cmdline);
printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery)\r\n",
millis() / 1000, vbat, batteryCellCount);
mask = sensorsMask();
@ -987,6 +1003,8 @@ static void cliStatus(char *cmdline)
static void cliVersion(char *cmdline)
{
UNUSED(cmdline);
cliPrint("Afro32 CLI version 2.2 " __DATE__ " / " __TIME__ " - (" __FORKNAME__ ")");
}
@ -1001,7 +1019,7 @@ void cliProcess(void)
if (c == '\t' || c == '?') {
// do tab completion
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
int i = bufferIndex;
uint32_t i = bufferIndex;
for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
continue;

View File

@ -31,6 +31,8 @@
#include "drivers/accgyro.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "flight/flight.h"
@ -911,7 +913,7 @@ static const uint8_t mspTelemetryCommandSequence[] = {
void sendMspTelemetry(void)
{
static int sequenceIndex = 0;
static uint32_t sequenceIndex = 0;
cmdMSP = mspTelemetryCommandSequence[sequenceIndex];
evaluateCommand();

View File

@ -185,7 +185,7 @@ void init(void)
#ifdef STM32F10X_MD
if (!feature(FEATURE_RX_PARALLEL_PWM)) {
pwm_params.useUART2 = doesConfigurationUsePort(&masterConfig.serialConfig, SERIAL_PORT_USART2);
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
}
#endif

View File

@ -31,6 +31,7 @@
#include "drivers/gpio.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "flight/flight.h"

View File

@ -20,6 +20,8 @@
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/serial.h"
@ -31,8 +33,9 @@
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan)
{
UNUSED(rxRuntimeConfigPtr);
return rcData[chan];
}
@ -52,6 +55,7 @@ bool rxMspFrameComplete(void)
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
UNUSED(rxConfig);
rxRuntimeConfig->channelCount = 8; // See MSP_SET_RAW_RC
if (callback)
*callback = rxMspReadRawRC;

View File

@ -21,8 +21,12 @@
#include <string.h>
#include "build_config.h"
#include "platform.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "config/config.h"
@ -30,21 +34,23 @@
#include "rx/rx.h"
#include "rx/pwm.h"
static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan)
{
UNUSED(rxRuntimeConfigPtr);
return pwmRead(chan);
}
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfigPtr, rcReadRawDataPtr *callback)
{
UNUSED(rxRuntimeConfigPtr);
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
*callback = pwmReadRawRC;
if (feature(FEATURE_RX_PARALLEL_PWM)) {
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
}
if (feature(FEATURE_RX_PPM)) {
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
}
}

View File

@ -33,6 +33,8 @@
#include "flight/failsafe.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "rx/pwm.h"
#include "rx/sbus.h"

View File

@ -21,6 +21,8 @@
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/serial.h"
@ -142,6 +144,7 @@ bool sbusFrameComplete(void)
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
return sbusChannelData[chan] / 2 + SBUS_OFFSET;
}

View File

@ -46,7 +46,7 @@ static bool rcFrameComplete = false;
static bool spekHiRes = false;
static bool spekDataIncoming = false;
volatile static uint8_t spekFrame[SPEK_FRAME_SIZE];
static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static void spektrumDataReceive(uint16_t c);
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);

View File

@ -21,6 +21,8 @@
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/serial.h"
@ -57,6 +59,7 @@ void sumdUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstrai
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
UNUSED(rxConfig);
sumdPort = openSerialPort(FUNCTION_SERIAL_RX, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED);
if (callback)
*callback = sumdReadRawRC;
@ -131,5 +134,6 @@ bool sumdFrameComplete(void)
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
return sumdChannelData[chan] / 8;
}

View File

@ -27,6 +27,8 @@
#include "platform.h"
#include "build_config.h"
#ifdef TELEMETRY
#include "drivers/serial.h"
@ -35,6 +37,7 @@
void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig)
{
UNUSED(initialTelemetryConfig);
}
void handleMSPTelemetry(void)