diff --git a/Makefile b/Makefile index 3f5ab295cc..1f40f9c291 100644 --- a/Makefile +++ b/Makefile @@ -223,6 +223,7 @@ CFLAGS += $(ARCH_FLAGS) \ $(DEBUG_FLAGS) \ -std=gnu99 \ -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ + -Wstrict-prototypes \ -Werror=switch \ -ffunction-sections \ -fdata-sections \ diff --git a/src/main/cms/cms_menu_vtx_smartaudio.h b/src/main/cms/cms_menu_vtx_smartaudio.h index d8aeea3ab5..e29f05d891 100644 --- a/src/main/cms/cms_menu_vtx_smartaudio.h +++ b/src/main/cms/cms_menu_vtx_smartaudio.h @@ -26,4 +26,4 @@ extern CMS_Menu cmsx_menuVtxSmartAudio; void saCmsUpdate(void); -void saCmsResetOpmodel(); +void saCmsResetOpmodel(void); diff --git a/src/main/drivers/rx_spi.h b/src/main/drivers/rx_spi.h index 55613b12bc..c459c4735c 100755 --- a/src/main/drivers/rx_spi.h +++ b/src/main/drivers/rx_spi.h @@ -20,7 +20,7 @@ #define RX_SPI_MAX_PAYLOAD_SIZE 32 -void rxSpiDeviceInit(); +void rxSpiDeviceInit(void); uint8_t rxSpiTransferByte(uint8_t data); uint8_t rxSpiWriteByte(uint8_t data); uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data); diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index 3d7d0c9a36..c63978e3f6 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -39,6 +39,6 @@ void tryArm(void); disarmReason_t getDisarmReason(void); bool isCalibrating(void); -float getFlightTime(); +float getFlightTime(void); -void fcReboot(bool bootLoader); \ No newline at end of file +void fcReboot(bool bootLoader); diff --git a/src/main/fc/stats.h b/src/main/fc/stats.h index 95bf8c2bca..275460643c 100644 --- a/src/main/fc/stats.h +++ b/src/main/fc/stats.h @@ -11,7 +11,7 @@ typedef struct statsConfig_s { uint8_t stats_enabled; } statsConfig_t; -uint32_t getFlyingEnergy(); +uint32_t getFlyingEnergy(void); void statsOnArm(void); void statsOnDisarm(void); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 013fe88df6..9cc9788177 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -140,8 +140,8 @@ typedef struct pidAutotuneConfig_s { PG_DECLARE_PROFILE(pidProfile_t, pidProfile); PG_DECLARE(pidAutotuneConfig_t, pidAutotuneConfig); -static inline const pidBank_t * pidBank() { return STATE(FIXED_WING) ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } -static inline pidBank_t * pidBankMutable() { return STATE(FIXED_WING) ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } +static inline const pidBank_t * pidBank(void) { return STATE(FIXED_WING) ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } +static inline pidBank_t * pidBankMutable(void) { return STATE(FIXED_WING) ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } extern int16_t axisPID[]; extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[]; diff --git a/src/main/io/pwmdriver_i2c.c b/src/main/io/pwmdriver_i2c.c index 2fda679d41..727b8428f9 100644 --- a/src/main/io/pwmdriver_i2c.c +++ b/src/main/io/pwmdriver_i2c.c @@ -30,7 +30,7 @@ pwmDriverDriver_t pwmDrivers[PWM_DRIVER_IMPLEMENTATION_COUNT] = { } }; -bool isPwmDriverEnabled() { +bool isPwmDriverEnabled(void) { return driverEnabled; } diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index dffa7ad56b..d1353f2a47 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -382,7 +382,7 @@ void resetWaypointList(void); bool loadNonVolatileWaypointList(void); bool saveNonVolatileWaypointList(void); -float RTHAltitude(); +float RTHAltitude(void); /* Geodetic functions */ typedef enum { @@ -438,7 +438,7 @@ bool isNavLaunchEnabled(void); bool isFixedWingLaunchDetected(void); bool isFixedWingLaunchFinishedOrAborted(void); -float calculateAverageSpeed(); +float calculateAverageSpeed(void); const navigationPIDControllers_t* getNavigationPIDControllers(void); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index d9ef1cb447..2fa663fd46 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -157,7 +157,7 @@ static int profile_compare(profile_comp_t *a, profile_comp_t *b) { } // Find profile matching plugged battery for profile_autoselect -static int8_t profileDetect() { +static int8_t profileDetect(void) { profile_comp_t profile_comp_array[MAX_BATTERY_PROFILE_COUNT]; // Prepare profile sort diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 2ce0370074..45b9affad3 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -148,6 +148,6 @@ void powerMeterUpdate(timeUs_t timeDelta); uint8_t calculateBatteryPercentage(void); float calculateThrottleCompensationFactor(void); -int32_t calculateAveragePower(); -int32_t calculateAverageEfficiency(); +int32_t calculateAveragePower(void); +int32_t calculateAverageEfficiency(void); int32_t heatLossesCompensatedPower(int32_t power); diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 84ea3e16ca..b6802b011c 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -67,7 +67,7 @@ PG_DECLARE(gyroConfig_t, gyroConfig); bool gyroInit(void); void gyroInitFilters(void); void gyroGetMeasuredRotationRate(fpVector3_t *imuMeasuredRotationBF); -void gyroUpdate(); +void gyroUpdate(void); void gyroStartCalibration(void); bool gyroIsCalibrationComplete(void); bool gyroReadTemperature(void); diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb index 54979c193a..3a8f4d9919 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -61,6 +61,10 @@ class Compiler if flag == "" || flag == "-MMD" || flag == "-MP" || flag.start_with?("-save-temps") next end + # -Wstrict-prototypes is not valid for C++ + if flag == "-Wstrict-prototypes" + next + end if flag.start_with? "-std=" flag = "-std=c++11" end