From a2d854493178174a3957fbde153a19fadbb68a67 Mon Sep 17 00:00:00 2001 From: "Richard Flay (Hyper)" Date: Sun, 5 May 2013 16:32:24 +0930 Subject: [PATCH] OP-931: adds -Wextra compiler option for the flight code, and makes the bazillion code changes required to make the flight code compile again. Needs careful review, particularly all the fixes for the signed vs unsigned comparisons. +review OPReview-459 --- flight/libraries/insgps13state.c | 2 +- flight/libraries/op_dfu.c | 2 +- flight/libraries/printf2.c | 30 ++++----- flight/modules/Actuator/actuator.c | 6 +- flight/modules/Airspeed/revolution/airspeed.c | 4 +- .../revolution/baro_airspeed_etasv3.c | 2 +- flight/modules/Altitude/altitude.c | 2 +- flight/modules/Altitude/revolution/altitude.c | 2 +- flight/modules/AltitudeHold/altitudehold.c | 4 +- flight/modules/Attitude/attitude.c | 4 +- flight/modules/Attitude/revolution/attitude.c | 2 +- flight/modules/Autotune/autotune.c | 2 +- flight/modules/Battery/battery.c | 2 +- flight/modules/ComUsbBridge/ComUsbBridge.c | 8 +-- flight/modules/Example/examplemodcallback.c | 2 +- flight/modules/Example/examplemodperiodic.c | 2 +- flight/modules/Example/examplemodthread.c | 2 +- flight/modules/Extensions/MagBaro/magbaro.c | 2 +- flight/modules/FirmwareIAP/firmwareiap.c | 2 +- .../fixedwingpathfollower.c | 6 +- flight/modules/FlightPlan/flightplan.c | 2 +- flight/modules/GPS/GPS.c | 4 +- flight/modules/GPS/NMEA.c | 8 +-- flight/modules/MK/MKSerial/MKSerial.c | 2 +- flight/modules/ManualControl/manualcontrol.c | 20 +++--- flight/modules/OPLink/oplinkmod.c | 5 +- flight/modules/Osd/OsdEtStd/OsdEtStd.c | 6 +- flight/modules/Osd/WavPlayer/wavplayer.c | 2 +- flight/modules/Osd/osdgen/inc/osdgen.h | 14 ++--- flight/modules/Osd/osdgen/osdgen.c | 61 ++++++++++--------- flight/modules/Osd/osdinput/osdinput.c | 2 +- flight/modules/Osd/osdoutput/osdoutput.c | 2 +- flight/modules/OveroSync/overosync.c | 2 +- .../modules/OveroSync/simulated/overosync.c | 2 +- flight/modules/PathPlanner/pathplanner.c | 4 +- .../modules/RadioComBridge/RadioComBridge.c | 8 +-- flight/modules/Sensors/sensors.c | 4 +- flight/modules/Sensors/simulated/sensors.c | 2 +- flight/modules/Stabilization/stabilization.c | 4 +- flight/modules/System/systemmod.c | 7 ++- flight/modules/Telemetry/telemetry.c | 6 +- .../VtolPathFollower/vtolpathfollower.c | 4 +- flight/pios/common/libraries/dosfs/dosfs.c | 4 +- flight/pios/common/libraries/msheap/msheap.c | 2 +- .../common/libraries/msheap/pios_msheap.c | 2 +- flight/pios/common/pios_adxl345.c | 2 +- flight/pios/common/pios_bma180.c | 2 +- flight/pios/common/pios_bmp085.c | 4 +- flight/pios/common/pios_com_msg.c | 4 +- flight/pios/common/pios_flash_jedec.c | 4 +- flight/pios/common/pios_flashfs_logfs.c | 8 +-- flight/pios/common/pios_gcsrcvr.c | 4 +- flight/pios/common/pios_mpu6000.c | 4 +- flight/pios/common/pios_rfm22b.c | 6 +- flight/pios/common/pios_rfm22b_com.c | 5 +- flight/pios/inc/pios_rfm22b_priv.h | 2 +- flight/pios/stm32f10x/pios_debug.c | 13 ++-- flight/pios/stm32f10x/pios_eeprom.c | 2 +- flight/pios/stm32f10x/pios_led.c | 2 +- flight/pios/stm32f10x/pios_ppm.c | 14 +++-- flight/pios/stm32f10x/pios_ppm_out.c | 7 ++- flight/pios/stm32f10x/pios_pwm.c | 8 +-- flight/pios/stm32f10x/pios_spi.c | 2 +- flight/pios/stm32f10x/pios_usart.c | 4 +- flight/pios/stm32f10x/pios_usb.c | 2 +- flight/pios/stm32f10x/pios_usb_cdc.c | 2 +- flight/pios/stm32f10x/pios_usb_hid.c | 2 +- flight/pios/stm32f10x/pios_usb_hid_pwr.c | 2 +- flight/pios/stm32f10x/pios_usbhook.c | 2 +- .../Core/src/usbd_core.c | 2 +- .../STM32_USB_OTG_Driver/inc/usb_dcd_int.h | 4 +- flight/pios/stm32f4xx/pios_adc.c | 12 ++-- flight/pios/stm32f4xx/pios_debug.c | 12 ++-- flight/pios/stm32f4xx/pios_flash_internal.c | 2 +- flight/pios/stm32f4xx/pios_i2c.c | 8 +-- flight/pios/stm32f4xx/pios_led.c | 2 +- flight/pios/stm32f4xx/pios_overo.c | 4 +- flight/pios/stm32f4xx/pios_ppm.c | 9 +-- flight/pios/stm32f4xx/pios_pwm.c | 8 +-- flight/pios/stm32f4xx/pios_spi.c | 2 +- flight/pios/stm32f4xx/pios_usart.c | 4 +- flight/pios/stm32f4xx/pios_usb.c | 6 +- flight/pios/stm32f4xx/pios_usb_hid.c | 8 +-- flight/pios/stm32f4xx/pios_usbhook.c | 36 +++++------ flight/pios/stm32f4xx/startup.c | 4 +- flight/pios/stm32f4xx/vectors_stm32f4xx.c | 4 +- .../targets/boards/oplinkmini/board_hw_defs.c | 4 +- flight/targets/boards/osd/board_hw_defs.c | 10 +-- flight/targets/boards/osd/firmware/fonts.c | 2 +- .../targets/boards/osd/firmware/inc/splash.h | 12 ++-- flight/targets/boards/osd/firmware/osd.c | 2 +- .../targets/boards/osd/firmware/pios_board.c | 4 +- .../boards/revolution/firmware/pios_board.c | 10 +-- .../boards/revolution/firmware/revolution.c | 2 +- .../targets/boards/revoproto/board_hw_defs.c | 2 +- .../boards/revoproto/firmware/pios_board.c | 2 +- .../boards/revoproto/firmware/revolution.c | 2 +- .../boards/simposix/firmware/simposix.c | 2 +- flight/uavobjects/eventdispatcher.c | 10 +-- flight/uavobjects/uavobjectmanager.c | 6 +- flight/uavtalk/inc/uavtalk_priv.h | 2 +- flight/uavtalk/uavtalk.c | 7 ++- make/common-defs.mk | 2 +- 103 files changed, 300 insertions(+), 282 deletions(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index 051338572..420505eb6 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -141,7 +141,7 @@ void INSResetP(float PDiag[NUMX]) } } -void INSSetState(float pos[3], float vel[3], float q[4], float gyro_bias[3], float accel_bias[3]) +void INSSetState(float pos[3], float vel[3], float q[4], float gyro_bias[3], __attribute__((unused)) float accel_bias[3]) { /* Note: accel_bias not used in 13 state INS */ X[0] = pos[0]; diff --git a/flight/libraries/op_dfu.c b/flight/libraries/op_dfu.c index 60fe8fe86..786ce1910 100644 --- a/flight/libraries/op_dfu.c +++ b/flight/libraries/op_dfu.c @@ -78,7 +78,7 @@ extern uint8_t JumpToApp; void sendData(uint8_t * buf, uint16_t size); uint32_t CalcFirmCRC(void); -void DataDownload(DownloadAction action) { +void DataDownload(__attribute__((unused)) DownloadAction action) { if ((DeviceState == downloading)) { uint8_t packetSize; diff --git a/flight/libraries/printf2.c b/flight/libraries/printf2.c index 8a3f44e2c..dee058976 100644 --- a/flight/libraries/printf2.c +++ b/flight/libraries/printf2.c @@ -74,7 +74,7 @@ char **environ = __env; /*============================================================================== * Close a file. */ -int _close(int file) +int _close(__attribute__((unused)) int file) { return -1; } @@ -82,7 +82,7 @@ int _close(int file) /*============================================================================== * Transfer control to a new process. */ -int _execve(char *name, char **argv, char **env) +int _execve(__attribute__((unused)) char *name, __attribute__((unused)) char **argv, __attribute__((unused)) char **env) { errno = ENOMEM; return -1; @@ -91,7 +91,7 @@ int _execve(char *name, char **argv, char **env) /*============================================================================== * Exit a program without cleaning up files. */ -void _exit( int code ) +void _exit( __attribute__((unused)) int code ) { /* Should we force a system reset? */ while( 1 ) @@ -112,7 +112,7 @@ int _fork(void) /*============================================================================== * Status of an open file. */ -int _fstat(int file, struct stat *st) +int _fstat(__attribute__((unused)) int file, struct stat *st) { st->st_mode = S_IFCHR; return 0; @@ -129,7 +129,7 @@ int _getpid(void) /*============================================================================== * Query whether output stream is a terminal. */ -int _isatty(int file) +int _isatty(__attribute__((unused)) int file) { return 1; } @@ -137,7 +137,7 @@ int _isatty(int file) /*============================================================================== * Send a signal. */ -int _kill(int pid, int sig) +int _kill(__attribute__((unused)) int pid, __attribute__((unused)) int sig) { errno = EINVAL; return -1; @@ -146,7 +146,7 @@ int _kill(int pid, int sig) /*============================================================================== * Establish a new name for an existing file. */ -int _link(char *old, char *new) +int _link(__attribute__((unused)) char *old, __attribute__((unused)) char *new) { errno = EMLINK; return -1; @@ -155,7 +155,7 @@ int _link(char *old, char *new) /*============================================================================== * Set position in a file. */ -int _lseek(int file, int ptr, int dir) +int _lseek(__attribute__((unused)) int file, __attribute__((unused)) int ptr, __attribute__((unused)) int dir) { return 0; } @@ -163,7 +163,7 @@ int _lseek(int file, int ptr, int dir) /*============================================================================== * Open a file. */ -int _open(const char *name, int flags, int mode) +int _open(__attribute__((unused)) const char *name, __attribute__((unused)) int flags, __attribute__((unused)) int mode) { return -1; } @@ -171,7 +171,7 @@ int _open(const char *name, int flags, int mode) /*============================================================================== * Read from a file. */ -int _read(int file, char *ptr, int len) +int _read(__attribute__((unused)) int file, __attribute__((unused)) char *ptr, __attribute__((unused)) int len) { return 0; } @@ -182,7 +182,7 @@ int _read(int file, char *ptr, int len) * example to a serial port for debugging, you should make your minimal write * capable of doing this. */ -int _write_r( void * reent, int file, char * ptr, int len ) +int _write_r( __attribute__((unused)) void * reent, __attribute__((unused)) int file, __attribute__((unused)) char * ptr, __attribute__((unused)) int len ) { return 0; } @@ -220,7 +220,7 @@ caddr_t _sbrk(int incr) /*============================================================================== * Status of a file (by name). */ -int _stat(char *file, struct stat *st) +int _stat(__attribute__((unused)) char *file, struct stat *st) { st->st_mode = S_IFCHR; return 0; @@ -229,7 +229,7 @@ int _stat(char *file, struct stat *st) /*============================================================================== * Timing information for current process. */ -int _times(struct tms *buf) +int _times(__attribute__((unused)) struct tms *buf) { return -1; } @@ -237,7 +237,7 @@ int _times(struct tms *buf) /*============================================================================== * Remove a file's directory entry. */ -int _unlink(char *name) +int _unlink(__attribute__((unused)) char *name) { errno = ENOENT; return -1; @@ -246,7 +246,7 @@ int _unlink(char *name) /*============================================================================== * Wait for a child process. */ -int _wait(int *status) +int _wait(__attribute__((unused)) int *status) { errno = ECHILD; return -1; diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index 39d2faabf..8ee52fce9 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -150,7 +150,7 @@ MODULE_INITCALL(ActuatorInitialize, ActuatorStart) * * @return -1 if error, 0 if success */ -static void actuatorTask(void* parameters) +static void actuatorTask(__attribute__((unused)) void* parameters) { UAVObjEvent ev; portTickType lastSysTime; @@ -718,12 +718,12 @@ static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuato } } -static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev) +static void ActuatorSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { actuator_settings_updated = true; } -static void MixerSettingsUpdatedCb(UAVObjEvent * ev) +static void MixerSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { mixer_settings_updated = true; } diff --git a/flight/modules/Airspeed/revolution/airspeed.c b/flight/modules/Airspeed/revolution/airspeed.c index fd1479d0f..5703f33a8 100644 --- a/flight/modules/Airspeed/revolution/airspeed.c +++ b/flight/modules/Airspeed/revolution/airspeed.c @@ -129,7 +129,7 @@ MODULE_INITCALL(AirspeedInitialize, AirspeedStart) /** * Module thread, should not return. */ -static void airspeedTask(void *parameters) +static void airspeedTask(__attribute__((unused)) void *parameters) { AirspeedSettingsUpdatedCb(AirspeedSettingsHandle()); @@ -177,7 +177,7 @@ static void airspeedTask(void *parameters) -static void AirspeedSettingsUpdatedCb(UAVObjEvent * ev) +static void AirspeedSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { AirspeedSettingsGet(&airspeedSettings); diff --git a/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c b/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c index 5da2e2810..3f6012c30 100644 --- a/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c +++ b/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c @@ -61,7 +61,7 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings //Check to see if airspeed sensor is returning airspeedSensor airspeedSensor->SensorValue = PIOS_ETASV3_ReadAirspeed(); - if (airspeedSensor->SensorValue==-1) { + if (airspeedSensor->SensorValue==(uint16_t)-1) { airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE; airspeedSensor->CalibratedAirspeed = 0; return; diff --git a/flight/modules/Altitude/altitude.c b/flight/modules/Altitude/altitude.c index 04c2ac48c..f848d8931 100644 --- a/flight/modules/Altitude/altitude.c +++ b/flight/modules/Altitude/altitude.c @@ -125,7 +125,7 @@ MODULE_INITCALL(AltitudeInitialize, AltitudeStart) /** * Module thread, should not return. */ -static void altitudeTask(void *parameters) +static void altitudeTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; diff --git a/flight/modules/Altitude/revolution/altitude.c b/flight/modules/Altitude/revolution/altitude.c index 1cee36418..a97e4bd2c 100644 --- a/flight/modules/Altitude/revolution/altitude.c +++ b/flight/modules/Altitude/revolution/altitude.c @@ -84,7 +84,7 @@ MODULE_INITCALL(AltitudeInitialize, AltitudeStart) /** * Module thread, should not return. */ -static void altitudeTask(void *parameters) +static void altitudeTask(__attribute__((unused)) void *parameters) { BaroAltitudeData data; diff --git a/flight/modules/AltitudeHold/altitudehold.c b/flight/modules/AltitudeHold/altitudehold.c index 69c617d46..129875b60 100644 --- a/flight/modules/AltitudeHold/altitudehold.c +++ b/flight/modules/AltitudeHold/altitudehold.c @@ -118,7 +118,7 @@ float starting_altitude; /** * Module thread, should not return. */ -static void altitudeHoldTask(void *parameters) +static void altitudeHoldTask(__attribute__((unused)) void *parameters) { AltitudeHoldDesiredData altitudeHoldDesired; StabilizationDesiredData stabilizationDesired; @@ -386,7 +386,7 @@ static void altitudeHoldTask(void *parameters) } } -static void SettingsUpdatedCb(UAVObjEvent * ev) +static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { AltitudeHoldSettingsGet(&altitudeHoldSettings); } diff --git a/flight/modules/Attitude/attitude.c b/flight/modules/Attitude/attitude.c index 4186091b7..74137c001 100644 --- a/flight/modules/Attitude/attitude.c +++ b/flight/modules/Attitude/attitude.c @@ -174,7 +174,7 @@ MODULE_INITCALL(AttitudeInitialize, AttitudeStart) int32_t accel_test; int32_t gyro_test; -static void AttitudeTask(void *parameters) +static void AttitudeTask(__attribute__((unused)) void *parameters) { uint8_t init = 0; AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); @@ -573,7 +573,7 @@ static void updateAttitude(AccelsData * accelsData, GyrosData * gyrosData) AttitudeActualSet(&attitudeActual); } -static void settingsUpdatedCb(UAVObjEvent * objEv) { +static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent * objEv) { AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); diff --git a/flight/modules/Attitude/revolution/attitude.c b/flight/modules/Attitude/revolution/attitude.c index 7c8427ddd..962898ed1 100644 --- a/flight/modules/Attitude/revolution/attitude.c +++ b/flight/modules/Attitude/revolution/attitude.c @@ -203,7 +203,7 @@ MODULE_INITCALL(AttitudeInitialize, AttitudeStart) /** * Module thread, should not return. */ -static void AttitudeTask(void *parameters) +static void AttitudeTask(__attribute__((unused)) void *parameters) { bool first_run = true; uint32_t last_algorithm; diff --git a/flight/modules/Autotune/autotune.c b/flight/modules/Autotune/autotune.c index 260f70750..0570f7016 100644 --- a/flight/modules/Autotune/autotune.c +++ b/flight/modules/Autotune/autotune.c @@ -120,7 +120,7 @@ MODULE_INITCALL(AutotuneInitialize, AutotuneStart) /** * Module thread, should not return. */ -static void AutotuneTask(void *parameters) +static void AutotuneTask(__attribute__((unused)) void *parameters) { //AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); diff --git a/flight/modules/Battery/battery.c b/flight/modules/Battery/battery.c index ac9dcace3..c0f6db89e 100644 --- a/flight/modules/Battery/battery.c +++ b/flight/modules/Battery/battery.c @@ -124,7 +124,7 @@ int32_t BatteryInitialize(void) MODULE_INITCALL(BatteryInitialize, 0) #define HAS_SENSOR(x) batterySettings.SensorType[x]==FLIGHTBATTERYSETTINGS_SENSORTYPE_ENABLED -static void onTimer(UAVObjEvent* ev) +static void onTimer(__attribute__((unused)) UAVObjEvent* ev) { static FlightBatteryStateData flightBatteryData; FlightBatterySettingsData batterySettings; diff --git a/flight/modules/ComUsbBridge/ComUsbBridge.c b/flight/modules/ComUsbBridge/ComUsbBridge.c index 13c9f6ee4..7fd83b920 100644 --- a/flight/modules/ComUsbBridge/ComUsbBridge.c +++ b/flight/modules/ComUsbBridge/ComUsbBridge.c @@ -126,7 +126,7 @@ MODULE_INITCALL(comUsbBridgeInitialize, comUsbBridgeStart) * Main task. It does not return. */ -static void com2UsbBridgeTask(void *parameters) +static void com2UsbBridgeTask(__attribute__((unused)) void *parameters) { /* Handle usart -> vcp direction */ volatile uint32_t tx_errors = 0; @@ -136,7 +136,7 @@ static void com2UsbBridgeTask(void *parameters) rx_bytes = PIOS_COM_ReceiveBuffer(usart_port, com2usb_buf, BRIDGE_BUF_LEN, 500); if (rx_bytes > 0) { /* Bytes available to transfer */ - if (PIOS_COM_SendBuffer(vcp_port, com2usb_buf, rx_bytes) != rx_bytes) { + if (PIOS_COM_SendBuffer(vcp_port, com2usb_buf, rx_bytes) != (int32_t)rx_bytes) { /* Error on transmit */ tx_errors++; } @@ -144,7 +144,7 @@ static void com2UsbBridgeTask(void *parameters) } } -static void usb2ComBridgeTask(void * parameters) +static void usb2ComBridgeTask(__attribute__((unused)) void * parameters) { /* Handle vcp -> usart direction */ volatile uint32_t tx_errors = 0; @@ -154,7 +154,7 @@ static void usb2ComBridgeTask(void * parameters) rx_bytes = PIOS_COM_ReceiveBuffer(vcp_port, usb2com_buf, BRIDGE_BUF_LEN, 500); if (rx_bytes > 0) { /* Bytes available to transfer */ - if (PIOS_COM_SendBuffer(usart_port, usb2com_buf, rx_bytes) != rx_bytes) { + if (PIOS_COM_SendBuffer(usart_port, usb2com_buf, rx_bytes) != (int32_t)rx_bytes) { /* Error on transmit */ tx_errors++; } diff --git a/flight/modules/Example/examplemodcallback.c b/flight/modules/Example/examplemodcallback.c index 1a050f07e..6faba152f 100644 --- a/flight/modules/Example/examplemodcallback.c +++ b/flight/modules/Example/examplemodcallback.c @@ -83,7 +83,7 @@ int32_t ExampleModCallbackInitialize() * event thread. Because of that the callback execution time must be kept to * a minimum. */ -static void ObjectUpdatedCb(UAVObjEvent * ev) +static void ObjectUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { DelayedCallbackDispatch(cbinfo); } diff --git a/flight/modules/Example/examplemodperiodic.c b/flight/modules/Example/examplemodperiodic.c index abb2484f7..8bfe98211 100644 --- a/flight/modules/Example/examplemodperiodic.c +++ b/flight/modules/Example/examplemodperiodic.c @@ -76,7 +76,7 @@ int32_t ExampleModPeriodicInitialize() /** * Module thread, should not return. */ -static void exampleTask(void *parameters) +static void exampleTask(__attribute__((unused)) void *parameters) { ExampleSettingsData settings; ExampleObject2Data data; diff --git a/flight/modules/Example/examplemodthread.c b/flight/modules/Example/examplemodthread.c index d8d881a5d..813a437e4 100644 --- a/flight/modules/Example/examplemodthread.c +++ b/flight/modules/Example/examplemodthread.c @@ -84,7 +84,7 @@ int32_t ExampleModThreadInitialize() /** * Module thread, should not return. */ -static void exampleTask(void *parameters) +static void exampleTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; ExampleSettingsData settings; diff --git a/flight/modules/Extensions/MagBaro/magbaro.c b/flight/modules/Extensions/MagBaro/magbaro.c index 0cbc77dbd..a706940b2 100644 --- a/flight/modules/Extensions/MagBaro/magbaro.c +++ b/flight/modules/Extensions/MagBaro/magbaro.c @@ -140,7 +140,7 @@ static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { }; #endif -static void magbaroTask(void *parameters) +static void magbaroTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; diff --git a/flight/modules/FirmwareIAP/firmwareiap.c b/flight/modules/FirmwareIAP/firmwareiap.c index f8e6fd231..f0cc119c5 100644 --- a/flight/modules/FirmwareIAP/firmwareiap.c +++ b/flight/modules/FirmwareIAP/firmwareiap.c @@ -238,7 +238,7 @@ static uint32_t get_time(void) /** * Executed by event dispatcher callback to reset INS before resetting OP */ -static void resetTask(UAVObjEvent * ev) +static void resetTask(__attribute__((unused)) UAVObjEvent * ev) { #if defined (PIOS_LED_HEARTBEAT) PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); diff --git a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c index 6c67a18bc..8f4dcc049 100644 --- a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -143,7 +143,7 @@ static float indicatedAirspeedActualBias = 0; /** * Module thread, should not return. */ -static void pathfollowerTask(void *parameters) +static void pathfollowerTask(__attribute__((unused)) void *parameters) { SystemSettingsData systemSettings; FlightStatusData flightStatus; @@ -629,13 +629,13 @@ static float bound(float val, float min, float max) return val; } -static void SettingsUpdatedCb(UAVObjEvent * ev) +static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); PathDesiredGet(&pathDesired); } -static void airspeedActualUpdatedCb(UAVObjEvent * ev) +static void airspeedActualUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { AirspeedActualData airspeedActual; diff --git a/flight/modules/FlightPlan/flightplan.c b/flight/modules/FlightPlan/flightplan.c index e919dd41e..7c3b58027 100644 --- a/flight/modules/FlightPlan/flightplan.c +++ b/flight/modules/FlightPlan/flightplan.c @@ -94,7 +94,7 @@ MODULE_INITCALL(FlightPlanInitialize, FlightPlanStart) /** * Module task */ -static void flightPlanTask(void *parameters) +static void flightPlanTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; PmReturn_t retval; diff --git a/flight/modules/GPS/GPS.c b/flight/modules/GPS/GPS.c index c9a2422fd..ec2d79d3f 100644 --- a/flight/modules/GPS/GPS.c +++ b/flight/modules/GPS/GPS.c @@ -194,7 +194,7 @@ MODULE_INITCALL(GPSInitialize, GPSStart) * Main gps task. It does not return. */ -static void gpsTask(void *parameters) +static void gpsTask(__attribute__((unused)) void *parameters) { portTickType xDelay = 100 / portTICK_RATE_MS; uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; @@ -275,7 +275,7 @@ static void gpsTask(void *parameters) /* * Estimate the acceleration due to gravity for a particular location in LLA */ -static float GravityAccel(float latitude, float longitude, float altitude) +static float GravityAccel(float latitude, __attribute__((unused)) float longitude, float altitude) { /* WGS84 gravity model. The effect of gravity over latitude is strong * enough to change the estimated accelerometer bias in those apps. */ diff --git a/flight/modules/GPS/NMEA.c b/flight/modules/GPS/NMEA.c index 17b1678ba..98cfe48cc 100644 --- a/flight/modules/GPS/NMEA.c +++ b/flight/modules/GPS/NMEA.c @@ -78,7 +78,7 @@ static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, ch static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); #endif //PIOS_GPS_MINIMAL -const static struct nmea_parser nmea_parsers[] = { +static const struct nmea_parser nmea_parsers[] = { { .prefix = "GPGGA", .handler = nmeaProcessGPGGA, @@ -189,7 +189,7 @@ int parse_nmea_stream (uint8_t c, char *gps_rx_buffer, GPSPositionData *GpsData, return PARSER_INCOMPLETE; } -const static struct nmea_parser *NMEA_find_parser_by_prefix(const char *prefix) +static const struct nmea_parser *NMEA_find_parser_by_prefix(const char *prefix) { if (!prefix) { return (NULL); @@ -601,7 +601,7 @@ static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, ch * \param[in] A pointer to a GPSPosition UAVObject to be updated (unused). * \param[in] An NMEA sentence with a valid checksum */ -static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) +static bool nmeaProcessGPZDA(__attribute__((unused)) GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) { if (nbParam != 7) return false; @@ -640,7 +640,7 @@ static uint8_t gsv_processed_mask; static uint16_t gsv_incomplete_error; static uint16_t gsv_duplicate_error; -static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) +static bool nmeaProcessGPGSV(__attribute__((unused)) GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) { if (nbParam < 4) return false; diff --git a/flight/modules/MK/MKSerial/MKSerial.c b/flight/modules/MK/MKSerial/MKSerial.c index 3c8972711..ed1cb7006 100644 --- a/flight/modules/MK/MKSerial/MKSerial.c +++ b/flight/modules/MK/MKSerial/MKSerial.c @@ -501,7 +501,7 @@ static void DoConnectedToNC(void) } } -static void MkSerialTask(void *parameters) +static void MkSerialTask(__attribute__((unused)) void *parameters) { MkMsg_t msg; uint32_t version; diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index b49039bf7..7e248ae0c 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -164,7 +164,7 @@ MODULE_INITCALL( ManualControlInitialize, ManualControlStart) /** * Module task */ -static void manualControlTask(void *parameters) +static void manualControlTask(__attribute__((unused)) void *parameters) { ManualControlSettingsData settings; ManualControlCommandData cmd; @@ -250,7 +250,7 @@ static void manualControlTask(void *parameters) // If a channel has timed out this is not valid data and we shouldn't update anything // until we decide to go to failsafe - if (cmd.Channel[n] == PIOS_RCVR_TIMEOUT) + if (cmd.Channel[n] == (uint16_t)PIOS_RCVR_TIMEOUT) valid_input_detected = false; else scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); @@ -700,7 +700,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon * @brief Update the position desired to current location when * enabled and allow the waypoint to be moved by transmitter */ -static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool home) +static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd, bool changed,bool home) { /* static portTickType lastSysTime; @@ -755,7 +755,7 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool } } -static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +static void updateLandDesired(__attribute__((unused)) ManualControlCommandData * cmd, bool changed) { /* static portTickType lastSysTime; @@ -838,17 +838,21 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) // TODO: These functions should never be accessible on CC. Any configuration that // could allow them to be called sholud already throw an error to prevent this happening // in flight -static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home) +static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd, + __attribute__((unused)) bool changed, + __attribute__((unused)) bool home) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } -static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +static void updateLandDesired(__attribute__((unused)) ManualControlCommandData * cmd, + __attribute__((unused)) bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } -static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) +static void altitudeHoldDesired(__attribute__((unused)) ManualControlCommandData * cmd, + __attribute__((unused)) bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } @@ -1134,7 +1138,7 @@ static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel /** * Called whenever a critical configuration component changes */ -static void configurationUpdatedCb(UAVObjEvent * ev) +static void configurationUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { configuration_check(); } diff --git a/flight/modules/OPLink/oplinkmod.c b/flight/modules/OPLink/oplinkmod.c index 26be45c62..3c8cec1eb 100644 --- a/flight/modules/OPLink/oplinkmod.c +++ b/flight/modules/OPLink/oplinkmod.c @@ -120,7 +120,7 @@ MODULE_INITCALL(OPLinkModInitialize, 0) /** * System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS */ -static void systemTask(void *parameters) +static void systemTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; uint16_t prev_tx_count = 0; @@ -224,7 +224,8 @@ void vApplicationIdleHook(void) * Called by the RTOS when a stack overflow is detected. */ #define DEBUG_STACK_OVERFLOW 0 -void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName) +void vApplicationStackOverflowHook(__attribute__((unused)) xTaskHandle * pxTask, + __attribute__((unused)) signed portCHAR * pcTaskName) { stackOverflow = true; #if DEBUG_STACK_OVERFLOW diff --git a/flight/modules/Osd/OsdEtStd/OsdEtStd.c b/flight/modules/Osd/OsdEtStd/OsdEtStd.c index a1e4a5d69..2c806ad64 100644 --- a/flight/modules/Osd/OsdEtStd/OsdEtStd.c +++ b/flight/modules/Osd/OsdEtStd/OsdEtStd.c @@ -206,17 +206,17 @@ static void SetNbSats(uint8_t nb) msg[OSDMSG_NB_SATS] = nb; } -static void FlightBatteryStateUpdatedCb(UAVObjEvent * ev) +static void FlightBatteryStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { newBattData = TRUE; } -static void GPSPositionUpdatedCb(UAVObjEvent * ev) +static void GPSPositionUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { newPosData = TRUE; } -static void BaroAltitudeUpdatedCb(UAVObjEvent * ev) +static void BaroAltitudeUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { newBaroData = TRUE; } diff --git a/flight/modules/Osd/WavPlayer/wavplayer.c b/flight/modules/Osd/WavPlayer/wavplayer.c index a5d9d0374..2bf8949ea 100644 --- a/flight/modules/Osd/WavPlayer/wavplayer.c +++ b/flight/modules/Osd/WavPlayer/wavplayer.c @@ -76,7 +76,7 @@ MODULE_INITCALL( WavPlayerInitialize, WavPlayerStart) * Main WavPlayer task. It does not return. */ -static void WavPlayerTask(void *parameters) +static void WavPlayerTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; // Loop forever diff --git a/flight/modules/Osd/osdgen/inc/osdgen.h b/flight/modules/Osd/osdgen/inc/osdgen.h index 92f8d6cd3..ac5621f51 100644 --- a/flight/modules/Osd/osdgen/inc/osdgen.h +++ b/flight/modules/Osd/osdgen/inc/osdgen.h @@ -129,14 +129,14 @@ struct FontDimensions #define APPLY_VDEADBAND(y) ((y)+GRAPHICS_VDEADBAND) #define APPLY_HDEADBAND(x) ((x)+GRAPHICS_HDEADBAND) -// Check if coordinates are valid. If not, return. -#define CHECK_COORDS(x, y) if(x < 0 || x >= GRAPHICS_WIDTH_REAL || y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; -#define CHECK_COORD_X(x) if(x < 0 || x >= GRAPHICS_WIDTH_REAL) return; -#define CHECK_COORD_Y(y) if(y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; +// Check if coordinates are valid. If not, return. Assumes unsigned coordinate +#define CHECK_COORDS(x, y) if(x >= GRAPHICS_WIDTH_REAL || y >= GRAPHICS_HEIGHT_REAL) return; +#define CHECK_COORD_X(x) if(x >= GRAPHICS_WIDTH_REAL) return; +#define CHECK_COORD_Y(y) if(y >= GRAPHICS_HEIGHT_REAL) return; -// Clip coordinates out of range. -#define CLIP_COORD_X(x) { x = MAX(0, MIN(x, GRAPHICS_WIDTH_REAL)); } -#define CLIP_COORD_Y(y) { y = MAX(0, MIN(y, GRAPHICS_HEIGHT_REAL)); } +// Clip coordinates out of range - assumes unsigned coordinate +#define CLIP_COORD_X(x) { x = MIN(x, GRAPHICS_WIDTH_REAL); } +#define CLIP_COORD_Y(y) { y = MIN(y, GRAPHICS_HEIGHT_REAL); } #define CLIP_COORDS(x, y) { CLIP_COORD_X(x); CLIP_COORD_Y(y); } // Macro to swap two variables using XOR swap. diff --git a/flight/modules/Osd/osdgen/osdgen.c b/flight/modules/Osd/osdgen/osdgen.c index e2d20341e..575cb38e8 100644 --- a/flight/modules/Osd/osdgen/osdgen.c +++ b/flight/modules/Osd/osdgen/osdgen.c @@ -205,7 +205,7 @@ void swap(uint16_t* a, uint16_t* b) *b = temp; } -const static int8_t sinData[91] = +static const int8_t sinData[91] = { 0, 2, 3, 5, 7, 9, 10, 12, 14, 16, 17, 19, 21, 22, 24, 26, 28, 29, 31, 33, 34, 36, 37, 39, 41, 42, 44, 45, 47, 48, 50, 52, 53, 54, 56, 57, 59, 60, 62, 63, 64, 66, 67, 68, 69, 71, 72, 73, 74, 75, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 87, 88, 89, 90, 91, 91, 92, 93, 93, 94, 95, 95, 96, 96, 97, 97, 97, 98, 98, 98, 99, 99, 99, 99, 100, 100, 100, 100, 100, 100 }; @@ -485,10 +485,10 @@ void write_vline(uint8_t *buff, unsigned int x, unsigned int y0, unsigned int y1 } /* This is an optimised algorithm for writing vertical lines. * We begin by finding the addresses of the x,y0 and x,y1 points. */ - int addr0 = CALC_BUFF_ADDR(x, y0); - int addr1 = CALC_BUFF_ADDR(x, y1); + unsigned int addr0 = CALC_BUFF_ADDR(x, y0); + unsigned int addr1 = CALC_BUFF_ADDR(x, y1); /* Then we calculate the pixel data to be written. */ - int bitnum = CALC_BIT_IN_WORD(x); + unsigned int bitnum = CALC_BIT_IN_WORD(x); uint16_t mask = 1 << (7 - bitnum); /* Run from addr0 to addr1 placing pixels. Increment by the number * of words n each graphics line. */ @@ -558,7 +558,7 @@ void write_vline_outlined(unsigned int x, unsigned int y0, unsigned int y1, int */ void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsigned int width, unsigned int height, int mode) { - int yy, addr0_old, addr1_old; + unsigned int yy, addr0_old, addr1_old; CHECK_COORDS(x, y); CHECK_COORD_X(x + width); CHECK_COORD_Y(y + height); @@ -567,11 +567,11 @@ void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsig } // Calculate as if the rectangle was only a horizontal line. We then // step these addresses through each row until we iterate `height` times. - int addr0 = CALC_BUFF_ADDR(x, y); - int addr1 = CALC_BUFF_ADDR(x + width, y); - int addr0_bit = CALC_BIT_IN_WORD(x); - int addr1_bit = CALC_BIT_IN_WORD(x + width); - int mask, mask_l, mask_r, i; + unsigned int addr0 = CALC_BUFF_ADDR(x, y); + unsigned int addr1 = CALC_BUFF_ADDR(x + width, y); + unsigned int addr0_bit = CALC_BIT_IN_WORD(x); + unsigned int addr1_bit = CALC_BIT_IN_WORD(x + width); + unsigned int mask, mask_l, mask_r, i; // If the addresses are equal, we need to write one word vertically. if (addr0 == addr1) { mask = COMPUTE_HLINE_ISLAND_MASK(addr0_bit, addr1_bit); @@ -794,7 +794,7 @@ void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsign void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode) { // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm - int steep = abs(y1 - y0) > abs(x1 - x0); + unsigned int steep = abs(y1 - y0) > abs(x1 - x0); if (steep) { SWAP(x0, y0); SWAP(x1, y1); @@ -804,11 +804,11 @@ void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1 SWAP(y0, y1); } int deltax = x1 - x0; - int deltay = abs(y1 - y0); + unsigned int deltay = abs(y1 - y0); int error = deltax / 2; int ystep; - int y = y0; - int x; //, lasty = y, stox = 0; + unsigned int y = y0; + unsigned int x; //, lasty = y, stox = 0; if (y0 < y1) { ystep = 1; } else { @@ -857,7 +857,9 @@ void write_line_lm(unsigned int x0, unsigned int y0, unsigned int x1, unsigned i * @param mode 0 = black outline, white body, 1 = white outline, black body * @param mmode 0 = clear, 1 = set, 2 = toggle */ -void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int endcap0, int endcap1, int mode, int mmode) +void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, + __attribute__((unused)) int endcap0, __attribute__((unused)) int endcap1, + int mode, int mmode) { // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm // This could be improved for speed. @@ -879,11 +881,11 @@ void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsi SWAP(y0, y1); } int deltax = x1 - x0; - int deltay = abs(y1 - y0); + unsigned int deltay = abs(y1 - y0); int error = deltax / 2; int ystep; - int y = y0; - int x; + unsigned int y = y0; + unsigned int x; if (y0 < y1) { ystep = 1; } else { @@ -939,8 +941,8 @@ void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsi */ void write_word_misaligned(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff, int mode) { - uint16_t firstmask = word >> xoff; - uint16_t lastmask = word << (16 - xoff); + int16_t firstmask = word >> xoff; + int16_t lastmask = word << (16 - xoff); WRITE_WORD_MODE(buff, addr+1, firstmask && 0x00ff, mode); WRITE_WORD_MODE(buff, addr, (firstmask & 0xff00) >> 8, mode); if (xoff > 0) { @@ -1028,7 +1030,7 @@ void write_word_misaligned_lm(uint16_t wordl, uint16_t wordm, unsigned int addr, int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *lookup) { // First locate the font struct. - if (font > SIZEOF_ARRAY(fonts)) { + if ((unsigned int)font > SIZEOF_ARRAY(fonts)) { return 0; // font does not exist, exit. } // Load the font info; IDs are always sequential. @@ -1056,7 +1058,7 @@ int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *loo */ void write_char16(char ch, unsigned int x, unsigned int y, int font) { - int yy, addr_temp, row, row_temp, xshift; + unsigned int yy, addr_temp, row, row_temp, xshift; uint16_t and_mask, or_mask, level_bits; struct FontEntry font_info; //char lookup = 0; @@ -1132,14 +1134,14 @@ void write_char16(char ch, unsigned int x, unsigned int y, int font) */ void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) { - int yy, addr_temp, row, row_temp, xshift; + unsigned int yy, addr_temp, row, row_temp, xshift; uint16_t and_mask, or_mask, level_bits; struct FontEntry font_info; char lookup = 0; fetch_font_info(ch, font, &font_info, &lookup); // Compute starting address (for x,y) of character. - int addr = CALC_BUFF_ADDR(x, y); - int wbit = CALC_BIT_IN_WORD(x); + unsigned int addr = CALC_BUFF_ADDR(x, y); + unsigned int wbit = CALC_BIT_IN_WORD(x); // If font only supports lowercase or uppercase, make the letter // lowercase or uppercase. /*if(font_info.flags & FONT_LOWERCASE_ONLY) @@ -1298,7 +1300,8 @@ void write_string(char *str, unsigned int x, unsigned int y, unsigned int xs, un * @param ha horizontal align * @param flags flags (passed to write_char) */ -void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags) +void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, + __attribute__((unused)) int va, __attribute__((unused)) int ha, int flags) { int fcode = 0, fptr = 0, font = 0, fwidth = 0, fheight = 0, xx = x, yy = y, max_xx = 0, max_height = 0; struct FontEntry font_info; @@ -1600,7 +1603,7 @@ void printTime(uint16_t x, uint16_t y) * @param flags special flags (see hud.h.) */ void hud_draw_vertical_scale(int v, int range, int halign, int x, int y, int height, int mintick_step, int majtick_step, int mintick_len, int majtick_len, - int boundtick_len, int max_val, int flags) + int boundtick_len, __attribute__((unused)) int max_val, int flags) { char temp[15]; //, temp2[15]; struct FontEntry font_info; @@ -1743,7 +1746,7 @@ void hud_draw_vertical_scale(int v, int range, int halign, int x, int y, int hei * @param majtick_len major tick length * @param flags special flags (see hud.h.) */ -void hud_draw_linear_compass(int v, int range, int width, int x, int y, int mintick_step, int majtick_step, int mintick_len, int majtick_len, int flags) +void hud_draw_linear_compass(int v, int range, int width, int x, int y, int mintick_step, int majtick_step, int mintick_len, int majtick_len, __attribute__((unused)) int flags) { v %= 360; // wrap, just in case. struct FontEntry font_info; @@ -2400,7 +2403,7 @@ MODULE_INITCALL( osdgenInitialize, osdgenStart) * Main osd task. It does not return. */ -static void osdgenTask(void *parameters) +static void osdgenTask(__attribute__((unused)) void *parameters) { //portTickType lastSysTime; // Loop forever diff --git a/flight/modules/Osd/osdinput/osdinput.c b/flight/modules/Osd/osdinput/osdinput.c index abde6bd22..3d846946e 100644 --- a/flight/modules/Osd/osdinput/osdinput.c +++ b/flight/modules/Osd/osdinput/osdinput.c @@ -110,7 +110,7 @@ MODULE_INITCALL( osdinputInitialize, osdinputStart) * Main osdinput task. It does not return. */ -static void osdinputTask(void *parameters) +static void osdinputTask(__attribute__((unused)) void *parameters) { portTickType xDelay = 100 / portTICK_RATE_MS; portTickType lastSysTime; diff --git a/flight/modules/Osd/osdoutput/osdoutput.c b/flight/modules/Osd/osdoutput/osdoutput.c index 5285a88a8..5b329831e 100644 --- a/flight/modules/Osd/osdoutput/osdoutput.c +++ b/flight/modules/Osd/osdoutput/osdoutput.c @@ -136,7 +136,7 @@ static uint32_t osd_hk_com_id; static uint8_t osd_hk_msg_dropped; static uint8_t osd_packet; -static void send_update(UAVObjEvent * ev) +static void send_update(__attribute__((unused)) UAVObjEvent * ev) { static enum osd_hk_sync sync = OSD_HK_SYNC_A; diff --git a/flight/modules/OveroSync/overosync.c b/flight/modules/OveroSync/overosync.c index 639082fce..9d1bf850d 100644 --- a/flight/modules/OveroSync/overosync.c +++ b/flight/modules/OveroSync/overosync.c @@ -159,7 +159,7 @@ static void registerObject(UAVObjHandle obj) * when done packing the buffer we should call PIOS_SPI_TransferBlock, change the active buffer * and then take the semaphrore */ -static void overoSyncTask(void *parameters) +static void overoSyncTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; diff --git a/flight/modules/OveroSync/simulated/overosync.c b/flight/modules/OveroSync/simulated/overosync.c index a8bf6c769..8b8808895 100644 --- a/flight/modules/OveroSync/simulated/overosync.c +++ b/flight/modules/OveroSync/simulated/overosync.c @@ -158,7 +158,7 @@ static void registerObject(UAVObjHandle obj) * when done packing the buffer we should call PIOS_SPI_TransferBlock, change the active buffer * and then take the semaphrore */ -static void overoSyncTask(void *parameters) +static void overoSyncTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index 32f99552a..34b36220e 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -115,7 +115,7 @@ MODULE_INITCALL(PathPlannerInitialize, PathPlannerStart) /** * Module task */ -static void pathPlannerTask(void *parameters) +static void pathPlannerTask(__attribute__((unused)) void *parameters) { // when the active waypoint changes, update pathDesired WaypointConnectCallback(updatePathDesired); @@ -207,7 +207,7 @@ static void pathPlannerTask(void *parameters) } // callback function when waypoints changed in any way, update pathDesired -void updatePathDesired(UAVObjEvent * ev) { +void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) { // only ever touch pathDesired if pathplanner is enabled if (!pathplanner_active) return; diff --git a/flight/modules/RadioComBridge/RadioComBridge.c b/flight/modules/RadioComBridge/RadioComBridge.c index b4653dabc..0b1453d6d 100644 --- a/flight/modules/RadioComBridge/RadioComBridge.c +++ b/flight/modules/RadioComBridge/RadioComBridge.c @@ -256,7 +256,7 @@ MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart) * * @param[in] parameters The task parameters */ -static void telemetryTxTask(void *parameters) +static void telemetryTxTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; @@ -307,7 +307,7 @@ static void telemetryTxTask(void *parameters) * * @param[in] parameters The task parameters */ -static void radioTxTask(void *parameters) +static void radioTxTask(__attribute__((unused)) void *parameters) { // Task loop while (1) { @@ -335,7 +335,7 @@ static void radioTxTask(void *parameters) * * @param[in] parameters The task parameters */ -static void radioRxTask(void *parameters) +static void radioRxTask(__attribute__((unused)) void *parameters) { // Task loop while (1) { @@ -364,7 +364,7 @@ static void radioRxTask(void *parameters) * * @param[in] parameters The task parameters */ -static void telemetryRxTask(void *parameters) +static void telemetryRxTask(__attribute__((unused)) void *parameters) { // Task loop while (1) { diff --git a/flight/modules/Sensors/sensors.c b/flight/modules/Sensors/sensors.c index 8f09a93a1..13689a66c 100644 --- a/flight/modules/Sensors/sensors.c +++ b/flight/modules/Sensors/sensors.c @@ -155,7 +155,7 @@ int32_t mag_test; */ uint32_t sensor_dt_us; -static void SensorsTask(void *parameters) +static void SensorsTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; uint32_t accel_samples = 0; @@ -523,7 +523,7 @@ static void magOffsetEstimation(MagnetometerData *mag) /** * Locally cache some variables from the AtttitudeSettings object */ -static void settingsUpdatedCb(UAVObjEvent * objEv) { +static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent * objEv) { RevoCalibrationGet(&cal); mag_bias[0] = cal.mag_bias[REVOCALIBRATION_MAG_BIAS_X]; diff --git a/flight/modules/Sensors/simulated/sensors.c b/flight/modules/Sensors/simulated/sensors.c index fef692598..b3e27c986 100644 --- a/flight/modules/Sensors/simulated/sensors.c +++ b/flight/modules/Sensors/simulated/sensors.c @@ -144,7 +144,7 @@ MODULE_INITCALL(SensorsInitialize, SensorsStart) * Simulated sensor task. Run a model of the airframe and produce sensor values */ int sensors_count; -static void SensorsTask(void *parameters) +static void SensorsTask(__attribute__((unused)) void *parameters) { portTickType lastSysTime; diff --git a/flight/modules/Stabilization/stabilization.c b/flight/modules/Stabilization/stabilization.c index 73b928b8e..412aaea44 100644 --- a/flight/modules/Stabilization/stabilization.c +++ b/flight/modules/Stabilization/stabilization.c @@ -139,7 +139,7 @@ MODULE_INITCALL(StabilizationInitialize, StabilizationStart) /** * Module task */ -static void stabilizationTask(void* parameters) +static void stabilizationTask(__attribute__((unused)) void* parameters) { UAVObjEvent ev; @@ -432,7 +432,7 @@ static float bound(float val, float range) return val; } -static void SettingsUpdatedCb(UAVObjEvent * ev) +static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent * ev) { StabilizationSettingsGet(&settings); diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index bb8a82e4d..e561b46eb 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -155,7 +155,7 @@ MODULE_INITCALL(SystemModInitialize, 0) /** * System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS */ -static void systemTask(void *parameters) +static void systemTask(__attribute__((unused))void *parameters) { /* start the delayed callback scheduler */ CallbackSchedulerStart(); @@ -334,7 +334,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) /** * Called whenever hardware settings changed */ -static void hwSettingsUpdatedCb(UAVObjEvent * ev) +static void hwSettingsUpdatedCb(__attribute__((unused))UAVObjEvent * ev) { HwSettingsData currentHwSettings; HwSettingsGet(¤tHwSettings); @@ -552,7 +552,8 @@ void vApplicationIdleHook(void) * Called by the RTOS when a stack overflow is detected. */ #define DEBUG_STACK_OVERFLOW 0 -void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName) +void vApplicationStackOverflowHook(__attribute__((unused))xTaskHandle * pxTask, + __attribute__((unused))signed portCHAR * pcTaskName) { stackOverflow = true; #if DEBUG_STACK_OVERFLOW diff --git a/flight/modules/Telemetry/telemetry.c b/flight/modules/Telemetry/telemetry.c index 64d093d32..f57ad32d7 100644 --- a/flight/modules/Telemetry/telemetry.c +++ b/flight/modules/Telemetry/telemetry.c @@ -304,7 +304,7 @@ static void processObjEvent(UAVObjEvent * ev) /** * Telemetry transmit task, regular priority */ -static void telemetryTxTask(void *parameters) +static void telemetryTxTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; @@ -322,7 +322,7 @@ static void telemetryTxTask(void *parameters) * Telemetry transmit task, high priority */ #if defined(PIOS_TELEM_PRIORITY_QUEUE) -static void telemetryTxPriTask(void *parameters) +static void telemetryTxPriTask(__attribute__((unused)) void *parameters) { UAVObjEvent ev; @@ -340,7 +340,7 @@ static void telemetryTxPriTask(void *parameters) /** * Telemetry transmit task. Processes queue events and periodic updates. */ -static void telemetryRxTask(void *parameters) +static void telemetryRxTask(__attribute__((unused)) void *parameters) { // Task loop diff --git a/flight/modules/VtolPathFollower/vtolpathfollower.c b/flight/modules/VtolPathFollower/vtolpathfollower.c index a96a91a03..61ccf19f1 100644 --- a/flight/modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/modules/VtolPathFollower/vtolpathfollower.c @@ -159,7 +159,7 @@ static float throttleOffset = 0; /** * Module thread, should not return. */ -static void vtolPathFollowerTask(void *parameters) +static void vtolPathFollowerTask(__attribute__((unused)) void *parameters) { SystemSettingsData systemSettings; FlightStatusData flightStatus; @@ -732,7 +732,7 @@ static float bound(float val, float min, float max) return val; } -static void SettingsUpdatedCb(UAVObjEvent * ev) +static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { VtolPathFollowerSettingsGet(&vtolpathfollowerSettings); } diff --git a/flight/pios/common/libraries/dosfs/dosfs.c b/flight/pios/common/libraries/dosfs/dosfs.c index 4c35f5e77..7fc5f164f 100644 --- a/flight/pios/common/libraries/dosfs/dosfs.c +++ b/flight/pios/common/libraries/dosfs/dosfs.c @@ -1194,7 +1194,7 @@ uint32_t DFS_WriteFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, ui // this point, all passes through the read loop will be aligned on a // sector boundary, which allows us to go through the optimal path // 2A below. - if (remain >= SECTOR_SIZE - tempsize) { + if (remain >= (uint32_t)SECTOR_SIZE - tempsize) { memcpy(scratch + tempsize, buffer, SECTOR_SIZE - tempsize); if (!result) result = DFS_WriteSector(fileinfo->volinfo->unit, scratch, sector, 1); @@ -1330,7 +1330,7 @@ uint32_t DFS_WriteFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, ui No original function of DosFS driver It has no effect if writing to SD Card, it's only used by the DosFS wrapper in emulation */ -uint32_t DFS_Close(PFILEINFO fileinfo) +uint32_t DFS_Close(__attribute__((unused)) PFILEINFO fileinfo) { return DFS_OK; } diff --git a/flight/pios/common/libraries/msheap/msheap.c b/flight/pios/common/libraries/msheap/msheap.c index 8c86eb45f..2c8c082ba 100644 --- a/flight/pios/common/libraries/msheap/msheap.c +++ b/flight/pios/common/libraries/msheap/msheap.c @@ -423,7 +423,7 @@ msheap_extend(uint32_t size) * @param reason The reason we are panicking. */ void -msheap_panic(const char *reason) +msheap_panic(__attribute__((unused)) const char *reason) { for (;;) ; diff --git a/flight/pios/common/libraries/msheap/pios_msheap.c b/flight/pios/common/libraries/msheap/pios_msheap.c index 7fca3a8b5..e8426f7eb 100644 --- a/flight/pios/common/libraries/msheap/pios_msheap.c +++ b/flight/pios/common/libraries/msheap/pios_msheap.c @@ -134,7 +134,7 @@ free(void *p) #endif /* PIOS_INCLUDE_FREERTOS */ void -msheap_panic(const char *reason) +msheap_panic(__attribute__((unused)) const char *reason) { //PIOS_DEBUG_Panic(reason); } diff --git a/flight/pios/common/pios_adxl345.c b/flight/pios/common/pios_adxl345.c index 3f3ba88f8..f8e23e8d3 100644 --- a/flight/pios/common/pios_adxl345.c +++ b/flight/pios/common/pios_adxl345.c @@ -187,7 +187,7 @@ static int32_t PIOS_ADXL345_FifoDepth(uint8_t depth) /** * @brief Enable measuring. This also disables the activity sensors (tap or free fall) */ -static int32_t PIOS_ADXL345_SetMeasure(uint8_t enable) +static int32_t PIOS_ADXL345_SetMeasure(__attribute__((unused)) uint8_t enable) { if(PIOS_ADXL345_Validate(dev) != 0) return -1; diff --git a/flight/pios/common/pios_bma180.c b/flight/pios/common/pios_bma180.c index a5f64a121..35fd09d2f 100644 --- a/flight/pios/common/pios_bma180.c +++ b/flight/pios/common/pios_bma180.c @@ -438,7 +438,7 @@ bool PIOS_BMA180_IRQHandler(void) { bma180_irqs++; - const static uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; + static const uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; uint8_t pios_bma180_dmabuf[8]; // If we can't get the bus then just move on for efficiency diff --git a/flight/pios/common/pios_bmp085.c b/flight/pios/common/pios_bmp085.c index 0b1201caf..83a77e95e 100644 --- a/flight/pios/common/pios_bmp085.c +++ b/flight/pios/common/pios_bmp085.c @@ -311,8 +311,8 @@ bool PIOS_BMP085_Write(uint8_t address, uint8_t buffer) int32_t PIOS_BMP085_Test() { // TODO: Is there a better way to test this than just checking that pressure/temperature has changed? - int32_t passed = 1; - int32_t cur_value = 0; + uint32_t passed = 1; + uint32_t cur_value = 0; cur_value = Temperature; PIOS_BMP085_StartADC(TemperatureConv); diff --git a/flight/pios/common/pios_com_msg.c b/flight/pios/common/pios_com_msg.c index afc68c1ec..91e285a3d 100644 --- a/flight/pios/common/pios_com_msg.c +++ b/flight/pios/common/pios_com_msg.c @@ -76,7 +76,7 @@ int32_t PIOS_COM_MSG_Init(uint32_t * com_id, const struct pios_com_driver * driv return(0); } -static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) +static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, __attribute__((unused)) bool * need_yield) { struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context; @@ -103,7 +103,7 @@ static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint return (bytes_from_fifo); } -static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) +static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, __attribute__((unused)) bool * need_yield) { struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context; diff --git a/flight/pios/common/pios_flash_jedec.c b/flight/pios/common/pios_flash_jedec.c index 935861484..a05431e19 100644 --- a/flight/pios/common/pios_flash_jedec.c +++ b/flight/pios/common/pios_flash_jedec.c @@ -303,12 +303,12 @@ static int32_t PIOS_Flash_Jedec_EndTransaction(uintptr_t flash_id) #else /* FLASH_USE_FREERTOS_LOCKS */ -static int32_t PIOS_Flash_Jedec_StartTransaction(uintptr_t flash_id) +static int32_t PIOS_Flash_Jedec_StartTransaction(__attribute__((unused)) uintptr_t flash_id) { return 0; } -static int32_t PIOS_Flash_Jedec_EndTransaction(uintptr_t flash_id) +static int32_t PIOS_Flash_Jedec_EndTransaction(__attribute__((unused)) uintptr_t flash_id) { return 0; } diff --git a/flight/pios/common/pios_flashfs_logfs.c b/flight/pios/common/pios_flashfs_logfs.c index 6f7b59fae..bff3279a8 100644 --- a/flight/pios/common/pios_flashfs_logfs.c +++ b/flight/pios/common/pios_flashfs_logfs.c @@ -818,7 +818,7 @@ static int8_t logfs_append_to_log (uint32_t obj_id, uint16_t obj_inst_id, uint8_ * @retval -5 if filesystem is full even after garbage collection should have freed space * @retval -6 if writing the new object to the filesystem failed */ -int32_t PIOS_FLASHFS_ObjSave(uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id, uint8_t * obj_data, uint16_t obj_size) +int32_t PIOS_FLASHFS_ObjSave(__attribute__((unused)) uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id, uint8_t * obj_data, uint16_t obj_size) { int8_t rc; @@ -896,7 +896,7 @@ out_exit: * @retval -3 if object size in filesystem does not exactly match buffer size * @retval -4 if reading the object data from flash fails */ -int32_t PIOS_FLASHFS_ObjLoad(uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id, uint8_t * obj_data, uint16_t obj_size) +int32_t PIOS_FLASHFS_ObjLoad(__attribute__((unused)) uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id, uint8_t * obj_data, uint16_t obj_size) { int8_t rc; @@ -955,7 +955,7 @@ out_exit: * @retval -1 if failed to start transaction * @retval -2 if failed to delete the object from the filesystem */ -int32_t PIOS_FLASHFS_ObjDelete(uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id) +int32_t PIOS_FLASHFS_ObjDelete(__attribute__((unused)) uint32_t fs_id, uint32_t obj_id, uint16_t obj_inst_id) { int8_t rc; @@ -988,7 +988,7 @@ out_exit: * @retval -3 if failed to activate arena 0 * @retval -4 if failed to mount arena 0 */ -int32_t PIOS_FLASHFS_Format(uint32_t fs_id) +int32_t PIOS_FLASHFS_Format(__attribute__((unused)) uint32_t fs_id) { int32_t rc; diff --git a/flight/pios/common/pios_gcsrcvr.c b/flight/pios/common/pios_gcsrcvr.c index 89998a5bc..e7c281d9f 100644 --- a/flight/pios/common/pios_gcsrcvr.c +++ b/flight/pios/common/pios_gcsrcvr.c @@ -113,7 +113,7 @@ static void gcsreceiver_updated(UAVObjEvent * ev) } } -extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id) +extern int32_t PIOS_GCSRCVR_Init(__attribute__((unused)) uint32_t *gcsrcvr_id) { struct pios_gcsrcvr_dev *gcsrcvr_dev; @@ -145,7 +145,7 @@ extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id) * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver * \output >=0 channel value */ -static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel) +static int32_t PIOS_GCSRCVR_Get(__attribute__((unused)) uint32_t rcvr_id, uint8_t channel) { if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) { /* channel is out of range */ diff --git a/flight/pios/common/pios_mpu6000.c b/flight/pios/common/pios_mpu6000.c index 37a01f5e4..2b2d06b0b 100644 --- a/flight/pios/common/pios_mpu6000.c +++ b/flight/pios/common/pios_mpu6000.c @@ -454,7 +454,7 @@ bool PIOS_MPU6000_IRQHandler(void) return false; mpu6000_count = PIOS_MPU6000_FifoDepth(true); - if (mpu6000_count < sizeof(struct pios_mpu6000_data)) + if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) return false; if (PIOS_MPU6000_ClaimBus(true) != 0) @@ -474,7 +474,7 @@ bool PIOS_MPU6000_IRQHandler(void) static struct pios_mpu6000_data data; // In the case where extras samples backed up grabbed an extra - if (mpu6000_count >= (sizeof(data) * 2)) { + if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) { mpu6000_fifo_backup++; if (PIOS_MPU6000_ClaimBus(true) != 0) return false; diff --git a/flight/pios/common/pios_rfm22b.c b/flight/pios/common/pios_rfm22b.c index 1cf8b074a..481370b7a 100644 --- a/flight/pios/common/pios_rfm22b.c +++ b/flight/pios/common/pios_rfm22b.c @@ -212,7 +212,7 @@ static uint8_t rfm22_read_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t ad /* The state transition table */ -const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_STATES] = { +static const struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_STATES] = { // Initialization thread [RFM22B_STATE_UNINITIALIZED] = { @@ -2057,7 +2057,7 @@ static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev) * * @param[in] rfm22b_dev The device structure */ -static void rfm22_sendPPM(struct pios_rfm22b_dev *rfm22b_dev) +static void rfm22_sendPPM(__attribute__((unused)) struct pios_rfm22b_dev *rfm22b_dev) { #ifdef PIOS_PPM_RECEIVER // Only send PPM if we're connected @@ -2568,7 +2568,7 @@ static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) * @parem [in] rfm22b_dev The device structure * @return enum pios_rfm22b_event The next event to inject */ -static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev) +static enum pios_rfm22b_event rfm22_fatal_error(__attribute__((unused)) struct pios_rfm22b_dev *rfm22b_dev) { // RF module error .. flash the LED's rfm22_clearLEDs(); diff --git a/flight/pios/common/pios_rfm22b_com.c b/flight/pios/common/pios_rfm22b_com.c index 11081b11d..e0800eb27 100644 --- a/flight/pios/common/pios_rfm22b_com.c +++ b/flight/pios/common/pios_rfm22b_com.c @@ -91,7 +91,8 @@ static void PIOS_RFM22B_COM_ChangeBaud(uint32_t rfm22b_id, uint32_t baud) * @param[in] rfm22b_dev The device ID. * @param[in] rx_bytes_available The number of bytes available to receive */ -static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) +static void PIOS_RFM22B_COM_RxStart(__attribute__((unused)) uint32_t rfm22b_id, + __attribute__((unused)) uint16_t rx_bytes_avail) { } @@ -101,7 +102,7 @@ static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) * @param[in] rfm22b_dev The device ID. * @param[in] tx_bytes_available The number of bytes available to transmit */ -static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) +static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; if (!PIOS_RFM22B_Validate(rfm22b_dev)) { diff --git a/flight/pios/inc/pios_rfm22b_priv.h b/flight/pios/inc/pios_rfm22b_priv.h index 584c354d5..bb2234683 100644 --- a/flight/pios/inc/pios_rfm22b_priv.h +++ b/flight/pios/inc/pios_rfm22b_priv.h @@ -749,7 +749,7 @@ struct pios_rfm22b_dev { #ifdef PIOS_INCLUDE_RFM22B_RCVR // The PPM channel values uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS]; - uint8_t ppm_supv_timer; + uint32_t ppm_supv_timer; bool ppm_fresh; #endif }; diff --git a/flight/pios/stm32f10x/pios_debug.c b/flight/pios/stm32f10x/pios_debug.c index e7e7e148e..f0f6dbcaf 100644 --- a/flight/pios/stm32f10x/pios_debug.c +++ b/flight/pios/stm32f10x/pios_debug.c @@ -41,7 +41,8 @@ static uint8_t debug_num_channels; /** * Initialise Debug-features */ -void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels) +void PIOS_DEBUG_Init(__attribute__((unused)) const struct pios_tim_channel * channels, + __attribute__((unused)) uint8_t num_channels) { #ifdef PIOS_ENABLE_DEBUG_PINS PIOS_Assert(channels); @@ -75,7 +76,7 @@ void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_chann * Set debug-pin high * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinHigh(uint8_t pin) +void PIOS_DEBUG_PinHigh(__attribute__((unused)) uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels || pin >= debug_num_channels) { @@ -93,7 +94,7 @@ void PIOS_DEBUG_PinHigh(uint8_t pin) * Set debug-pin low * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinLow(uint8_t pin) +void PIOS_DEBUG_PinLow(__attribute__((unused)) uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels || pin >= debug_num_channels) { @@ -108,7 +109,7 @@ void PIOS_DEBUG_PinLow(uint8_t pin) } -void PIOS_DEBUG_PinValue8Bit(uint8_t value) +void PIOS_DEBUG_PinValue8Bit(__attribute__((unused)) uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels) { @@ -131,7 +132,7 @@ void PIOS_DEBUG_PinValue8Bit(uint8_t value) #endif // PIOS_ENABLE_DEBUG_PINS } -void PIOS_DEBUG_PinValue4BitL(uint8_t value) +void PIOS_DEBUG_PinValue4BitL(__attribute__((unused)) uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels) { @@ -151,7 +152,7 @@ void PIOS_DEBUG_PinValue4BitL(uint8_t value) /** * Report a serious error and halt */ -void PIOS_DEBUG_Panic(const char *msg) +void PIOS_DEBUG_Panic(__attribute__((unused)) const char *msg) { #ifdef PIOS_INCLUDE_DEBUG_CONSOLE register int *lr asm("lr"); // Link-register holds the PC of the caller diff --git a/flight/pios/stm32f10x/pios_eeprom.c b/flight/pios/stm32f10x/pios_eeprom.c index a3e11c544..8771a522a 100644 --- a/flight/pios/stm32f10x/pios_eeprom.c +++ b/flight/pios/stm32f10x/pios_eeprom.c @@ -88,7 +88,7 @@ int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len) // write 4 bytes at a time into program flash area (emulated EEPROM area) uint8_t *p1 = data; uint32_t *p3 = (uint32_t *)config.base_address; - for (int32_t i = 0; i < size; p3++) + for (uint32_t i = 0; i < size; p3++) { uint32_t value = 0; diff --git a/flight/pios/stm32f10x/pios_led.c b/flight/pios/stm32f10x/pios_led.c index 79dad8a8c..c9d26da8a 100644 --- a/flight/pios/stm32f10x/pios_led.c +++ b/flight/pios/stm32f10x/pios_led.c @@ -34,7 +34,7 @@ #include -const static struct pios_led_cfg * led_cfg; +static const struct pios_led_cfg * led_cfg; /** * Initialises all the LED's diff --git a/flight/pios/stm32f10x/pios_ppm.c b/flight/pios/stm32f10x/pios_ppm.c index f9d825162..2088e426e 100644 --- a/flight/pios/stm32f10x/pios_ppm.c +++ b/flight/pios/stm32f10x/pios_ppm.c @@ -114,7 +114,7 @@ static struct pios_ppm_dev * PIOS_PPM_alloc(void) static void PIOS_PPM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); static void PIOS_PPM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); -const static struct pios_tim_callbacks tim_callbacks = { +static const struct pios_tim_callbacks tim_callbacks = { .overflow = PIOS_PPM_tim_overflow_cb, .edge = PIOS_PPM_tim_edge_cb, }; @@ -224,7 +224,10 @@ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) return ppm_dev->CaptureValue[channel]; } -static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +static void PIOS_PPM_tim_overflow_cb (__attribute__((unused)) uint32_t tim_id, + uint32_t context, + __attribute__((unused)) uint8_t channel, + uint16_t count) { struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; @@ -239,7 +242,10 @@ static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t } -static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +static void PIOS_PPM_tim_edge_cb (__attribute__((unused)) uint32_t tim_id, + uint32_t context, + uint8_t chan_idx, + uint16_t count) { /* Recover our device context */ struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; @@ -287,7 +293,7 @@ static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t cha /* Check if the last frame was well formed */ if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) { /* The last frame was well formed */ - for (uint32_t i = 0; i < ppm_dev->NumChannels; i++) { + for (int32_t i = 0; i < ppm_dev->NumChannels; i++) { ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i]; } for (uint32_t i = ppm_dev->NumChannels; diff --git a/flight/pios/stm32f10x/pios_ppm_out.c b/flight/pios/stm32f10x/pios_ppm_out.c index 72dbf3056..1352d38d2 100644 --- a/flight/pios/stm32f10x/pios_ppm_out.c +++ b/flight/pios/stm32f10x/pios_ppm_out.c @@ -98,7 +98,7 @@ static struct pios_ppm_out_dev * PIOS_PPM_alloc(void) #endif static void PIOS_PPM_OUT_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count); -const static struct pios_tim_callbacks tim_out_callbacks = { +static const struct pios_tim_callbacks tim_out_callbacks = { .overflow = NULL, .edge = PIOS_PPM_OUT_tim_edge_cb, }; @@ -203,7 +203,10 @@ void PIOS_PPM_OUT_Set(uint32_t ppm_out_id, uint8_t servo, uint16_t position) ppm_dev->ChannelValue[servo] = position; } -static void PIOS_PPM_OUT_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +static void PIOS_PPM_OUT_tim_edge_cb (__attribute__((unused)) uint32_t tim_id, + uint32_t context, + __attribute__((unused)) uint8_t chan_idx, + __attribute__((unused)) uint16_t count) { struct pios_ppm_out_dev *ppm_dev = (struct pios_ppm_out_dev *)context; if (!PIOS_PPM_Out_validate(ppm_dev)) diff --git a/flight/pios/stm32f10x/pios_pwm.c b/flight/pios/stm32f10x/pios_pwm.c index 2c6707664..d93d37ebc 100644 --- a/flight/pios/stm32f10x/pios_pwm.c +++ b/flight/pios/stm32f10x/pios_pwm.c @@ -44,7 +44,7 @@ const struct pios_rcvr_driver pios_pwm_rcvr_driver = { /* Local Variables */ /* 100 ms timeout without updates on channels */ -const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; +static const uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; enum pios_pwm_dev_magic { PIOS_PWM_DEV_MAGIC = 0xab30293c, @@ -98,7 +98,7 @@ static struct pios_pwm_dev * PIOS_PWM_alloc(void) static void PIOS_PWM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); static void PIOS_PWM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); -const static struct pios_tim_callbacks tim_callbacks = { +static const struct pios_tim_callbacks tim_callbacks = { .overflow = PIOS_PWM_tim_overflow_cb, .edge = PIOS_PWM_tim_edge_cb, }; @@ -193,7 +193,7 @@ static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) return pwm_dev->CaptureValue[channel]; } -static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +static void PIOS_PWM_tim_overflow_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; @@ -219,7 +219,7 @@ static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t return; } -static void PIOS_PWM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +static void PIOS_PWM_tim_edge_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) { /* Recover our device context */ struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; diff --git a/flight/pios/stm32f10x/pios_spi.c b/flight/pios/stm32f10x/pios_spi.c index fcb46ee9a..4e001b775 100644 --- a/flight/pios/stm32f10x/pios_spi.c +++ b/flight/pios/stm32f10x/pios_spi.c @@ -39,7 +39,7 @@ #include -static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) +static bool PIOS_SPI_validate(__attribute__((unused)) struct pios_spi_dev * com_dev) { /* Should check device magic here */ return(true); diff --git a/flight/pios/stm32f10x/pios_usart.c b/flight/pios/stm32f10x/pios_usart.c index 3054c09e3..3691c0dfd 100644 --- a/flight/pios/stm32f10x/pios_usart.c +++ b/flight/pios/stm32f10x/pios_usart.c @@ -196,7 +196,7 @@ out_fail: return(-1); } -static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail) +static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail) { struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; @@ -205,7 +205,7 @@ static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail) USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE); } -static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail) +static void PIOS_USART_TxStart(uint32_t usart_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; diff --git a/flight/pios/stm32f10x/pios_usb.c b/flight/pios/stm32f10x/pios_usb.c index 6a5d676e5..13fb8c3c5 100644 --- a/flight/pios/stm32f10x/pios_usb.c +++ b/flight/pios/stm32f10x/pios_usb.c @@ -208,7 +208,7 @@ int32_t PIOS_USB_Reenumerate() return 0; } -bool PIOS_USB_CableConnected(uint8_t id) +bool PIOS_USB_CableConnected(__attribute__((unused)) uint8_t id) { struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_com_id; diff --git a/flight/pios/stm32f10x/pios_usb_cdc.c b/flight/pios/stm32f10x/pios_usb_cdc.c index 0da873966..2d470dee9 100644 --- a/flight/pios/stm32f10x/pios_usb_cdc.c +++ b/flight/pios/stm32f10x/pios_usb_cdc.c @@ -229,7 +229,7 @@ static void PIOS_USB_CDC_SendData(struct pios_usb_cdc_dev * usb_cdc_dev) #endif /* PIOS_INCLUDE_FREERTOS */ } -static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail) +static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; diff --git a/flight/pios/stm32f10x/pios_usb_hid.c b/flight/pios/stm32f10x/pios_usb_hid.c index ba49ceb5a..2656c3dce 100644 --- a/flight/pios/stm32f10x/pios_usb_hid.c +++ b/flight/pios/stm32f10x/pios_usb_hid.c @@ -223,7 +223,7 @@ static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail) { PIOS_IRQ_Enable(); } -static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail) +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; diff --git a/flight/pios/stm32f10x/pios_usb_hid_pwr.c b/flight/pios/stm32f10x/pios_usb_hid_pwr.c index e55e1104e..888f2d748 100644 --- a/flight/pios/stm32f10x/pios_usb_hid_pwr.c +++ b/flight/pios/stm32f10x/pios_usb_hid_pwr.c @@ -44,7 +44,7 @@ struct { * Output : None. * Return : None *******************************************************************************/ -void USB_Cable_Config(FunctionalState NewState) +void USB_Cable_Config(__attribute__((unused)) FunctionalState NewState) { } diff --git a/flight/pios/stm32f10x/pios_usbhook.c b/flight/pios/stm32f10x/pios_usbhook.c index 0fd6e2e5b..ba01d8fee 100644 --- a/flight/pios/stm32f10x/pios_usbhook.c +++ b/flight/pios/stm32f10x/pios_usbhook.c @@ -52,7 +52,7 @@ void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size) static ONE_DESCRIPTOR Config_Descriptor; -void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size) +void PIOS_USBHOOK_RegisterConfig(__attribute__((unused)) uint8_t config_id, const uint8_t * desc, uint16_t desc_size) { Config_Descriptor.Descriptor = desc; Config_Descriptor.Descriptor_Size = desc_size; diff --git a/flight/pios/stm32f4xx/libraries/STM32_USB_Device_Library/Core/src/usbd_core.c b/flight/pios/stm32f4xx/libraries/STM32_USB_Device_Library/Core/src/usbd_core.c index 2a51d3aef..91025c4db 100644 --- a/flight/pios/stm32f4xx/libraries/STM32_USB_Device_Library/Core/src/usbd_core.c +++ b/flight/pios/stm32f4xx/libraries/STM32_USB_Device_Library/Core/src/usbd_core.c @@ -156,7 +156,7 @@ void USBD_Init(USB_OTG_CORE_HANDLE *pdev, * @param pdev: device instance * @retval status: status */ -USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev) +USBD_Status USBD_DeInit(__attribute__((unused)) USB_OTG_CORE_HANDLE *pdev) { /* Software Init */ diff --git a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h index 9df1a4172..d8be8b19f 100644 --- a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h +++ b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h @@ -53,10 +53,10 @@ typedef struct _USBD_DCD_INT uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev); - +#ifdef VBUS_SENSING_ENABLED uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); - +#endif }USBD_DCD_INT_cb_TypeDef; extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; diff --git a/flight/pios/stm32f4xx/pios_adc.c b/flight/pios/stm32f4xx/pios_adc.c index 7131e440a..1f26dee4e 100644 --- a/flight/pios/stm32f4xx/pios_adc.c +++ b/flight/pios/stm32f4xx/pios_adc.c @@ -130,7 +130,7 @@ init_pins(void) GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; - for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { + for (uint32_t i = 0; i < PIOS_ADC_NUM_PINS; ++i) { if (config[i].port == NULL) continue; GPIO_InitStructure.GPIO_Pin = config[i].pin; @@ -210,7 +210,7 @@ init_adc(void) ADC_DMACmd(pios_adc_dev->cfg->adc_dev, ENABLE); /* Configure input scan */ - for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { + for (uint32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { ADC_RegularChannelConfig(pios_adc_dev->cfg->adc_dev, config[i].channel, i+1, @@ -284,7 +284,7 @@ int32_t PIOS_ADC_Init(const struct pios_adc_cfg * cfg) * @brief Configure the ADC to run at a fixed oversampling * @param[in] oversampling the amount of oversampling to run at */ -void PIOS_ADC_Config(uint32_t oversampling) +void PIOS_ADC_Config(__attribute__((unused)) uint32_t oversampling) { /* we ignore this */ } @@ -376,7 +376,7 @@ uint8_t PIOS_ADC_GetOverSampling(void) * filter coefficients * @note Not currently supported. */ -void PIOS_ADC_SetFIRCoefficients(float * new_filter) +void PIOS_ADC_SetFIRCoefficients(__attribute__((unused)) float * new_filter) { // not implemented } @@ -393,14 +393,14 @@ void accumulate(uint16_t *buffer, uint32_t count) * Accumulate sampled values. */ while (count--) { - for (int i = 0; i < PIOS_ADC_NUM_PINS; i++) { + for (uint32_t i = 0; i < PIOS_ADC_NUM_PINS; ++i) { accumulator[i].accumulator += *sp++; accumulator[i].count++; /* * If the accumulator reaches half-full, rescale in order to * make more space. */ - if (accumulator[i].accumulator >= (1 << 31)) { + if (accumulator[i].accumulator >= (((uint32_t)1) << 31)) { accumulator[i].accumulator /= 2; accumulator[i].count /= 2; } diff --git a/flight/pios/stm32f4xx/pios_debug.c b/flight/pios/stm32f4xx/pios_debug.c index 8fe050b07..af10d3918 100644 --- a/flight/pios/stm32f4xx/pios_debug.c +++ b/flight/pios/stm32f4xx/pios_debug.c @@ -41,7 +41,7 @@ static uint8_t debug_num_channels; /** * Initialise Debug-features */ -void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels) +void PIOS_DEBUG_Init(__attribute__((unused)) const struct pios_tim_channel * channels, __attribute__((unused)) uint8_t num_channels) { #ifdef PIOS_ENABLE_DEBUG_PINS PIOS_Assert(channels); @@ -77,7 +77,7 @@ void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_chann * Set debug-pin high * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinHigh(uint8_t pin) +void PIOS_DEBUG_PinHigh(__attribute__((unused)) uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels || pin >= debug_num_channels) { @@ -95,7 +95,7 @@ void PIOS_DEBUG_PinHigh(uint8_t pin) * Set debug-pin low * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinLow(uint8_t pin) +void PIOS_DEBUG_PinLow(__attribute__((unused)) uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels || pin >= debug_num_channels) { @@ -110,7 +110,7 @@ void PIOS_DEBUG_PinLow(uint8_t pin) } -void PIOS_DEBUG_PinValue8Bit(uint8_t value) +void PIOS_DEBUG_PinValue8Bit(__attribute__((unused)) uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels) { @@ -136,7 +136,7 @@ void PIOS_DEBUG_PinValue8Bit(uint8_t value) #endif // PIOS_ENABLE_DEBUG_PINS } -void PIOS_DEBUG_PinValue4BitL(uint8_t value) +void PIOS_DEBUG_PinValue4BitL(__attribute__((unused)) uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS if (!debug_channels) { @@ -159,7 +159,7 @@ void PIOS_DEBUG_PinValue4BitL(uint8_t value) /** * Report a serious error and halt */ -void PIOS_DEBUG_Panic(const char *msg) +void PIOS_DEBUG_Panic(__attribute__((unused)) const char *msg) { #ifdef PIOS_INCLUDE_DEBUG_CONSOLE register int *lr asm("lr"); // Link-register holds the PC of the caller diff --git a/flight/pios/stm32f4xx/pios_flash_internal.c b/flight/pios/stm32f4xx/pios_flash_internal.c index fceae8038..c106573b3 100644 --- a/flight/pios/stm32f4xx/pios_flash_internal.c +++ b/flight/pios/stm32f4xx/pios_flash_internal.c @@ -166,7 +166,7 @@ static struct pios_internal_flash_dev * PIOS_Flash_Internal_alloc(void) #endif /* defined(PIOS_INCLUDE_FREERTOS) */ -int32_t PIOS_Flash_Internal_Init(uintptr_t * flash_id, const struct pios_flash_internal_cfg * cfg) +int32_t PIOS_Flash_Internal_Init(uintptr_t * flash_id, __attribute__((unused)) const struct pios_flash_internal_cfg * cfg) { struct pios_internal_flash_dev * flash_dev; diff --git a/flight/pios/stm32f4xx/pios_i2c.c b/flight/pios/stm32f4xx/pios_i2c.c index af2074307..9dec896da 100644 --- a/flight/pios/stm32f4xx/pios_i2c.c +++ b/flight/pios/stm32f4xx/pios_i2c.c @@ -132,7 +132,7 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter); static void i2c_adapter_log_fault(enum pios_i2c_error_type type); static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter); -const static struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { +static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { [I2C_STATE_FSM_FAULT] = { .entry_fn = go_fsm_fault, .next_state = { @@ -617,9 +617,6 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum * guarantee that the entry function never depends on the previous * state. This way, it cannot ever know what the previous state was. */ - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event]; /* Call the entry function (if any) for the next state. */ @@ -637,9 +634,6 @@ static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter) { PIOS_IRQ_Disable(); - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - while (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]) { i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]; diff --git a/flight/pios/stm32f4xx/pios_led.c b/flight/pios/stm32f4xx/pios_led.c index 7ff5dec42..b0d6a4f88 100644 --- a/flight/pios/stm32f4xx/pios_led.c +++ b/flight/pios/stm32f4xx/pios_led.c @@ -34,7 +34,7 @@ #include -const static struct pios_led_cfg * led_cfg; +static const struct pios_led_cfg * led_cfg; /** * Initialises all the LED's diff --git a/flight/pios/stm32f4xx/pios_overo.c b/flight/pios/stm32f4xx/pios_overo.c index 2de75591a..609436295 100644 --- a/flight/pios/stm32f4xx/pios_overo.c +++ b/flight/pios/stm32f4xx/pios_overo.c @@ -308,7 +308,7 @@ out_fail: return(-1); } -static void PIOS_OVERO_RxStart(uint32_t overo_id, uint16_t rx_bytes_avail) +static void PIOS_OVERO_RxStart(uint32_t overo_id, __attribute__((unused)) uint16_t rx_bytes_avail) { struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; @@ -318,7 +318,7 @@ static void PIOS_OVERO_RxStart(uint32_t overo_id, uint16_t rx_bytes_avail) // DMA RX enable (enable IRQ) ? } -static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) +static void PIOS_OVERO_TxStart(uint32_t overo_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; diff --git a/flight/pios/stm32f4xx/pios_ppm.c b/flight/pios/stm32f4xx/pios_ppm.c index 922e7d6e1..fad9a22e3 100644 --- a/flight/pios/stm32f4xx/pios_ppm.c +++ b/flight/pios/stm32f4xx/pios_ppm.c @@ -113,7 +113,7 @@ static struct pios_ppm_dev * PIOS_PPM_alloc(void) static void PIOS_PPM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); static void PIOS_PPM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); -const static struct pios_tim_callbacks tim_callbacks = { +static const struct pios_tim_callbacks tim_callbacks = { .overflow = PIOS_PPM_tim_overflow_cb, .edge = PIOS_PPM_tim_edge_cb, }; @@ -222,7 +222,8 @@ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) return ppm_dev->CaptureValue[channel]; } -static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +static void PIOS_PPM_tim_overflow_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, + __attribute__((unused)) uint8_t channel, uint16_t count) { struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; @@ -237,7 +238,7 @@ static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t } -static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +static void PIOS_PPM_tim_edge_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) { /* Recover our device context */ struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; @@ -285,7 +286,7 @@ static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t cha /* Check if the last frame was well formed */ if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) { /* The last frame was well formed */ - for (uint32_t i = 0; i < ppm_dev->NumChannels; i++) { + for (int32_t i = 0; i < ppm_dev->NumChannels; i++) { ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i]; } for (uint32_t i = ppm_dev->NumChannels; diff --git a/flight/pios/stm32f4xx/pios_pwm.c b/flight/pios/stm32f4xx/pios_pwm.c index 752dcbaa8..9c55cc624 100644 --- a/flight/pios/stm32f4xx/pios_pwm.c +++ b/flight/pios/stm32f4xx/pios_pwm.c @@ -43,7 +43,7 @@ const struct pios_rcvr_driver pios_pwm_rcvr_driver = { /* Local Variables */ /* 100 ms timeout without updates on channels */ -const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; +static const uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; enum pios_pwm_dev_magic { PIOS_PWM_DEV_MAGIC = 0xab30293c, @@ -97,7 +97,7 @@ static struct pios_pwm_dev * PIOS_PWM_alloc(void) static void PIOS_PWM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); static void PIOS_PWM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); -const static struct pios_tim_callbacks tim_callbacks = { +static const struct pios_tim_callbacks tim_callbacks = { .overflow = PIOS_PWM_tim_overflow_cb, .edge = PIOS_PWM_tim_edge_cb, }; @@ -192,7 +192,7 @@ static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) return pwm_dev->CaptureValue[channel]; } -static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +static void PIOS_PWM_tim_overflow_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; @@ -218,7 +218,7 @@ static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t return; } -static void PIOS_PWM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +static void PIOS_PWM_tim_edge_cb (__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) { /* Recover our device context */ struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; diff --git a/flight/pios/stm32f4xx/pios_spi.c b/flight/pios/stm32f4xx/pios_spi.c index bf82a9951..56134c165 100644 --- a/flight/pios/stm32f4xx/pios_spi.c +++ b/flight/pios/stm32f4xx/pios_spi.c @@ -44,7 +44,7 @@ #define SPI_MAX_BLOCK_PIO 128 -static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) +static bool PIOS_SPI_validate(__attribute__((unused)) struct pios_spi_dev * com_dev) { /* Should check device magic here */ return(true); diff --git a/flight/pios/stm32f4xx/pios_usart.c b/flight/pios/stm32f4xx/pios_usart.c index 8080cbb69..daa4d25bb 100644 --- a/flight/pios/stm32f4xx/pios_usart.c +++ b/flight/pios/stm32f4xx/pios_usart.c @@ -227,7 +227,7 @@ out_fail: return(-1); } -static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail) +static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail) { struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; @@ -236,7 +236,7 @@ static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail) USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE); } -static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail) +static void PIOS_USART_TxStart(uint32_t usart_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; diff --git a/flight/pios/stm32f4xx/pios_usb.c b/flight/pios/stm32f4xx/pios_usb.c index 50ae0837f..d0592a815 100644 --- a/flight/pios/stm32f4xx/pios_usb.c +++ b/flight/pios/stm32f4xx/pios_usb.c @@ -155,7 +155,7 @@ int32_t PIOS_USB_ChangeConnectionState(bool connected) * \return 0: interface not available */ uint32_t usb_found; -bool PIOS_USB_CheckAvailable(uint32_t id) +bool PIOS_USB_CheckAvailable(__attribute__((unused)) uint32_t id) { struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; @@ -175,7 +175,7 @@ bool PIOS_USB_CheckAvailable(uint32_t id) #include "usb_bsp.h" -void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) +void USB_OTG_BSP_Init(__attribute__((unused)) USB_OTG_CORE_HANDLE *pdev) { struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; @@ -210,7 +210,7 @@ void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE); } -void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev) +void USB_OTG_BSP_EnableInterrupt(__attribute__((unused)) USB_OTG_CORE_HANDLE *pdev) { struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; diff --git a/flight/pios/stm32f4xx/pios_usb_hid.c b/flight/pios/stm32f4xx/pios_usb_hid.c index 88f45978b..4ef149297 100644 --- a/flight/pios/stm32f4xx/pios_usb_hid.c +++ b/flight/pios/stm32f4xx/pios_usb_hid.c @@ -261,7 +261,7 @@ static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail) { } } -static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail) +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, __attribute__((unused)) uint16_t tx_bytes_avail) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; @@ -428,7 +428,7 @@ static bool PIOS_USB_HID_IF_Setup(uint32_t usb_hid_id, struct usb_setup_request return true; } -static void PIOS_USB_HID_IF_CtrlDataOut(uint32_t usb_hid_id, struct usb_setup_request *req) +static void PIOS_USB_HID_IF_CtrlDataOut(__attribute__((unused)) uint32_t usb_hid_id, __attribute__((unused)) struct usb_setup_request *req) { /* HID devices don't have any OUT data stages on the control endpoint */ PIOS_Assert(0); @@ -438,7 +438,7 @@ static void PIOS_USB_HID_IF_CtrlDataOut(uint32_t usb_hid_id, struct usb_setup_re * @brief Callback used to indicate a transmission from device INto host completed * Checks if any data remains, pads it into HID packet and sends. */ -static bool PIOS_USB_HID_EP_IN_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len) +static bool PIOS_USB_HID_EP_IN_Callback(uint32_t usb_hid_id, __attribute__((unused)) uint8_t epnum, __attribute__((unused)) uint16_t len) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; @@ -460,7 +460,7 @@ static bool PIOS_USB_HID_EP_IN_Callback(uint32_t usb_hid_id, uint8_t epnum, uint /** * EP1 OUT Callback Routine */ -static bool PIOS_USB_HID_EP_OUT_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len) +static bool PIOS_USB_HID_EP_OUT_Callback(uint32_t usb_hid_id, __attribute__((unused)) uint8_t epnum, uint16_t len) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; diff --git a/flight/pios/stm32f4xx/pios_usbhook.c b/flight/pios/stm32f4xx/pios_usbhook.c index fa7b8284b..df722b0c0 100644 --- a/flight/pios/stm32f4xx/pios_usbhook.c +++ b/flight/pios/stm32f4xx/pios_usbhook.c @@ -69,7 +69,7 @@ void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * static struct pios_usbhook_descriptor Config_Descriptor; -void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size) +void PIOS_USBHOOK_RegisterConfig(__attribute__((unused)) uint8_t config_id, const uint8_t * desc, uint16_t desc_size) { Config_Descriptor.descriptor = desc; Config_Descriptor.length = desc_size; @@ -205,42 +205,42 @@ void PIOS_USBHOOK_EndpointRx(uint8_t epnum, uint8_t *buf, uint16_t len) * Device level hooks into STM USB library */ -static const uint8_t * PIOS_USBHOOK_DEV_GetDeviceDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetDeviceDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = Device_Descriptor.length; return Device_Descriptor.descriptor; } -static const uint8_t * PIOS_USBHOOK_DEV_GetLangIDStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetLangIDStrDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = String_Descriptor[USB_STRING_DESC_LANG].length; return String_Descriptor[USB_STRING_DESC_LANG].descriptor; } -static const uint8_t * PIOS_USBHOOK_DEV_GetManufacturerStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetManufacturerStrDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = String_Descriptor[USB_STRING_DESC_VENDOR].length; return String_Descriptor[USB_STRING_DESC_VENDOR].descriptor; } -static const uint8_t * PIOS_USBHOOK_DEV_GetProductStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetProductStrDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = String_Descriptor[USB_STRING_DESC_PRODUCT].length; return String_Descriptor[USB_STRING_DESC_PRODUCT].descriptor; } -static const uint8_t * PIOS_USBHOOK_DEV_GetSerialStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetSerialStrDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = String_Descriptor[USB_STRING_DESC_SERIAL].length; return String_Descriptor[USB_STRING_DESC_SERIAL].descriptor; } -static const uint8_t * PIOS_USBHOOK_DEV_GetConfigurationStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetConfigurationStrDescriptor(__attribute__((unused)) uint8_t speed, __attribute__((unused)) uint16_t *length) { return NULL; } -static const uint8_t * PIOS_USBHOOK_DEV_GetInterfaceStrDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_DEV_GetInterfaceStrDescriptor(__attribute__((unused)) uint8_t speed, __attribute__((unused)) uint16_t *length) { return NULL; } @@ -266,7 +266,7 @@ static void PIOS_USBHOOK_USR_Init(void) #endif } -static void PIOS_USBHOOK_USR_DeviceReset(uint8_t speed) +static void PIOS_USBHOOK_USR_DeviceReset(__attribute__((unused)) uint8_t speed) { PIOS_USB_ChangeConnectionState(false); } @@ -306,7 +306,7 @@ static USBD_Usr_cb_TypeDef user_callbacks = { .DeviceDisconnected = PIOS_USBHOOK_USR_DeviceDisconnected, }; -static uint8_t PIOS_USBHOOK_CLASS_Init(void *pdev, uint8_t cfgidx) +static uint8_t PIOS_USBHOOK_CLASS_Init(__attribute__((unused)) void *pdev, __attribute__((unused)) uint8_t cfgidx) { /* Call all of the registered init callbacks */ for (uint8_t i = 0; i < NELEMENTS(usb_if_table); i++) { @@ -318,7 +318,7 @@ static uint8_t PIOS_USBHOOK_CLASS_Init(void *pdev, uint8_t cfgidx) return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_DeInit(void *pdev, uint8_t cfgidx) +static uint8_t PIOS_USBHOOK_CLASS_DeInit(__attribute__((unused)) void *pdev, __attribute__((unused)) uint8_t cfgidx) { /* Call all of the registered deinit callbacks */ for (uint8_t i = 0; i < NELEMENTS(usb_if_table); i++) { @@ -331,7 +331,7 @@ static uint8_t PIOS_USBHOOK_CLASS_DeInit(void *pdev, uint8_t cfgidx) } static struct usb_setup_request usb_ep0_active_req; -static uint8_t PIOS_USBHOOK_CLASS_Setup(void *pdev, USB_SETUP_REQ *req) +static uint8_t PIOS_USBHOOK_CLASS_Setup(__attribute__((unused)) void *pdev, USB_SETUP_REQ *req) { switch (req->bmRequest & (USB_REQ_TYPE_MASK | USB_REQ_RECIPIENT_MASK)) { case (USB_REQ_TYPE_STANDARD | USB_REQ_RECIPIENT_INTERFACE): @@ -365,12 +365,12 @@ static uint8_t PIOS_USBHOOK_CLASS_Setup(void *pdev, USB_SETUP_REQ *req) return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_EP0_TxSent(void *pdev) +static uint8_t PIOS_USBHOOK_CLASS_EP0_TxSent(__attribute__((unused)) void *pdev) { return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_EP0_RxReady(void *pdev) +static uint8_t PIOS_USBHOOK_CLASS_EP0_RxReady(__attribute__((unused)) void *pdev) { uint8_t ifnum = LOBYTE(usb_ep0_active_req.wIndex); @@ -418,22 +418,22 @@ static uint8_t PIOS_USBHOOK_CLASS_DataOut(void *pdev, uint8_t epnum) return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_SOF(void *pdev) +static uint8_t PIOS_USBHOOK_CLASS_SOF(__attribute__((unused)) void *pdev) { return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_IsoINIncomplete(void *pdev) +static uint8_t PIOS_USBHOOK_CLASS_IsoINIncomplete(__attribute__((unused)) void *pdev) { return USBD_OK; } -static uint8_t PIOS_USBHOOK_CLASS_IsoOUTIncomplete(void *pdev) +static uint8_t PIOS_USBHOOK_CLASS_IsoOUTIncomplete(__attribute__((unused)) void *pdev) { return USBD_OK; } -static const uint8_t * PIOS_USBHOOK_CLASS_GetConfigDescriptor(uint8_t speed, uint16_t *length) +static const uint8_t * PIOS_USBHOOK_CLASS_GetConfigDescriptor(__attribute__((unused)) uint8_t speed, uint16_t *length) { *length = Config_Descriptor.length; return Config_Descriptor.descriptor; diff --git a/flight/pios/stm32f4xx/startup.c b/flight/pios/stm32f4xx/startup.c index 94a3debcd..933481714 100644 --- a/flight/pios/stm32f4xx/startup.c +++ b/flight/pios/stm32f4xx/startup.c @@ -48,7 +48,7 @@ extern char _sidata, _sdata, _edata, _sfast, _efast; char irq_stack[1024] __attribute__((section(".irqstack"))); /** exception handler */ -typedef const void (vector)(void); +typedef void (vector)(void); /** CortexM3 CPU vectors */ struct cm3_vectors { @@ -145,4 +145,4 @@ struct cm3_vectors cpu_vectors __attribute((section(".cpu_vectors"))) = { /** * @} - */ \ No newline at end of file + */ diff --git a/flight/pios/stm32f4xx/vectors_stm32f4xx.c b/flight/pios/stm32f4xx/vectors_stm32f4xx.c index 2b28d558c..f1a958010 100644 --- a/flight/pios/stm32f4xx/vectors_stm32f4xx.c +++ b/flight/pios/stm32f4xx/vectors_stm32f4xx.c @@ -26,7 +26,7 @@ */ /** interrupt handler */ -typedef const void (vector)(void); +typedef void (vector)(void); /** default interrupt handler */ static void @@ -209,4 +209,4 @@ vector *io_vectors[] __attribute__((section(".io_vectors"))) = { /** * @} - */ \ No newline at end of file + */ diff --git a/flight/targets/boards/oplinkmini/board_hw_defs.c b/flight/targets/boards/oplinkmini/board_hw_defs.c index e0926a433..ad8b4eacc 100644 --- a/flight/targets/boards/oplinkmini/board_hw_defs.c +++ b/flight/targets/boards/oplinkmini/board_hw_defs.c @@ -92,7 +92,7 @@ static const struct pios_led_cfg pios_led_cfg = { .num_leds = NELEMENTS(pios_leds), }; -const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (__attribute__((unused)) uint32_t board_revision) { return &pios_led_cfg; } @@ -268,7 +268,7 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { }; //! Compatibility layer for various hardware revisions -const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision) +const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (__attribute__((unused)) uint32_t board_revision) { return &pios_rfm22b_cfg; } diff --git a/flight/targets/boards/osd/board_hw_defs.c b/flight/targets/boards/osd/board_hw_defs.c index 390e672e7..7b433a030 100644 --- a/flight/targets/boards/osd/board_hw_defs.c +++ b/flight/targets/boards/osd/board_hw_defs.c @@ -62,7 +62,7 @@ static const struct pios_led_cfg pios_led_cfg = { .num_leds = NELEMENTS(pios_leds), }; -const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (__attribute__((unused)) uint32_t board_revision) { return &pios_led_cfg; } @@ -712,7 +712,7 @@ static const struct pios_video_cfg pios_video_cfg = { .NVIC_IRQChannelCmd = ENABLE, }, }, - .rx = {}, + /*.rx = {},*/ .tx = { .channel = DMA1_Stream7, .init = { @@ -753,7 +753,7 @@ static const struct pios_video_cfg pios_video_cfg = { .GPIO_PuPd = GPIO_PuPd_NOPULL }, }, - .mosi = {}, + /*.mosi = {},*/ .slave_count = 1, }, .level = { @@ -781,7 +781,7 @@ static const struct pios_video_cfg pios_video_cfg = { .NVIC_IRQChannelCmd = ENABLE, }, }, - .rx = {}, + /*.rx = {},*/ .tx = { .channel = DMA2_Stream5, .init = { @@ -822,7 +822,7 @@ static const struct pios_video_cfg pios_video_cfg = { .GPIO_PuPd = GPIO_PuPd_UP }, }, - .mosi = {}, + /*.mosi = {},*/ .slave_count = 1, }, diff --git a/flight/targets/boards/osd/firmware/fonts.c b/flight/targets/boards/osd/firmware/fonts.c index d7fe657e1..5b0c22d75 100644 --- a/flight/targets/boards/osd/firmware/fonts.c +++ b/flight/targets/boards/osd/firmware/fonts.c @@ -31,5 +31,5 @@ struct FontEntry fonts[NUM_FONTS + 1] = { FONT_UPPERCASE_ONLY }, { 2, 8, 10, "font8x10", 0, 0, 0 }, { 3, 12, 18, "font12x18", 0, 0, 0 }, - { -1 } // ends font table + { -1, -1, -1, "", 0, 0, 0 } // ends font table }; diff --git a/flight/targets/boards/osd/firmware/inc/splash.h b/flight/targets/boards/osd/firmware/inc/splash.h index 6cbd41357..3ea31872c 100644 --- a/flight/targets/boards/osd/firmware/inc/splash.h +++ b/flight/targets/boards/osd/firmware/inc/splash.h @@ -10,7 +10,7 @@ #define oplogo_width 144 #define oplogo_height 144 -const static unsigned short oplogo_bits[] = { +static const unsigned short oplogo_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, @@ -156,7 +156,7 @@ const static unsigned short oplogo_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; -const static unsigned short oplogo_mask_bits[] = { +static const unsigned short oplogo_mask_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x03ff, 0x0000, 0x0000, 0x0000, @@ -305,7 +305,7 @@ const static unsigned short oplogo_mask_bits[] = { #define level_width 144 #define level_height 129 -const static unsigned short level_bits[] = { +static const unsigned short level_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, @@ -438,7 +438,7 @@ const static unsigned short level_bits[] = { #define level_mask_width 144 #define level_mask_height 129 -const static unsigned short level_mask_bits[] = { +static const unsigned short level_mask_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, @@ -571,7 +571,7 @@ const static unsigned short level_mask_bits[] = { #define llama_width 240 #define llama_height 260 -const static unsigned short llama_bits[] = { +static const unsigned short llama_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, @@ -1009,7 +1009,7 @@ const static unsigned short llama_bits[] = { #define llama_mask_width 240 #define llama_mask_height 260 -const static unsigned short llama_mask_bits[] = { +static const unsigned short llama_mask_bits[] = { 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, diff --git a/flight/targets/boards/osd/firmware/osd.c b/flight/targets/boards/osd/firmware/osd.c index f43bacc96..499d1d8ca 100644 --- a/flight/targets/boards/osd/firmware/osd.c +++ b/flight/targets/boards/osd/firmware/osd.c @@ -222,7 +222,7 @@ int main() * Runs board and module initialisation, then terminates. */ void -initTask(void *parameters) +initTask(__attribute__((unused)) void *parameters) { /* board driver init */ PIOS_Board_Init(); diff --git a/flight/targets/boards/osd/firmware/pios_board.c b/flight/targets/boards/osd/firmware/pios_board.c index 1edd83dd8..93db87174 100644 --- a/flight/targets/boards/osd/firmware/pios_board.c +++ b/flight/targets/boards/osd/firmware/pios_board.c @@ -128,7 +128,7 @@ static const TIM_TimeBaseInitTypeDef tim_4_time_base = { .TIM_RepetitionCounter = 0x0000, }; -const static struct pios_tim_clock_cfg pios_tim4_cfg = { +static const struct pios_tim_clock_cfg pios_tim4_cfg = { .timer = TIM4, .time_base_init = &tim_4_time_base, .irq = { @@ -469,7 +469,7 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv uint16_t supv_timer=0; -static void Clock(uint32_t spektrum_id) { +static void Clock(__attribute__((unused)) uint32_t spektrum_id) { /* 125hz */ ++supv_timer; if(supv_timer >= 625) { diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index 41baaf0d9..c1acafb7d 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -248,7 +248,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len); PIOS_Assert(rx_buffer); - if(tx_buf_len!= -1){ // this is the case for rx/tx ports + if(tx_buf_len!= (size_t)-1){ // this is the case for rx/tx ports uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len); PIOS_Assert(tx_buffer); @@ -830,9 +830,11 @@ void PIOS_Board_Init(void) { * \param[in] vcp_port The USB virtual com port options * \param[in] com_speed The com port speed */ -static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port, - OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed, - uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing) +static void configureComCallback(__attribute__((unused)) OPLinkSettingsRemoteMainPortOptions main_port, + __attribute__((unused)) OPLinkSettingsRemoteFlexiPortOptions flexi_port, + __attribute__((unused)) OPLinkSettingsRemoteVCPPortOptions vcp_port, + OPLinkSettingsComSpeedOptions com_speed, + uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing) { uint32_t comBaud = 9600; switch (com_speed) { diff --git a/flight/targets/boards/revolution/firmware/revolution.c b/flight/targets/boards/revolution/firmware/revolution.c index 65a7db7dd..02c7f0d01 100644 --- a/flight/targets/boards/revolution/firmware/revolution.c +++ b/flight/targets/boards/revolution/firmware/revolution.c @@ -121,7 +121,7 @@ int main() * Runs board and module initialisation, then terminates. */ void -initTask(void *parameters) +initTask(__attribute__((unused)) void *parameters) { /* board driver init */ PIOS_Board_Init(); diff --git a/flight/targets/boards/revoproto/board_hw_defs.c b/flight/targets/boards/revoproto/board_hw_defs.c index 493df060a..0934a5a26 100644 --- a/flight/targets/boards/revoproto/board_hw_defs.c +++ b/flight/targets/boards/revoproto/board_hw_defs.c @@ -60,7 +60,7 @@ static const struct pios_led_cfg pios_led_cfg = { .num_leds = NELEMENTS(pios_leds), }; -const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (__attribute__((unused)) uint32_t board_revision) { return &pios_led_cfg; } diff --git a/flight/targets/boards/revoproto/firmware/pios_board.c b/flight/targets/boards/revoproto/firmware/pios_board.c index c11651a7c..3fda1d1a6 100644 --- a/flight/targets/boards/revoproto/firmware/pios_board.c +++ b/flight/targets/boards/revoproto/firmware/pios_board.c @@ -318,7 +318,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len); PIOS_Assert(rx_buffer); - if(tx_buf_len!= -1){ // this is the case for rx/tx ports + if(tx_buf_len!= (size_t)-1){ // this is the case for rx/tx ports uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len); PIOS_Assert(tx_buffer); diff --git a/flight/targets/boards/revoproto/firmware/revolution.c b/flight/targets/boards/revoproto/firmware/revolution.c index 5785cd655..b1f771ddd 100644 --- a/flight/targets/boards/revoproto/firmware/revolution.c +++ b/flight/targets/boards/revoproto/firmware/revolution.c @@ -120,7 +120,7 @@ int main() * Runs board and module initialisation, then terminates. */ void -initTask(void *parameters) +initTask(__attribute__((unused)) void *parameters) { /* board driver init */ PIOS_Board_Init(); diff --git a/flight/targets/boards/simposix/firmware/simposix.c b/flight/targets/boards/simposix/firmware/simposix.c index e232259fd..4b6620b9f 100644 --- a/flight/targets/boards/simposix/firmware/simposix.c +++ b/flight/targets/boards/simposix/firmware/simposix.c @@ -121,7 +121,7 @@ int main() * Runs board and module initialisation, then terminates. */ void -initTask(void *parameters) +initTask(__attribute__((unused)) void *parameters) { /* board driver init */ PIOS_Board_Init(); diff --git a/flight/uavobjects/eventdispatcher.c b/flight/uavobjects/eventdispatcher.c index e0ffbc99a..bcf706b78 100644 --- a/flight/uavobjects/eventdispatcher.c +++ b/flight/uavobjects/eventdispatcher.c @@ -276,8 +276,8 @@ static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue */ static void eventTask() { - int32_t timeToNextUpdateMs; - int32_t delayMs; + uint32_t timeToNextUpdateMs; + uint32_t delayMs; EventCallbackInfo evInfo; /* Must do this in task context to ensure that TaskMonitor has already finished its init */ @@ -290,11 +290,7 @@ static void eventTask() while (1) { // Calculate delay time - delayMs = timeToNextUpdateMs-(xTaskGetTickCount()*portTICK_RATE_MS); - if (delayMs < 0) - { - delayMs = 0; - } + delayMs = timeToNextUpdateMs - (xTaskGetTickCount() * portTICK_RATE_MS); // Wait for queue message if ( xQueueReceive(queue, &evInfo, delayMs/portTICK_RATE_MS) == pdTRUE ) diff --git a/flight/uavobjects/uavobjectmanager.c b/flight/uavobjects/uavobjectmanager.c index 16f724d87..d4a22ce10 100644 --- a/flight/uavobjects/uavobjectmanager.c +++ b/flight/uavobjects/uavobjectmanager.c @@ -788,7 +788,7 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, * @param[in] file File to append to * @return 0 if success or -1 if failure */ -int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId) +int32_t UAVObjSave(UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId) { PIOS_Assert(obj_handle); @@ -942,7 +942,7 @@ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) * @param[in] instId The object instance * @return 0 if success or -1 if failure */ -int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId) +int32_t UAVObjLoad(UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId) { PIOS_Assert(obj_handle); @@ -1018,7 +1018,7 @@ int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId) * @param[in] instId The object instance * @return 0 if success or -1 if failure */ -int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId) +int32_t UAVObjDelete(UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId) { PIOS_Assert(obj_handle); #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) diff --git a/flight/uavtalk/inc/uavtalk_priv.h b/flight/uavtalk/inc/uavtalk_priv.h index ba107e970..84174e90a 100644 --- a/flight/uavtalk/inc/uavtalk_priv.h +++ b/flight/uavtalk/inc/uavtalk_priv.h @@ -67,7 +67,7 @@ typedef struct { uint8_t timestampLength; uint8_t cs; uint16_t timestamp; - int32_t rxCount; + uint32_t rxCount; UAVTalkRxState state; uint16_t rxPacketLength; } UAVTalkInputProcessor; diff --git a/flight/uavtalk/uavtalk.c b/flight/uavtalk/uavtalk.c index 1f25cb767..eb060b735 100644 --- a/flight/uavtalk/uavtalk.c +++ b/flight/uavtalk/uavtalk.c @@ -714,7 +714,12 @@ int32_t UAVTalkSendBuf(UAVTalkConnection connectionHandle, uint8_t *buf, uint16_ * \return 0 Success * \return -1 Failure */ -static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length) +static int32_t receiveObject(UAVTalkConnectionData *connection, + uint8_t type, + uint32_t objId, + uint16_t instId, + uint8_t* data, + __attribute__((unused))int32_t length) { UAVObjHandle obj; int32_t ret = 0; diff --git a/make/common-defs.mk b/make/common-defs.mk index 10b205634..f73624c13 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -123,7 +123,7 @@ CFLAGS += -O$(OPT) CFLAGS += -g$(DEBUGF) CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer -CFLAGS += -Wall +CFLAGS += -Wall -Wextra CFLAGS += -Wfloat-equal -Wunsuffixed-float-constants -Wdouble-promotion CFLAGS += -Werror CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.