diff --git a/Makefile b/Makefile index d73bd7c50e..2c2cca5857 100644 --- a/Makefile +++ b/Makefile @@ -236,12 +236,15 @@ CC_NO_OPTIMISATION := # TEMPORARY_FLAGS := +EXTRA_WARNING_FLAGS := -Wold-style-definition + CFLAGS += $(ARCH_FLAGS) \ $(addprefix -D,$(OPTIONS)) \ $(addprefix -I,$(INCLUDE_DIRS)) \ $(DEBUG_FLAGS) \ -std=gnu17 \ -Wall -Wextra -Werror -Wpedantic -Wunsafe-loop-optimizations -Wdouble-promotion \ + $(EXTRA_WARNING_FLAGS) \ -ffunction-sections \ -fdata-sections \ -fno-common \ diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index a530e677b7..076b2447b5 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -353,7 +353,7 @@ static void cliPrintInternal(bufWriter_t *writer, const char *str) } } -static void cliWriterFlush() +static void cliWriterFlush(void) { cliWriterFlushInternal(cliWriter); } @@ -709,13 +709,13 @@ static void restoreConfigs(uint16_t notToRestoreGroupId) } #if defined(USE_RESOURCE_MGMT) || defined(USE_TIMER_MGMT) -static bool isReadingConfigFromCopy() +static bool isReadingConfigFromCopy(void) { return configIsInCopy; } #endif -static bool isWritingConfigToCopy() +static bool isWritingConfigToCopy(void) { return configIsInCopy #if defined(USE_CUSTOM_DEFAULTS) @@ -746,12 +746,12 @@ static void backupAndResetConfigs(const bool useCustomDefaults) #endif } -static uint8_t getPidProfileIndexToUse() +static uint8_t getPidProfileIndexToUse(void) { return pidProfileIndexToUse == CURRENT_PROFILE_INDEX ? getCurrentPidProfileIndex() : pidProfileIndexToUse; } -static uint8_t getRateProfileIndexToUse() +static uint8_t getRateProfileIndexToUse(void) { return rateProfileIndexToUse == CURRENT_PROFILE_INDEX ? getCurrentControlRateProfileIndex() : rateProfileIndexToUse; } diff --git a/src/main/cms/cms_menu_vtx_smartaudio.c b/src/main/cms/cms_menu_vtx_smartaudio.c index 3614709744..520b2fb9d6 100644 --- a/src/main/cms/cms_menu_vtx_smartaudio.c +++ b/src/main/cms/cms_menu_vtx_smartaudio.c @@ -198,7 +198,7 @@ void saUpdateStatusString(void) } } -void saCmsResetOpmodel() +void saCmsResetOpmodel(void) { // trigger data refresh in 'saCmsUpdate()' saCmsOpmodel = SACMS_OPMODEL_UNDEF; diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index 56a53ef758..d6b0ea97b6 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -148,7 +148,7 @@ static void BMI160_Init(const extDevice_t *dev) BMI160InitDone = true; } -static uint8_t getBmiOsrMode() +static uint8_t getBmiOsrMode(void) { switch(gyroConfig()->gyro_hardware_lpf) { case GYRO_HARDWARE_LPF_NORMAL: diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c index 4fba400171..2fd0d94a18 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -187,7 +187,7 @@ static void bmi270UploadConfig(const extDevice_t *dev) bmi270RegisterWrite(dev, BMI270_REG_INIT_CTRL, 1, 1); } -static uint8_t getBmiOsrMode() +static uint8_t getBmiOsrMode(void) { switch(gyroConfig()->gyro_hardware_lpf) { case GYRO_HARDWARE_LPF_NORMAL: diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 70a7e7fd4c..704961a788 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -539,7 +539,7 @@ bool spiSetBusInstance(extDevice_t *dev, uint32_t device) return true; } -void spiInitBusDMA() +void spiInitBusDMA(void) { uint32_t device; #if defined(STM32F4) && defined(USE_DSHOT_BITBANG) diff --git a/src/main/drivers/dshot_bitbang.c b/src/main/drivers/dshot_bitbang.c index 471199ec7a..6783f24159 100644 --- a/src/main/drivers/dshot_bitbang.c +++ b/src/main/drivers/dshot_bitbang.c @@ -688,7 +688,7 @@ static bool bbIsMotorEnabled(uint8_t index) return bbMotors[index].enabled; } -static void bbPostInit() +static void bbPostInit(void) { bbFindPacerTimer(); @@ -721,7 +721,7 @@ static motorVTable_t bbVTable = { .shutdown = bbShutdown, }; -dshotBitbangStatus_e dshotBitbangGetStatus() +dshotBitbangStatus_e dshotBitbangGetStatus(void) { return bbStatus; } diff --git a/src/main/drivers/dshot_command.c b/src/main/drivers/dshot_command.c index 14faa2cbfb..37d02b7f21 100644 --- a/src/main/drivers/dshot_command.c +++ b/src/main/drivers/dshot_command.c @@ -77,7 +77,7 @@ void dshotSetPidLoopTime(uint32_t pidLoopTime) dshotCommandPidLoopTimeUs = pidLoopTime; } -static FAST_CODE bool dshotCommandQueueFull() +static FAST_CODE bool dshotCommandQueueFull(void) { return (commandQueueHead + 1) % (DSHOT_MAX_COMMANDS + 1) == commandQueueTail; } @@ -129,7 +129,7 @@ static FAST_CODE uint32_t dshotCommandCyclesFromTime(timeUs_t delayUs) return (delayUs + dshotCommandPidLoopTimeUs - 1) / dshotCommandPidLoopTimeUs; } -static dshotCommandControl_t* addCommand() +static dshotCommandControl_t* addCommand(void) { int newHead = (commandQueueHead + 1) % (DSHOT_MAX_COMMANDS + 1); if (newHead == commandQueueTail) { diff --git a/src/main/drivers/motor.c b/src/main/drivers/motor.c index df0717785c..cb6738ecc6 100644 --- a/src/main/drivers/motor.c +++ b/src/main/drivers/motor.c @@ -166,7 +166,7 @@ uint16_t motorConvertToExternal(float motorValue) return motorDevice->vTable.convertMotorToExternal(motorValue); } -void motorPostInit() +void motorPostInit(void) { motorDevice->vTable.postInit(); } diff --git a/src/main/drivers/pin_pull_up_down.c b/src/main/drivers/pin_pull_up_down.c index 021ac91e0c..56479b687a 100644 --- a/src/main/drivers/pin_pull_up_down.c +++ b/src/main/drivers/pin_pull_up_down.c @@ -46,7 +46,7 @@ static void initPin(const pinPullUpDownConfig_t* config, resourceOwner_e owner, } } -void pinPullupPulldownInit() +void pinPullupPulldownInit(void) { for (uint8_t i = 0; i < PIN_PULL_UP_DOWN_COUNT; i++) { initPin(pinPullupConfig(i), OWNER_PULLUP, i); diff --git a/src/main/drivers/rx/rx_spi.c b/src/main/drivers/rx/rx_spi.c index 1c3ab761c2..1755a06bb7 100644 --- a/src/main/drivers/rx/rx_spi.c +++ b/src/main/drivers/rx/rx_spi.c @@ -92,12 +92,12 @@ void rxSpiSetNormalSpeedMhz(uint32_t mhz) spiNormalSpeedMhz = mhz; } -void rxSpiNormalSpeed() +void rxSpiNormalSpeed(void) { spiSetClkDivisor(dev, spiCalculateDivider(spiNormalSpeedMhz)); } -void rxSpiStartupSpeed() +void rxSpiStartupSpeed(void) { spiSetClkDivisor(dev, spiCalculateDivider(RX_STARTUP_MAX_SPI_CLK_HZ)); } diff --git a/src/main/drivers/sdcard_sdio_baremetal.c b/src/main/drivers/sdcard_sdio_baremetal.c index 2baeb1c7be..3342e3bc14 100644 --- a/src/main/drivers/sdcard_sdio_baremetal.c +++ b/src/main/drivers/sdcard_sdio_baremetal.c @@ -252,7 +252,7 @@ static void sdcardSdio_init(const sdcardConfig_t *config, const spiPinConfig_t * /* * Returns true if the card is ready to accept read/write commands. */ -static bool sdcard_isReady() +static bool sdcard_isReady(void) { return sdcard.state == SDCARD_STATE_READY || sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS; } @@ -267,7 +267,7 @@ static bool sdcard_isReady() * the SDCARD_READY state. * */ -static sdcardOperationStatus_e sdcard_endWriteBlocks() +static sdcardOperationStatus_e sdcard_endWriteBlocks(void) { sdcard.multiWriteBlocksRemain = 0; if (sdcard.useCache) { diff --git a/src/main/fc/core.c b/src/main/fc/core.c index 5d7691e179..0c06c69206 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -747,7 +747,7 @@ uint8_t calculateThrottlePercentAbs(void) static bool airmodeIsActivated; -bool isAirmodeActivated() +bool isAirmodeActivated(void) { return airmodeIsActivated; } @@ -1315,12 +1315,12 @@ timeUs_t getLastDisarmTimeUs(void) return lastDisarmTimeUs; } -bool isTryingToArm() +bool isTryingToArm(void) { return (tryingToArm != ARMING_DELAYED_DISARMED); } -void resetTryingToArm() +void resetTryingToArm(void) { tryingToArm = ARMING_DELAYED_DISARMED; } diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 37902f642f..419ac1eee1 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -236,7 +236,7 @@ static void configureSPIAndQuadSPI(void) } #ifdef USE_SDCARD -static void sdCardAndFSInit() +static void sdCardAndFSInit(void) { sdcard_init(sdcardConfig()); afatfs_init(); diff --git a/src/main/fc/rc.c b/src/main/fc/rc.c index 5d72b30cfa..663600941d 100644 --- a/src/main/fc/rc.c +++ b/src/main/fc/rc.c @@ -99,7 +99,7 @@ static float rcDeflectionSmoothed[3]; #define RC_RX_RATE_MIN_US 950 // 0.950ms to fit 1kHz without an issue #define RC_RX_RATE_MAX_US 65500 // 65.5ms or 15.26hz -bool getShouldUpdateFeedforward() +bool getShouldUpdateFeedforward(void) // only used in pid.c, when feedforward is enabled, to initiate a new FF value { const bool updateFf = newRxDataForFF; diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 138065c098..0872abea86 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -135,7 +135,7 @@ throttleStatus_e calculateThrottleStatus(void) doNotRepeat = false; \ } -void processRcStickPositions() +void processRcStickPositions(void) { // time the sticks are maintained static int16_t rcDelayMs; diff --git a/src/main/fc/tasks.c b/src/main/fc/tasks.c index 2a82c7dd7b..419e136df9 100644 --- a/src/main/fc/tasks.c +++ b/src/main/fc/tasks.c @@ -179,7 +179,7 @@ typedef enum { static rxState_e rxState = RX_STATE_CHECK; -bool taskUpdateRxMainInProgress() +bool taskUpdateRxMainInProgress(void) { return (rxState != RX_STATE_CHECK); } @@ -310,8 +310,9 @@ static bool taskAltitudeCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTi return false; } - static void taskCalculateAltitude() + static void taskCalculateAltitude(timeUs_t currentTimeUs) { + UNUSED(currentTimeUs); calculateEstimatedAltitude(); } #endif // USE_BARO || USE_GPS diff --git a/src/main/flight/gps_rescue.c b/src/main/flight/gps_rescue.c index 62ce1269a6..df08dafa33 100644 --- a/src/main/flight/gps_rescue.c +++ b/src/main/flight/gps_rescue.c @@ -210,18 +210,18 @@ void rescueNewGpsData(void) newGPSData = true; } -static void rescueStart() +static void rescueStart(void) { rescueState.phase = RESCUE_INITIALIZE; } -static void rescueStop() +static void rescueStop(void) { rescueState.phase = RESCUE_IDLE; } // Things that need to run when GPS Rescue is enabled, and while armed, but while there is no Rescue in place -static void setReturnAltitude() +static void setReturnAltitude(void) { // Hold maxAltitude at zero while disarmed, but if set_home_point_once is true, hold maxAlt until power cycled if (!ARMING_FLAG(ARMED) && !gpsConfig()->gps_set_home_point_once) { @@ -255,7 +255,7 @@ static void setReturnAltitude() } } -static void rescueAttainPosition() +static void rescueAttainPosition(void) { // runs at 100hz, but only updates RPYT settings when new GPS Data arrives and when not in idle phase. static float previousVelocityError = 0.0f; @@ -425,7 +425,7 @@ static void rescueAttainPosition() DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING, 1, lrintf(rescueState.intent.targetVelocityCmS)); } -static void performSanityChecks() +static void performSanityChecks(void) { static timeUs_t previousTimeUs = 0; // Last time Stalled/LowSat was checked static float prevAltitudeCm = 0.0f; // to calculate ascent or descent change @@ -550,7 +550,7 @@ static void performSanityChecks() DEBUG_SET(DEBUG_RTH, 3, (rescueState.intent.secondsFailing * 100 + secondsLowSats)); } -static void sensorUpdate() +static void sensorUpdate(void) { static float prevDistanceToHomeCm = 0.0f; const timeUs_t currentTimeUs = micros(); diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index dbdb9338e6..c8567bcdd9 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -587,7 +587,7 @@ void imuUpdateAttitude(timeUs_t currentTimeUs) } #endif // USE_ACC -bool shouldInitializeGPSHeading() +bool shouldInitializeGPSHeading(void) { static bool initialized = false; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b01bfdcbd8..ece7322755 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -262,22 +262,22 @@ void pidStabilisationState(pidStabilisationState_e pidControllerState) const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; #ifdef USE_FEEDFORWARD -float pidGetFeedforwardTransitionFactor() +float pidGetFeedforwardTransitionFactor(void) { return pidRuntime.feedforwardTransitionFactor; } -float pidGetFeedforwardSmoothFactor() +float pidGetFeedforwardSmoothFactor(void) { return pidRuntime.feedforwardSmoothFactor; } -float pidGetFeedforwardJitterFactor() +float pidGetFeedforwardJitterFactor(void) { return pidRuntime.feedforwardJitterFactor; } -float pidGetFeedforwardBoostFactor() +float pidGetFeedforwardBoostFactor(void) { return pidRuntime.feedforwardBoostFactor; } @@ -377,7 +377,7 @@ static float getLevelModeRcDeflection(uint8_t axis) } // calculates strength of horizon leveling; 0 = none, 1.0 = most leveling -STATIC_UNIT_TESTED FAST_CODE_NOINLINE float calcHorizonLevelStrength() +STATIC_UNIT_TESTED FAST_CODE_NOINLINE float calcHorizonLevelStrength(void) { // start with 1.0 at center stick, 0.0 at max stick deflection: float horizonLevelStrength = 1.0f - MAX(fabsf(getLevelModeRcDeflection(FD_ROLL)), fabsf(getLevelModeRcDeflection(FD_PITCH))); @@ -636,7 +636,7 @@ static void rotateVector(float v[XYZ_AXIS_COUNT], float rotation[XYZ_AXIS_COUNT] } } -STATIC_UNIT_TESTED void rotateItermAndAxisError() +STATIC_UNIT_TESTED void rotateItermAndAxisError(void) { if (pidRuntime.itermRotation #if defined(USE_ABSOLUTE_CONTROL) @@ -778,7 +778,7 @@ void pidUpdateAirmodeLpf(float currentOffset) pidRuntime.airmodeThrottleLpf1.state = constrainf(pidRuntime.airmodeThrottleLpf1.state, -pidRuntime.airmodeThrottleOffsetLimit, pidRuntime.airmodeThrottleOffsetLimit); } -float pidGetAirmodeThrottleOffset() +float pidGetAirmodeThrottleOffset(void) { return pidRuntime.airmodeThrottleLpf1.state; } @@ -1278,12 +1278,12 @@ float pidGetPreviousSetpoint(int axis) return pidRuntime.previousPidSetpoint[axis]; } -float pidGetDT() +float pidGetDT(void) { return pidRuntime.dT; } -float pidGetPidFrequency() +float pidGetPidFrequency(void) { return pidRuntime.pidFrequency; } diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index acf0e2bd43..6a8f973223 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -448,7 +448,7 @@ void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPi void rotateItermAndAxisError(); float pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim, float currentPidSetpoint, float horizonLevelStrength); -float calcHorizonLevelStrength(); +float calcHorizonLevelStrength(void); #endif void dynLpfDTermUpdate(float throttle); void pidSetItermReset(bool enabled); diff --git a/src/main/flight/position.c b/src/main/flight/position.c index 268895de8e..d82c446085 100644 --- a/src/main/flight/position.c +++ b/src/main/flight/position.c @@ -85,7 +85,7 @@ PG_RESET_TEMPLATE(positionConfig_t, positionConfig, ); #if defined(USE_BARO) || defined(USE_GPS) -void calculateEstimatedAltitude() +void calculateEstimatedAltitude(void) { static bool wasArmed = false; static bool useZeroedGpsAltitude = false; // whether a zero for the GPS altitude value exists diff --git a/src/main/flight/position.h b/src/main/flight/position.h index 690af5180c..59e11603a6 100644 --- a/src/main/flight/position.h +++ b/src/main/flight/position.h @@ -32,7 +32,7 @@ typedef struct positionConfig_s { PG_DECLARE(positionConfig_t, positionConfig); -void calculateEstimatedAltitude(); +void calculateEstimatedAltitude(void); void positionInit(void); int32_t getEstimatedAltitudeCm(void); float getAltitude(void); diff --git a/src/main/io/displayport_crsf.c b/src/main/io/displayport_crsf.c index 64b60f6b66..58e01f8d86 100644 --- a/src/main/io/displayport_crsf.c +++ b/src/main/io/displayport_crsf.c @@ -200,7 +200,7 @@ bool crsfDisplayPortIsReady(void) return (bool)(delayExpired && cmsReady); } -static displayPort_t *displayPortCrsfInit() +static displayPort_t *displayPortCrsfInit(void) { crsfDisplayPortSetDimensions(CRSF_DISPLAY_PORT_ROWS_MAX, CRSF_DISPLAY_PORT_COLS_MAX); displayInit(&crsfDisplayPort, &crsfDisplayPortVTable, DISPLAYPORT_DEVICE_TYPE_CRSF); diff --git a/src/main/io/displayport_hott.c b/src/main/io/displayport_hott.c index 7a76e458b5..5873248086 100644 --- a/src/main/io/displayport_hott.c +++ b/src/main/io/displayport_hott.c @@ -130,7 +130,7 @@ static const displayPortVTable_t hottVTable = { .layerCopy = NULL, }; -static displayPort_t *displayPortHottInit() +static displayPort_t *displayPortHottInit(void) { hottDisplayPort.device = NULL; displayInit(&hottDisplayPort, &hottVTable, DISPLAYPORT_DEVICE_TYPE_HOTT); @@ -140,12 +140,12 @@ static displayPort_t *displayPortHottInit() return &hottDisplayPort; } -void hottDisplayportRegister() +void hottDisplayportRegister(void) { cmsDisplayPortRegister(displayPortHottInit()); } -void hottCmsOpen() +void hottCmsOpen(void) { if (!cmsInMenu) { cmsDisplayPortSelect(&hottDisplayPort); diff --git a/src/main/io/displayport_srxl.c b/src/main/io/displayport_srxl.c index 33a04dc989..0e107a2fd2 100644 --- a/src/main/io/displayport_srxl.c +++ b/src/main/io/displayport_srxl.c @@ -143,7 +143,7 @@ static const displayPortVTable_t srxlVTable = { .layerCopy = NULL, }; -static displayPort_t *displayPortSrxlInit() +static displayPort_t *displayPortSrxlInit(void) { srxlDisplayPort.device = NULL; displayInit(&srxlDisplayPort, &srxlVTable, DISPLAYPORT_DEVICE_TYPE_SRXL); diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 9cd7e869f9..55a549ee5d 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -317,7 +317,7 @@ static int flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferS } -static bool flashfsNewData() +static bool flashfsNewData(void) { return dataWritten; } diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 295a6188db..90f327543a 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -298,7 +298,7 @@ static void shiftPacketLog(void) } } -static bool isConfiguratorConnected() +static bool isConfiguratorConnected(void) { return (getArmingDisableFlags() & ARMING_DISABLED_MSP); } @@ -531,7 +531,7 @@ static void ubloxSetNavRate(uint16_t measRate, uint16_t navRate, uint16_t timeRe ubloxSendConfigMessage(&tx_buffer, MSG_CFG_RATE, sizeof(ubx_cfg_rate)); } -static void ubloxSetSbas() +static void ubloxSetSbas(void) { ubx_message tx_buffer; @@ -940,7 +940,7 @@ bool gpsNewFrame(uint8_t c) } // Check for healthy communications -bool gpsIsHealthy() +bool gpsIsHealthy(void) { return (gpsData.state == GPS_STATE_RECEIVING_DATA); } diff --git a/src/main/io/rcdevice.c b/src/main/io/rcdevice.c index 5a51951878..f747874961 100644 --- a/src/main/io/rcdevice.c +++ b/src/main/io/rcdevice.c @@ -382,7 +382,7 @@ static rcdeviceResponseParseContext_t* getWaitingResponse(timeMs_t currentTimeMs return respCtx; } -runcamDeviceRequest_t* rcdeviceGetRequest() +runcamDeviceRequest_t* rcdeviceGetRequest(void) { if (requestParserContext.isParseDone) { // reset the parse done state, then we can handle next request from rcdevice @@ -457,7 +457,7 @@ void rcdeviceReceive(timeUs_t currentTimeUs) break; } - // if it is during the packet receiving progress, check if it is already timeout(200 ms), + // if it is during the packet receiving progress, check if it is already timeout(200 ms), // if timeout, then reset the state, else the later requests can't be accept if (requestParserContext.state != RCDEVICE_STATE_WAITING_HEADER && millis() - requestParserContext.lastRecvDataTimestamp > 200) { memset(&requestParserContext, 0, sizeof(runcamDeviceRequestParseContext_t)); @@ -475,7 +475,7 @@ void rcdeviceReceive(timeUs_t currentTimeUs) case RCDEVICE_STATE_WAITING_COMMAND: requestParserContext.request.command = c; // there is no payload for RCDEVICE_PROTOCOL_COMMAND_REQUEST_FC_ATTITUDE, skip to waiting crc step - if (requestParserContext.request.command == RCDEVICE_PROTOCOL_COMMAND_REQUEST_FC_ATTITUDE) { + if (requestParserContext.request.command == RCDEVICE_PROTOCOL_COMMAND_REQUEST_FC_ATTITUDE) { requestParserContext.state = RCDEVICE_STATE_WAITING_CRC; } else { // for now, only RCDEVICE_PROTOCOL_COMMAND_REQUEST_FC_ATTITUDE support, so reset the state to waiting header. diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c index 8661c6f7b2..ae6942fdaa 100644 --- a/src/main/io/usb_cdc_hid.c +++ b/src/main/io/usb_cdc_hid.c @@ -103,7 +103,7 @@ void sendRcDataToHid(void) #endif } -bool cdcDeviceIsMayBeActive() +bool cdcDeviceIsMayBeActive(void) { return usbDevConfig()->type == COMPOSITE && usbIsConnected() && (getBatteryState() == BATTERY_NOT_PRESENT || batteryConfig()->voltageMeterSource == VOLTAGE_METER_NONE); } diff --git a/src/main/io/vtx_msp.c b/src/main/io/vtx_msp.c index 55402c06e6..11264300f7 100644 --- a/src/main/io/vtx_msp.c +++ b/src/main/io/vtx_msp.c @@ -354,7 +354,7 @@ static const vtxVTable_t mspVTable = { .serializeCustomDeviceStatus = NULL, }; -bool vtxMspInit() +bool vtxMspInit(void) { // don't bother setting up this device if we don't have MSP vtx enabled const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_MSP); diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 562eb30319..f2abcbdc2d 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -250,7 +250,7 @@ static void trampResetReceiver(void) } // returns completed response code or 0 -static char trampReceive() +static char trampReceive(void) { if (!trampSerialPort) { return 0; @@ -688,12 +688,12 @@ bool vtxTrampInit(void) return true; } -uint16_t vtxTrampGetCurrentActualPower() +uint16_t vtxTrampGetCurrentActualPower(void) { return trampCurActPower; } -uint16_t vtxTrampGetCurrentTemp() +uint16_t vtxTrampGetCurrentTemp(void) { return trampCurTemp; } diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 1528f16f25..ba85d706fe 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -1155,7 +1155,7 @@ void osdProcessStats2(timeUs_t currentTimeUs) #endif } -void osdProcessStats3() +void osdProcessStats3(void) { #if defined(USE_ACC) if (sensors(SENSOR_ACC) diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index 0fdac451be..dbe95ce295 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -1852,12 +1852,12 @@ static void osdDrawSingleElementBackground(displayPort_t *osdDisplayPort, uint8_ static uint8_t activeElement = 0; -uint8_t osdGetActiveElement() +uint8_t osdGetActiveElement(void) { return activeElement; } -uint8_t osdGetActiveElementCount() +uint8_t osdGetActiveElementCount(void) { return activeOsdElementCount; } @@ -1907,7 +1907,7 @@ void osdElementsInit(bool backgroundLayerFlag) pt1FilterInit(&batteryEfficiencyFilt, pt1FilterGain(EFFICIENCY_CUTOFF_HZ, 1.0f / osdConfig()->framerate_hz)); } -void osdSyncBlink() +void osdSyncBlink(void) { static int blinkCount = 0; diff --git a/src/main/rx/cc2500_frsky_shared.c b/src/main/rx/cc2500_frsky_shared.c index a54406ef3e..8c08625a7e 100644 --- a/src/main/rx/cc2500_frsky_shared.c +++ b/src/main/rx/cc2500_frsky_shared.c @@ -154,7 +154,7 @@ const cc2500RegisterConfigElement_t cc2500FrskyXLbtV2Config[] = { CC2500_08_PKTCTRL0, 0x05 }, }; -static void initialise() +static void initialise(void) { rxSpiStartupSpeed(); diff --git a/src/main/rx/cc2500_redpine.c b/src/main/rx/cc2500_redpine.c index 2a8ad0a97d..84895389cc 100644 --- a/src/main/rx/cc2500_redpine.c +++ b/src/main/rx/cc2500_redpine.c @@ -167,7 +167,7 @@ const cc2500RegisterConfigElement_t cc2500RedPineConfig[] = { CC2500_3E_PATABLE, 0xFF } }; -static void initialise() +static void initialise(void) { cc2500Reset(); diff --git a/src/main/rx/cc2500_sfhss.c b/src/main/rx/cc2500_sfhss.c index ffaee6ef76..640dd646d7 100644 --- a/src/main/rx/cc2500_sfhss.c +++ b/src/main/rx/cc2500_sfhss.c @@ -125,7 +125,7 @@ const cc2500RegisterConfigElement_t cc2500SfhssConfigPart2[] = { CC2500_3E_PATABLE, 0xFF } }; -static void initialise() +static void initialise(void) { cc2500Reset(); diff --git a/src/main/rx/expresslrs.c b/src/main/rx/expresslrs.c index 3bde6d77c0..196277fa96 100644 --- a/src/main/rx/expresslrs.c +++ b/src/main/rx/expresslrs.c @@ -301,7 +301,7 @@ static uint8_t minLqForChaos(void) return interval * ((interval * numfhss + 99) / (interval * numfhss)); } -static bool domainIsTeam24() +static bool domainIsTeam24(void) { const elrsFreqDomain_e domain = rxExpressLrsSpiConfig()->domain; return (domain == ISM2400) || (domain == CE2400); diff --git a/src/main/rx/ghst.c b/src/main/rx/ghst.c index ba3466b283..2dc65ccc7b 100644 --- a/src/main/rx/ghst.c +++ b/src/main/rx/ghst.c @@ -144,7 +144,7 @@ STATIC_UNIT_TESTED uint8_t ghstFrameCRC(const ghstFrame_t *const pGhstFrame) return crc; } -static void rxSwapFrameBuffers() +static void rxSwapFrameBuffers(void) { ghstFrame_t *const tmp = ghstIncomingFrame; ghstIncomingFrame = ghstValidatedFrame; @@ -392,7 +392,7 @@ STATIC_UNIT_TESTED float ghstReadRawRC(const rxRuntimeState_t *rxRuntimeState, u } // UART idle detected (inter-packet) -static void ghstIdle() +static void ghstIdle(void) { if (ghstTransmittingTelemetry) { ghstTransmittingTelemetry = false; diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index a1ece1c100..873cb9751d 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -325,7 +325,7 @@ static bool spektrumProcessFrame(const rxRuntimeState_t *rxRuntimeState) return true; } -bool srxlTelemetryBufferEmpty() +bool srxlTelemetryBufferEmpty(void) { if (telemetryBufLen == 0) { return true; diff --git a/src/main/rx/srxl2.c b/src/main/rx/srxl2.c index d1969dd726..8caf68e1fd 100644 --- a/src/main/rx/srxl2.c +++ b/src/main/rx/srxl2.c @@ -302,7 +302,7 @@ static void srxl2DataReceive(uint16_t character, void *data) } } -static void srxl2Idle() +static void srxl2Idle(void) { if (transmittingTelemetry) { // Transmitting telemetry triggers idle interrupt as well. We dont want to change buffers then transmittingTelemetry = false; diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index de947c8783..95a598ad8c 100644 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -271,25 +271,25 @@ timeDelta_t getTaskDeltaTimeUs(taskId_e taskId) } // Called by tasks executing what are known to be short states -void schedulerIgnoreTaskStateTime() +void schedulerIgnoreTaskStateTime(void) { ignoreCurrentTaskExecRate = true; ignoreCurrentTaskExecTime = true; } // Called by tasks with state machines to only count one state as determining rate -void schedulerIgnoreTaskExecRate() +void schedulerIgnoreTaskExecRate(void) { ignoreCurrentTaskExecRate = true; } // Called by tasks without state machines executing in what is known to be a shorter time than peak -void schedulerIgnoreTaskExecTime() +void schedulerIgnoreTaskExecTime(void) { ignoreCurrentTaskExecTime = true; } -bool schedulerGetIgnoreTaskExecTime() +bool schedulerGetIgnoreTaskExecTime(void) { return ignoreCurrentTaskExecTime; } @@ -365,7 +365,7 @@ FAST_CODE void schedulerSetNextStateTime(timeDelta_t nextStateTime) taskNextStateTime = nextStateTime; } -FAST_CODE timeDelta_t schedulerGetNextStateTime() +FAST_CODE timeDelta_t schedulerGetNextStateTime(void) { return currentTask->anticipatedExecutionTime >> TASK_EXEC_TIME_SHIFT; } diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index a9cb63db73..67d295912d 100644 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -236,7 +236,7 @@ void schedulerResetTaskStatistics(taskId_e taskId); void schedulerResetTaskMaxExecutionTime(taskId_e taskId); void schedulerResetCheckFunctionMaxExecutionTime(void); void schedulerSetNextStateTime(timeDelta_t nextStateTime); -timeDelta_t schedulerGetNextStateTime(); +timeDelta_t schedulerGetNextStateTime(void); void schedulerInit(void); void scheduler(void); timeUs_t schedulerExecuteTask(task_t *selectedTask, timeUs_t currentTimeUs); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index db3f94496c..15d5f2465d 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -569,7 +569,7 @@ int32_t getMAhDrawn(void) } #ifdef USE_BATTERY_CONTINUE -bool hasUsedMAh() +bool hasUsedMAh(void) { return batteryConfig()->isBatteryContinueEnabled && !(ARMING_FLAG(ARMED) || ARMING_FLAG(WAS_EVER_ARMED)) && (getBatteryState() == BATTERY_OK) diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 11ac3a4e69..aa33e3318a 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -122,7 +122,7 @@ int32_t getAmperageLatest(void); int32_t getMAhDrawn(void); float getWhDrawn(void); #ifdef USE_BATTERY_CONTINUE -bool hasUsedMAh(); +bool hasUsedMAh(void); void setMAhDrawn(uint32_t mAhDrawn); #endif diff --git a/src/main/sensors/gyro_init.c b/src/main/sensors/gyro_init.c index 92239e147a..5479d5b262 100644 --- a/src/main/sensors/gyro_init.c +++ b/src/main/sensors/gyro_init.c @@ -205,7 +205,7 @@ static bool gyroInitLowpassFilterLpf(int slot, int type, uint16_t lpfHz, uint32_ } #ifdef USE_DYN_LPF -static void dynLpfFilterInit() +static void dynLpfFilterInit(void) { if (gyroConfig()->gyro_lpf1_dyn_min_hz > 0) { switch (gyroConfig()->gyro_lpf1_type) { diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index 79dd466c9d..cbdce29269 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -230,7 +230,7 @@ void rangefinderUpdate(void) } } -bool isSurfaceAltitudeValid() +bool isSurfaceAltitudeValid(void) { /* diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index f9c6a06b02..0a550430a1 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -80,7 +80,7 @@ int lockMainPID(void) #define RAD2DEG (180.0 / M_PI) #define ACC_SCALE (256 / 9.80665) #define GYRO_SCALE (16.4) -void sendMotorUpdate() +void sendMotorUpdate(void) { udpSend(&pwmLink, &pwmPkt, sizeof(servo_packet)); } @@ -293,28 +293,28 @@ void indicateFailure(failureMode_e mode, int repeatCount) // Time part // Thanks ArduPilot -uint64_t nanos64_real() +uint64_t nanos64_real(void) { struct timespec ts; clock_gettime(CLOCK_MONOTONIC, &ts); return (ts.tv_sec*1e9 + ts.tv_nsec) - (start_time.tv_sec*1e9 + start_time.tv_nsec); } -uint64_t micros64_real() +uint64_t micros64_real(void) { struct timespec ts; clock_gettime(CLOCK_MONOTONIC, &ts); return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - (start_time.tv_sec + (start_time.tv_nsec*1.0e-9))); } -uint64_t millis64_real() +uint64_t millis64_real(void) { struct timespec ts; clock_gettime(CLOCK_MONOTONIC, &ts); return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - (start_time.tv_sec + (start_time.tv_nsec*1.0e-9))); } -uint64_t micros64() +uint64_t micros64(void) { static uint64_t last = 0; static uint64_t out = 0; @@ -327,7 +327,7 @@ uint64_t micros64() // return micros64_real(); } -uint64_t millis64() +uint64_t millis64(void) { static uint64_t last = 0; static uint64_t out = 0; diff --git a/src/main/telemetry/ghst.c b/src/main/telemetry/ghst.c index 74a3c0e19c..d23ab62e34 100644 --- a/src/main/telemetry/ghst.c +++ b/src/main/telemetry/ghst.c @@ -219,7 +219,7 @@ static uint8_t ghstSchedule[GHST_SCHEDULE_COUNT_MAX]; static bool mspReplyPending; -void ghstScheduleMspResponse() +void ghstScheduleMspResponse(void) { mspReplyPending = true; } diff --git a/src/main/telemetry/ghst.h b/src/main/telemetry/ghst.h index f8ac703bc6..ece839ae7f 100644 --- a/src/main/telemetry/ghst.h +++ b/src/main/telemetry/ghst.h @@ -34,5 +34,5 @@ void setGhstTelemetryState(bool state); void handleGhstTelemetry(timeUs_t currentTimeUs); #if defined(USE_MSP_OVER_TELEMETRY) -void ghstScheduleMspResponse(); +void ghstScheduleMspResponse(void); #endif diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index d572aae97e..5474fc49df 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -254,20 +254,18 @@ static inline void updateAlarmBatteryStatus(HOTT_EAM_MSG_t *hottEAMMessage) { if (shouldTriggerBatteryAlarmNow()) { lastHottAlarmSoundTime = millis(); - const batteryState_e voltageState = getVoltageState(); - const batteryState_e consumptionState = getConsumptionState(); + const batteryState_e voltageState = getVoltageState(); + const batteryState_e consumptionState = getConsumptionState(); if (voltageState == BATTERY_WARNING || voltageState == BATTERY_CRITICAL) { hottEAMMessage->warning_beeps = 0x10; hottEAMMessage->alarm_invers1 = HOTT_EAM_ALARM1_FLAG_BATTERY_1; - } - else if (consumptionState == BATTERY_WARNING || consumptionState == BATTERY_CRITICAL) { + } else if (consumptionState == BATTERY_WARNING || consumptionState == BATTERY_CRITICAL) { hottEAMMessage->warning_beeps = 0x16; hottEAMMessage->alarm_invers1 = HOTT_EAM_ALARM1_FLAG_MAH; - } - else { + } else { hottEAMMessage->warning_beeps = HOTT_EAM_ALARM1_FLAG_NONE; hottEAMMessage->alarm_invers1 = HOTT_EAM_ALARM1_FLAG_NONE; - } + } } } @@ -462,7 +460,7 @@ static void hottPrepareMessages(void) } #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS) -static void hottTextmodeStart() +static void hottTextmodeStart(void) { // Increase menu speed taskInfo_t taskInfo; @@ -474,7 +472,7 @@ static void hottTextmodeStart() txDelayUs = HOTT_TEXTMODE_TX_DELAY_US; } -static void hottTextmodeStop() +static void hottTextmodeStop(void) { // Set back to avoid slow down of the FC if (telemetryTaskPeriod > 0) { @@ -486,17 +484,17 @@ static void hottTextmodeStop() txDelayUs = HOTT_TX_DELAY_US; } -bool hottTextmodeIsAlive() +bool hottTextmodeIsAlive(void) { return textmodeIsAlive; } -void hottTextmodeGrab() +void hottTextmodeGrab(void) { hottTextModeMessage.esc = HOTT_EAM_SENSOR_TEXT_ID; } -void hottTextmodeExit() +void hottTextmodeExit(void) { hottTextModeMessage.esc = HOTT_TEXTMODE_ESC; } diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index 48e0c98a1e..c3705bdfba 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -177,7 +177,7 @@ static uint8_t getSensorLength(uint8_t sensorType) return IBUS_2BYTE_SESNSOR; } -static uint8_t transmitIbusPacket() +static uint8_t transmitIbusPacket(void) { unsigned frameLength = sendBuffer[0]; if (frameLength == INVALID_IBUS_ADDRESS) { @@ -209,12 +209,12 @@ static void setIbusSensorType(ibusAddress_t address) sendBuffer[3] = sensorLength; } -static uint16_t getVoltage() +static uint16_t getVoltage(void) { return (telemetryConfig()->report_cell_voltage ? getBatteryAverageCellVoltage() : getBatteryVoltage()); } -static uint16_t getTemperature() +static uint16_t getTemperature(void) { uint16_t temperature = gyroGetTemperature() * 10; #if defined(USE_BARO) @@ -226,7 +226,7 @@ static uint16_t getTemperature() } -static uint16_t getFuel() +static uint16_t getFuel(void) { uint16_t fuel = 0; if (batteryConfig()->batteryCapacity > 0) { @@ -237,7 +237,7 @@ static uint16_t getFuel() return fuel; } -static uint16_t getRPM() +static uint16_t getRPM(void) { uint16_t rpm = 0; if (ARMING_FLAG(ARMED)) { @@ -250,7 +250,7 @@ static uint16_t getRPM() return rpm; } -static uint16_t getMode() +static uint16_t getMode(void) { uint16_t flightMode = 1; //Acro if (FLIGHT_MODE(ANGLE_MODE)) { diff --git a/src/test/unit/arming_prevention_unittest.cc b/src/test/unit/arming_prevention_unittest.cc index 41c5510525..42ebb7e0f7 100644 --- a/src/test/unit/arming_prevention_unittest.cc +++ b/src/test/unit/arming_prevention_unittest.cc @@ -1011,7 +1011,7 @@ TEST(ArmingPreventionTest, Paralyze) // expect EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXVTXPITMODE)); EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXBEEPERON)); - + // given // try exiting paralyze mode and ensure arming and pit mode are still disabled rcData[AUX2] = 1000; @@ -1098,7 +1098,7 @@ extern "C" { float scaleRangef(float, float, float, float, float) { return 0.0f; } bool crashRecoveryModeActive(void) { return false; } int32_t getEstimatedAltitudeCm(void) { return 0; } - bool gpsIsHealthy() { return false; } + bool gpsIsHealthy(void) { return false; } float getCosTiltAngle(void) { return 0.0f; } void pidSetItermReset(bool) {} void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {} diff --git a/src/test/unit/link_quality_unittest.cc b/src/test/unit/link_quality_unittest.cc index b6482213a0..c6474a2f86 100644 --- a/src/test/unit/link_quality_unittest.cc +++ b/src/test/unit/link_quality_unittest.cc @@ -514,7 +514,7 @@ extern "C" { void failsafeOnValidDataReceived(void) { } void failsafeOnValidDataFailed(void) { } void pinioBoxTaskControl(void) { } - bool taskUpdateRxMainInProgress() { return true; } + bool taskUpdateRxMainInProgress(void) { return true; } void schedulerIgnoreTaskStateTime(void) { } void schedulerIgnoreTaskExecRate(void) { } bool schedulerGetIgnoreTaskExecTime() { return false; } diff --git a/src/test/unit/pid_unittest.cc b/src/test/unit/pid_unittest.cc index b537041efb..e720e19599 100644 --- a/src/test/unit/pid_unittest.cc +++ b/src/test/unit/pid_unittest.cc @@ -79,7 +79,7 @@ extern "C" { float getMotorMixRange(void) { return simulatedMotorMixRange; } float getSetpointRate(int axis) { return simulatedSetpointRate[axis]; } - bool isAirmodeActivated() { return simulatedAirmodeEnabled; } + bool isAirmodeActivated(void) { return simulatedAirmodeEnabled; } float getRcDeflectionAbs(int axis) { return fabsf(simulatedRcDeflection[axis]); } void systemBeep(bool) { } bool gyroOverflowDetected(void) { return false; } diff --git a/src/test/unit/rx_ranges_unittest.cc b/src/test/unit/rx_ranges_unittest.cc index 17edee3729..0cb82a2db4 100644 --- a/src/test/unit/rx_ranges_unittest.cc +++ b/src/test/unit/rx_ranges_unittest.cc @@ -113,7 +113,7 @@ void failsafeOnRxSuspend(uint32_t ) {} void failsafeOnRxResume(void) {} bool failsafeIsActive(void) { return false; } bool failsafeIsReceivingRxData(void) { return true; } -bool taskUpdateRxMainInProgress() { return true; } +bool taskUpdateRxMainInProgress(void) { return true; } void setArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } void unsetArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } uint16_t flightModeFlags = 0; diff --git a/src/test/unit/rx_rx_unittest.cc b/src/test/unit/rx_rx_unittest.cc index 898436c903..a53605825f 100644 --- a/src/test/unit/rx_rx_unittest.cc +++ b/src/test/unit/rx_rx_unittest.cc @@ -245,7 +245,7 @@ extern "C" { void rxPwmInit(const rxConfig_t *, rxRuntimeState_t *) {} void setArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } void unsetArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } - bool taskUpdateRxMainInProgress() { return true; } + bool taskUpdateRxMainInProgress(void) { return true; } float pt1FilterGain(float f_cut, float dT) { UNUSED(f_cut);