diff --git a/mk/config.mk b/mk/config.mk index 95c4d585f0..edd101b6d2 100644 --- a/mk/config.mk +++ b/mk/config.mk @@ -34,19 +34,17 @@ CONFIG_REVISION := $(shell git -C $(CONFIG_DIR) log -1 --format="%h") CONFIG_REVISION_DEFINE := -D'__CONFIG_REVISION__="$(CONFIG_REVISION)"' endif -TARGET := $(shell grep " FC_TARGET_MCU" $(CONFIG_HEADER_FILE) | awk '{print $$3}' ) -HSE_VALUE_MHZ := $(shell grep " SYSTEM_HSE_MHZ" $(CONFIG_HEADER_FILE) | awk '{print $$3}' ) +HSE_VALUE_MHZ := $(shell sed -E -n "/^\s*#\s*define\s+SYSTEM_HSE_MHZ\s+([0-9]+).*/s//\1/p" $(CONFIG_HEADER_FILE)) ifneq ($(HSE_VALUE_MHZ),) HSE_VALUE := $(shell echo $$(( $(HSE_VALUE_MHZ) * 1000000 )) ) endif -GYRO_DEFINE := $(shell grep " USE_GYRO_" $(CONFIG_HEADER_FILE) | awk '{print $$2}' ) - +TARGET := $(shell sed -E -n "/^\s*#\s*define\s+FC_TARGET_MCU\s+(\w+).*/s//\1/p" $(CONFIG_HEADER_FILE)) ifeq ($(TARGET),) $(error No TARGET identified. Is the $(CONFIG_HEADER_FILE) valid for $(CONFIG)?) endif -EXST_ADJUST_VMA := $(shell grep " FC_VMA_ADDRESS" $(CONFIG_HEADER_FILE) | awk '{print $$3}' ) +EXST_ADJUST_VMA := $(shell sed -E -n "/^\s*#\s*define\s+FC_VMA_ADDRESS\s+((0[xX])?[[:xdigit:]]+).*/s//\1/p" $(CONFIG_HEADER_FILE)) ifneq ($(EXST_ADJUST_VMA),) EXST = yes endif diff --git a/src/config b/src/config index be3155b97a..5e33fe422e 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit be3155b97a9d33fb34e181c15de891f6f72bef5d +Subproject commit 5e33fe422e2c1fb095db84508a9e3ebb465a80a4 diff --git a/src/main/build/debug_pin.c b/src/main/build/debug_pin.c index c3017a00f0..eb070f369f 100644 --- a/src/main/build/debug_pin.c +++ b/src/main/build/debug_pin.c @@ -20,13 +20,13 @@ #include "platform.h" +#include "debug_pin.h" + #ifdef USE_DEBUG_PIN #include "drivers/io.h" #include "drivers/io_impl.h" -#include "debug_pin.h" - typedef struct dbgPinState_s { GPIO_TypeDef *gpio; uint32_t setBSRR; diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index cb8c116594..a619f06a83 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -339,31 +339,37 @@ static void cliWriterFlush(void) cliWriterFlushInternal(cliWriter); } -void cliPrint(const char *str) +#ifdef USE_CLI_DEBUG_PRINT +#define CLI_DEBUG_EXPORT /* empty */ +#else +#define CLI_DEBUG_EXPORT static +#endif + +CLI_DEBUG_EXPORT void cliPrint(const char *str) { cliPrintInternal(cliWriter, str); } -void cliPrintLinefeed(void) +CLI_DEBUG_EXPORT void cliPrintLinefeed(void) { cliPrint("\r\n"); } -void cliPrintLine(const char *str) +CLI_DEBUG_EXPORT void cliPrintLine(const char *str) { cliPrint(str); cliPrintLinefeed(); } -#ifdef MINIMAL_CLI -#define cliPrintHashLine(str) -#else static void cliPrintHashLine(const char *str) { +#ifndef MINIMAL_CLI cliPrint("\r\n# "); cliPrintLine(str); -} +#else + UNUSED(str); #endif +} static void cliPutp(void *p, char ch) { @@ -415,7 +421,7 @@ static bool cliDefaultPrintLinef(dumpFlags_t dumpMask, bool equalsDefault, const } } -void cliPrintf(const char *format, ...) +CLI_DEBUG_EXPORT void cliPrintf(const char *format, ...) { va_list va; va_start(va, format); @@ -423,7 +429,7 @@ void cliPrintf(const char *format, ...) va_end(va); } -void cliPrintLinef(const char *format, ...) +CLI_DEBUG_EXPORT void cliPrintLinef(const char *format, ...) { va_list va; va_start(va, format); @@ -3228,7 +3234,7 @@ static void cliManufacturerId(const char *cmdName, char *cmdline) } #if defined(USE_SIGNATURE) -static void writeSignature(char *signatureStr, uint8_t *signature) +static void writeSignature(char *signatureStr, const uint8_t *signature) { for (unsigned i = 0; i < SIGNATURE_LENGTH; i++) { tfp_sprintf(&signatureStr[2 * i], "%02x", signature[i]); @@ -4269,7 +4275,7 @@ static bool prepareSave(void) return true; } -bool tryPrepareSave(const char *cmdName) +static bool tryPrepareSave(const char *cmdName) { bool success = prepareSave(); #if defined(USE_CLI_BATCH) @@ -4443,7 +4449,7 @@ static uint8_t getWordLength(const char *bufBegin, const char *bufEnd) return bufEnd - bufBegin; } -uint16_t cliGetSettingIndex(const char *name, size_t length) +STATIC_UNIT_TESTED uint16_t cliGetSettingIndex(const char *name, size_t length) { for (uint32_t i = 0; i < valueTableEntryCount; i++) { const char *settingName = valueTable[i].name; diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index d9ba4c1455..82df9227dd 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -1083,7 +1083,7 @@ const clivalue_t valueTable[] = { { PARAM_NAME_IMU_SMALL_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) }, { PARAM_NAME_IMU_PROCESS_DENOM, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 4 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_process_denom) }, #ifdef USE_MAG - { PARAM_NAME_IMU_MAG_DECLINATION, VAR_INT16 | MASTER_VALUE, .config.minmaxUnsigned = { -300, 300 }, PG_IMU_CONFIG, offsetof(imuConfig_t, mag_declination) }, + { PARAM_NAME_IMU_MAG_DECLINATION, VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_IMU_CONFIG, offsetof(imuConfig_t, mag_declination) }, #endif // PG_ARMING_CONFIG diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index af8f84622f..24c0daab01 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -1375,7 +1375,7 @@ void cmsSetExternKey(cms_key_e extKey) externKey = extKey; } -uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount) +static uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount) { uint16_t ret = 0; diff --git a/src/main/cms/cms_menu_vtx_msp.c b/src/main/cms/cms_menu_vtx_msp.c index 6f1cd42b63..288887f767 100644 --- a/src/main/cms/cms_menu_vtx_msp.c +++ b/src/main/cms/cms_menu_vtx_msp.c @@ -41,6 +41,8 @@ #include "io/vtx_msp.h" #include "io/vtx.h" +#include "cms_menu_vtx_msp.h" + char mspCmsStatusString[31] = "- -- ---- ----"; // m bc ffff tppp // 01234567890123 diff --git a/src/main/cms/cms_menu_vtx_smartaudio.h b/src/main/cms/cms_menu_vtx_smartaudio.h index 3140ffa3aa..7291660cdd 100644 --- a/src/main/cms/cms_menu_vtx_smartaudio.h +++ b/src/main/cms/cms_menu_vtx_smartaudio.h @@ -27,4 +27,4 @@ extern CMS_Menu cmsx_menuVtxSmartAudio; void saCmsUpdate(void); void saUpdateStatusString(void); -void saCmsResetOpmodel(); +void saCmsResetOpmodel(void); diff --git a/src/main/cms/cms_menu_vtx_tramp.c b/src/main/cms/cms_menu_vtx_tramp.c index c3a1f3a385..0a0cea8e4e 100644 --- a/src/main/cms/cms_menu_vtx_tramp.c +++ b/src/main/cms/cms_menu_vtx_tramp.c @@ -41,6 +41,8 @@ #include "io/vtx_tramp.h" #include "io/vtx.h" +#include "cms_menu_vtx_tramp.h" + char trampCmsStatusString[31] = "- -- ---- ----"; // m bc ffff tppp // 01234567890123 diff --git a/src/main/common/explog_approx.c b/src/main/common/explog_approx.c index b2eae4468e..ff50937801 100644 --- a/src/main/common/explog_approx.c +++ b/src/main/common/explog_approx.c @@ -32,6 +32,8 @@ Stripped down for BF use #include "platform.h" +#include "common/maths.h" + /* Workaround a lack of optimization in gcc */ float exp_cst1 = 2139095040.f; float exp_cst2 = 0.f; diff --git a/src/main/common/gps_conversion.c b/src/main/common/gps_conversion.c index 33fe1778f8..7b88e93aff 100644 --- a/src/main/common/gps_conversion.c +++ b/src/main/common/gps_conversion.c @@ -25,6 +25,8 @@ #include "platform.h" +#include "gps_conversion.h" + #ifdef USE_GPS #define DIGIT_TO_VAL(_x) (_x - '0') diff --git a/src/main/common/strtol.c b/src/main/common/strtol.c index 1d1e0413ff..f94f3fc38d 100644 --- a/src/main/common/strtol.c +++ b/src/main/common/strtol.c @@ -26,9 +26,11 @@ #include "common/utils.h" +#include "strtol.h" + #define _STRTO_ENDPTR 1 -unsigned long _strto_l(const char * str, char ** endptr, int base, int sflag) +static unsigned long _strto_l(const char * str, char ** endptr, int base, int sflag) { unsigned long number, cutoff; #if _STRTO_ENDPTR diff --git a/src/main/common/typeconversion.c b/src/main/common/typeconversion.c index 166339b300..1e2636c4b0 100644 --- a/src/main/common/typeconversion.c +++ b/src/main/common/typeconversion.c @@ -26,7 +26,9 @@ #include "platform.h" #include "build/build_config.h" -#include "maths.h" +#include "common/maths.h" + +#include "typeconversion.h" #ifdef REQUIRE_PRINTF_LONG_SUPPORT @@ -86,7 +88,7 @@ void i2a(int num, char *bf) ui2a(num, 10, 0, bf); } -int a2d(char ch) +static int a2d(char ch) { if (ch >= '0' && ch <= '9') return ch - '0'; diff --git a/src/main/common/utils.h b/src/main/common/utils.h index 3ec18bdd06..c23155cfa1 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -58,6 +58,9 @@ #define UNUSED(x) (void)(x) // Variables and parameters that are not used #endif +#define MAYBE_UNUSED __attribute__ ((unused)) +#define LOCAL_UNUSED_FUNCTION __attribute__ ((unused, deprecated ("function is marked as LOCAL_UNUSED_FUNCTION"))) + #define DISCARD(x) (void)(x) // To explicitly ignore result of x (usually an I/O register access). #ifndef __cplusplus diff --git a/src/main/config/config.c b/src/main/config/config.c index 002797cec0..16250fa3eb 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -217,7 +217,7 @@ static void validateAndFixConfig(void) #endif if (!isSerialConfigValid(serialConfigMutable())) { - pgResetFn_serialConfig(serialConfigMutable()); + PG_RESET(serialConfig); } #if defined(USE_GPS) diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index 83e2d79fa2..4b48a3914d 100644 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -87,7 +87,7 @@ typedef struct { } PG_PACKED packingTest_t; #if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) -MMFLASH_CODE bool loadEEPROMFromExternalFlash(void) +static MMFLASH_CODE bool loadEEPROMFromExternalFlash(void) { const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG); const flashGeometry_t *flashGeometry = flashGetGeometry(); diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index 206417d188..31260a0f96 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -267,7 +267,7 @@ extiCallbackRec_t bmi160IntCallbackRec; // Called in ISR context // Gyro read has just completed -busStatus_e bmi160Intcallback(uint32_t arg) +static busStatus_e bmi160Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; int32_t gyroDmaDuration = cmpTimeCycles(getCycleCounter(), gyro->gyroLastEXTI); @@ -281,7 +281,7 @@ busStatus_e bmi160Intcallback(uint32_t arg) return BUS_READY; } -void bmi160ExtiHandler(extiCallbackRec_t *cb) +static void bmi160ExtiHandler(extiCallbackRec_t *cb) { gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); extDevice_t *dev = &gyro->dev; @@ -440,7 +440,7 @@ static bool bmi160GyroRead(gyroDev_t *gyro) return true; } -void bmi160SpiGyroInit(gyroDev_t *gyro) +static void bmi160SpiGyroInit(gyroDev_t *gyro) { extDevice_t *dev = &gyro->dev; @@ -450,7 +450,7 @@ void bmi160SpiGyroInit(gyroDev_t *gyro) spiSetClkDivisor(dev, spiCalculateDivider(BMI160_MAX_SPI_CLK_HZ)); } -void bmi160SpiAccInit(accDev_t *acc) +static void bmi160SpiAccInit(accDev_t *acc) { acc->acc_1G = 512 * 8; } diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c index 79ab79077e..f13f39c75f 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -278,7 +278,7 @@ extiCallbackRec_t bmi270IntCallbackRec; */ // Called in ISR context // Gyro read has just completed -busStatus_e bmi270Intcallback(uint32_t arg) +static busStatus_e bmi270Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; int32_t gyroDmaDuration = cmpTimeCycles(getCycleCounter(), gyro->gyroLastEXTI); @@ -292,7 +292,7 @@ busStatus_e bmi270Intcallback(uint32_t arg) return BUS_READY; } -void bmi270ExtiHandler(extiCallbackRec_t *cb) +static void bmi270ExtiHandler(extiCallbackRec_t *cb) { gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); extDevice_t *dev = &gyro->dev; diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 7d87a00383..5e8e4cc574 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -40,6 +40,7 @@ #include "drivers/bus_spi.h" #include "drivers/exti.h" #include "drivers/io.h" +#include "drivers/pwm_output.h" #include "drivers/sensor.h" #include "drivers/time.h" diff --git a/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c b/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c index 21f33a7a35..c29aa85e68 100644 --- a/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c +++ b/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c @@ -856,7 +856,7 @@ uint8_t lsm6dsv16xSpiDetect(const extDevice_t *dev) return LSM6DSV16X_SPI; } -void lsm6dsv16xAccInit(accDev_t *acc) +static void lsm6dsv16xAccInit(accDev_t *acc) { // ±16G mode acc->acc_1G = 512 * 4; @@ -924,7 +924,7 @@ bool lsm6dsv16xSpiAccDetect(accDev_t *acc) return true; } -void lsm6dsv16xGyroInit(gyroDev_t *gyro) +static void lsm6dsv16xGyroInit(gyroDev_t *gyro) { const extDevice_t *dev = &gyro->dev; // Set default LPF1 filter bandwidth to be as close as possible to MPU6000's 250Hz cutoff @@ -1009,7 +1009,7 @@ void lsm6dsv16xGyroInit(gyroDev_t *gyro) mpuGyroInit(gyro); } -bool lsm6dsv16xGyroReadSPI(gyroDev_t *gyro) +static bool lsm6dsv16xGyroReadSPI(gyroDev_t *gyro) { int16_t *gyroData = (int16_t *)gyro->dev.rxBuf; switch (gyro->gyroModeSPI) { diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c index b94293758d..07f436c54d 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c @@ -100,7 +100,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro); #define MPU6000_REV_D9 0x59 #define MPU6000_REV_D10 0x5A -void mpu6000SpiGyroInit(gyroDev_t *gyro) +static void mpu6000SpiGyroInit(gyroDev_t *gyro) { extDevice_t *dev = &gyro->dev; @@ -121,7 +121,7 @@ void mpu6000SpiGyroInit(gyroDev_t *gyro) } } -void mpu6000SpiAccInit(accDev_t *acc) +static void mpu6000SpiAccInit(accDev_t *acc) { acc->acc_1G = 512 * 4; } diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c index eca0f03b6d..7ebc32b201 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c @@ -69,7 +69,7 @@ static bool mpu9250SpiSlowReadRegisterBuffer(const extDevice_t *dev, uint8_t reg return true; } -void mpu9250SpiGyroInit(gyroDev_t *gyro) +static void mpu9250SpiGyroInit(gyroDev_t *gyro) { extDevice_t *dev = &gyro->dev; @@ -86,7 +86,7 @@ void mpu9250SpiGyroInit(gyroDev_t *gyro) } } -void mpu9250SpiAccInit(accDev_t *acc) +static void mpu9250SpiAccInit(accDev_t *acc) { acc->acc_1G = 512 * 4; } diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index d9b337b45e..66baa5da9c 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -73,8 +73,10 @@ typedef struct adcTagMap_s { #define ADC_DEVICES_345 ((1 << ADCDEV_3)|(1 << ADCDEV_4)|(1 << ADCDEV_5)) typedef struct adcDevice_s { +#if !defined(SIMULATOR_BUILD) ADC_TypeDef* ADCx; rccPeriphTag_t rccADC; +#endif #if !defined(USE_DMA_SPEC) dmaResource_t* dmaResource; #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4) @@ -104,7 +106,9 @@ extern adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT]; extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT]; uint8_t adcChannelByTag(ioTag_t ioTag); +#if !defined(SIMULATOR_BUILD) ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance); +#endif bool adcVerifyPin(ioTag_t tag, ADCDevice device); // Marshall values in DMA instance/channel based order to adcChannel based order. diff --git a/src/main/drivers/barometer/barometer_bmp280.c b/src/main/drivers/barometer/barometer_bmp280.c index 4dc55468e5..efaaff941b 100644 --- a/src/main/drivers/barometer/barometer_bmp280.c +++ b/src/main/drivers/barometer/barometer_bmp280.c @@ -117,7 +117,7 @@ static bool bmp280GetUP(baroDev_t *baro); STATIC_UNIT_TESTED void bmp280Calculate(int32_t *pressure, int32_t *temperature); -void bmp280BusInit(const extDevice_t *dev) +static void bmp280BusInit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_BMP280 if (dev->bus->busType == BUS_TYPE_SPI) { @@ -131,7 +131,7 @@ void bmp280BusInit(const extDevice_t *dev) #endif } -void bmp280BusDeinit(const extDevice_t *dev) +static void bmp280BusDeinit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_BMP280 if (dev->bus->busType == BUS_TYPE_SPI) { diff --git a/src/main/drivers/barometer/barometer_bmp388.c b/src/main/drivers/barometer/barometer_bmp388.c index 6fa2e1efb7..a00c1fbccb 100644 --- a/src/main/drivers/barometer/barometer_bmp388.c +++ b/src/main/drivers/barometer/barometer_bmp388.c @@ -198,7 +198,7 @@ static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_ } } -void bmp388_extiHandler(extiCallbackRec_t* cb) +static void bmp388_extiHandler(extiCallbackRec_t* cb) { #ifdef DEBUG static uint32_t bmp388ExtiCallbackCounter = 0; @@ -212,7 +212,7 @@ void bmp388_extiHandler(extiCallbackRec_t* cb) bmp388ReadRegisterBuffer(&baro->dev, BMP388_INT_STATUS_REG, &intStatus, 1); } -void bmp388BusInit(const extDevice_t *dev) +static void bmp388BusInit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_BMP388 if (dev->bus->busType == BUS_TYPE_SPI) { @@ -226,7 +226,7 @@ void bmp388BusInit(const extDevice_t *dev) #endif } -void bmp388BusDeinit(const extDevice_t *dev) +static void bmp388BusDeinit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_BMP388 if (dev->bus->busType == BUS_TYPE_SPI) { @@ -237,7 +237,7 @@ void bmp388BusDeinit(const extDevice_t *dev) #endif } -bool bmp388BeginForcedMeasurement(const extDevice_t *dev) +static bool bmp388BeginForcedMeasurement(const extDevice_t *dev) { // enable pressure measurement, temperature measurement, set power mode and start sampling uint8_t mode = BMP388_MODE_FORCED << 4 | 1 << 1 | 1 << 0; diff --git a/src/main/drivers/barometer/barometer_lps.c b/src/main/drivers/barometer/barometer_lps.c index 021c784cfc..11591d32af 100644 --- a/src/main/drivers/barometer/barometer_lps.c +++ b/src/main/drivers/barometer/barometer_lps.c @@ -191,17 +191,17 @@ static uint32_t rawP = 0; static uint16_t rawT = 0; -bool lpsWriteCommand(const extDevice_t *dev, uint8_t cmd, uint8_t byte) +static bool lpsWriteCommand(const extDevice_t *dev, uint8_t cmd, uint8_t byte) { return spiWriteRegRB(dev, cmd, byte); } -bool lpsReadCommand(const extDevice_t *dev, uint8_t cmd, uint8_t *data, uint8_t len) +static bool lpsReadCommand(const extDevice_t *dev, uint8_t cmd, uint8_t *data, uint8_t len) { return spiReadRegMskBufRB(dev, cmd | 0x80 | 0x40, data, len); } -bool lpsWriteVerify(const extDevice_t *dev, uint8_t cmd, uint8_t byte) +static bool lpsWriteVerify(const extDevice_t *dev, uint8_t cmd, uint8_t byte) { uint8_t temp = 0xff; spiWriteReg(dev, cmd, byte); diff --git a/src/main/drivers/barometer/barometer_lps22df.c b/src/main/drivers/barometer/barometer_lps22df.c index 4ab3620e6c..c5e773943b 100644 --- a/src/main/drivers/barometer/barometer_lps22df.c +++ b/src/main/drivers/barometer/barometer_lps22df.c @@ -227,7 +227,7 @@ static bool lps22dfGetUP(baroDev_t *baro); STATIC_UNIT_TESTED void lps22dfCalculate(int32_t *pressure, int32_t *temperature); -void lps22dfBusInit(const extDevice_t *dev) +static void lps22dfBusInit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_LPS22DF if (dev->bus->busType == BUS_TYPE_SPI) { @@ -241,7 +241,7 @@ void lps22dfBusInit(const extDevice_t *dev) #endif } -void lps22dfBusDeinit(const extDevice_t *dev) +static void lps22dfBusDeinit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_LPS22DF if (dev->bus->busType == BUS_TYPE_SPI) { diff --git a/src/main/drivers/barometer/barometer_ms5611.c b/src/main/drivers/barometer/barometer_ms5611.c index 3223cde2c2..c301e9fc5f 100644 --- a/src/main/drivers/barometer/barometer_ms5611.c +++ b/src/main/drivers/barometer/barometer_ms5611.c @@ -62,7 +62,7 @@ static uint8_t ms5611_osr = CMD_ADC_4096; #define MS5611_DATA_FRAME_SIZE 3 static DMA_DATA_ZERO_INIT uint8_t sensor_data[MS5611_DATA_FRAME_SIZE]; -void ms5611BusInit(const extDevice_t *dev) +static void ms5611BusInit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_MS5611 if (dev->bus->busType == BUS_TYPE_SPI) { @@ -76,7 +76,7 @@ void ms5611BusInit(const extDevice_t *dev) #endif } -void ms5611BusDeinit(const extDevice_t *dev) +static void ms5611BusDeinit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_MS5611 if (dev->bus->busType == BUS_TYPE_SPI) { diff --git a/src/main/drivers/barometer/barometer_qmp6988.c b/src/main/drivers/barometer/barometer_qmp6988.c index 5887d8462f..6369891185 100644 --- a/src/main/drivers/barometer/barometer_qmp6988.c +++ b/src/main/drivers/barometer/barometer_qmp6988.c @@ -105,7 +105,7 @@ static bool qmp6988GetUP(baroDev_t *baro); STATIC_UNIT_TESTED void qmp6988Calculate(int32_t *pressure, int32_t *temperature); -void qmp6988BusInit(const extDevice_t *dev) +static void qmp6988BusInit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_QMP6988 if (dev->bus->busType == BUS_TYPE_SPI) { @@ -119,7 +119,7 @@ void qmp6988BusInit(const extDevice_t *dev) #endif } -void qmp6988BusDeinit(const extDevice_t *dev) +static void qmp6988BusDeinit(const extDevice_t *dev) { #ifdef USE_BARO_SPI_QMP6988 if (dev->bus->busType == BUS_TYPE_SPI) { diff --git a/src/main/drivers/bus_i2c_busdev.c b/src/main/drivers/bus_i2c_busdev.c index 720a898ac9..c2e7e9d74a 100644 --- a/src/main/drivers/bus_i2c_busdev.c +++ b/src/main/drivers/bus_i2c_busdev.c @@ -28,6 +28,7 @@ #include "drivers/bus.h" #include "drivers/bus_i2c.h" +#include "drivers/bus_i2c_busdev.h" static uint8_t i2cRegisteredDeviceCount = 0; diff --git a/src/main/drivers/bus_i2c_busdev.h b/src/main/drivers/bus_i2c_busdev.h index 1f2149ff70..4d3d638c70 100644 --- a/src/main/drivers/bus_i2c_busdev.h +++ b/src/main/drivers/bus_i2c_busdev.h @@ -27,5 +27,5 @@ uint8_t i2cBusReadRegister(const extDevice_t *dev, uint8_t reg); bool i2cBusReadRegisterBufferStart(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length); bool i2cBusBusy(const extDevice_t *dev, bool *error); // Associate a device with an I2C bus -bool i2cBusSetInstance(const extDevice_t *dev, uint32_t device); +bool i2cBusSetInstance(extDevice_t *dev, uint32_t device); void i2cBusDeviceRegister(const extDevice_t *dev); diff --git a/src/main/drivers/bus_i2c_timing.c b/src/main/drivers/bus_i2c_timing.c index ed3b959cac..f196fd385f 100644 --- a/src/main/drivers/bus_i2c_timing.c +++ b/src/main/drivers/bus_i2c_timing.c @@ -22,6 +22,8 @@ #include "platform.h" +#include "bus_i2c_timing.h" + /* * Compute SCLDEL, SDADEL, SCLH and SCLL for TIMINGR register according to reference manuals. */ diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index b355cbaab3..5723b6202c 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -68,7 +68,7 @@ void spiPreinit(void); bool spiInit(SPIDevice device); // Called after all devices are initialised to enable SPI DMA where streams are available. -void spiInitBusDMA(); +void spiInitBusDMA(void); SPIDevice spiDeviceByInstance(const SPI_TypeDef *instance); SPI_TypeDef *spiInstanceByDevice(SPIDevice device); diff --git a/src/main/drivers/bus_spi_config.c b/src/main/drivers/bus_spi_config.c index d27605dcca..0fd6999dbe 100644 --- a/src/main/drivers/bus_spi_config.c +++ b/src/main/drivers/bus_spi_config.c @@ -25,6 +25,7 @@ #ifdef USE_SPI +#include "drivers/bus_spi.h" #include "drivers/io.h" #include "drivers/resource.h" #include "drivers/system.h" diff --git a/src/main/drivers/compass/compass_ak8963.c b/src/main/drivers/compass/compass_ak8963.c index e744deb276..14796f9c0b 100644 --- a/src/main/drivers/compass/compass_ak8963.c +++ b/src/main/drivers/compass/compass_ak8963.c @@ -372,7 +372,7 @@ static bool ak8963Init(magDev_t *mag) return true; } -void ak8963BusInit(const extDevice_t *dev) +static void ak8963BusInit(const extDevice_t *dev) { switch (dev->bus->busType) { #ifdef USE_MAG_AK8963 @@ -409,7 +409,7 @@ void ak8963BusInit(const extDevice_t *dev) } } -void ak8963BusDeInit(const extDevice_t *dev) +static void ak8963BusDeInit(const extDevice_t *dev) { switch (dev->bus->busType) { #ifdef USE_MAG_AK8963 diff --git a/src/main/drivers/compass/compass_lis2mdl.c b/src/main/drivers/compass/compass_lis2mdl.c index 80fb4b87ea..f270b3ca29 100644 --- a/src/main/drivers/compass/compass_lis2mdl.c +++ b/src/main/drivers/compass/compass_lis2mdl.c @@ -35,6 +35,8 @@ #include "drivers/time.h" #include "common/axis.h" +#include "compass_lis2mdl.h" + #define LIS2MDL_MAG_I2C_ADDRESS 0x1E // LIS2MDL Registers diff --git a/src/main/drivers/compass/compass_lis3mdl.c b/src/main/drivers/compass/compass_lis3mdl.c index 530275c40f..ec67056e21 100644 --- a/src/main/drivers/compass/compass_lis3mdl.c +++ b/src/main/drivers/compass/compass_lis3mdl.c @@ -31,6 +31,8 @@ #include "drivers/time.h" #include "common/axis.h" +#include "compass_lis3mdl.h" + #define LIS3MDL_MAG_I2C_ADDRESS 0x1E #define LIS3MDL_DEVICE_ID 0x3D diff --git a/src/main/drivers/dshot.c b/src/main/drivers/dshot.c index d433240539..54bfe2a4ed 100644 --- a/src/main/drivers/dshot.c +++ b/src/main/drivers/dshot.c @@ -29,6 +29,8 @@ #include "platform.h" +#include "dshot.h" + #ifdef USE_DSHOT #include "build/debug.h" @@ -50,8 +52,6 @@ #include "rx/rx.h" -#include "dshot.h" - #define ERPM_PER_LSB 100.0f FAST_DATA_ZERO_INIT uint8_t dshotMotorCount = 0; diff --git a/src/main/drivers/dshot_bitbang.h b/src/main/drivers/dshot_bitbang.h index b791240815..115d3de906 100644 --- a/src/main/drivers/dshot_bitbang.h +++ b/src/main/drivers/dshot_bitbang.h @@ -39,6 +39,6 @@ typedef enum { } dshotBitbangStatus_e; bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig); -dshotBitbangStatus_e dshotBitbangGetStatus(); +dshotBitbangStatus_e dshotBitbangGetStatus(void); const timerHardware_t *dshotBitbangTimerGetAllocatedByNumberAndChannel(int8_t timerNumber, uint16_t timerChannel); const resourceOwner_t *dshotBitbangTimerGetOwner(const timerHardware_t *timer); diff --git a/src/main/drivers/flash/flash.c b/src/main/drivers/flash/flash.c index 8e48f07a92..a91cfd19dc 100644 --- a/src/main/drivers/flash/flash.c +++ b/src/main/drivers/flash/flash.c @@ -360,7 +360,7 @@ void flashPreinit(const flashConfig_t *flashConfig) ioPreinitByTag(flashConfig->csTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH); } -bool flashDeviceInit(const flashConfig_t *flashConfig) +static bool flashDeviceInit(const flashConfig_t *flashConfig) { bool haveFlash = false; diff --git a/src/main/drivers/flash/flash_m25p16.c b/src/main/drivers/flash/flash_m25p16.c index 8194ffd47e..1fcc66197e 100644 --- a/src/main/drivers/flash/flash_m25p16.c +++ b/src/main/drivers/flash/flash_m25p16.c @@ -248,7 +248,7 @@ bool m25p16_identify(flashDevice_t *fdevice, uint32_t jedecID) return true; } -void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +static void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { return; @@ -289,7 +289,7 @@ static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLon // Called in ISR context // A write enable has just been issued -busStatus_e m25p16_callbackWriteEnable(uint32_t arg) +static busStatus_e m25p16_callbackWriteEnable(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; @@ -301,7 +301,7 @@ busStatus_e m25p16_callbackWriteEnable(uint32_t arg) // Called in ISR context // Write operation has just completed -busStatus_e m25p16_callbackWriteComplete(uint32_t arg) +static busStatus_e m25p16_callbackWriteComplete(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; @@ -317,7 +317,7 @@ busStatus_e m25p16_callbackWriteComplete(uint32_t arg) // Called in ISR context // Check if the status was busy and if so repeat the poll -busStatus_e m25p16_callbackReady(uint32_t arg) +static busStatus_e m25p16_callbackReady(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; extDevice_t *dev = fdevice->io.handle.dev; diff --git a/src/main/drivers/flash/flash_w25m.c b/src/main/drivers/flash/flash_w25m.c index d0024e050f..4b6b8ea786 100644 --- a/src/main/drivers/flash/flash_w25m.c +++ b/src/main/drivers/flash/flash_w25m.c @@ -171,7 +171,7 @@ bool w25m_identify(flashDevice_t *fdevice, uint32_t jedecID) return true; } -void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +static void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) { w25m_dieSelect(fdevice->io.handle.dev, dieNumber); @@ -179,7 +179,7 @@ void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags) } } -void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address) +static void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address) { int dieNumber = address / dieSize; @@ -188,7 +188,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address) dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize); } -void w25m_eraseCompletely(flashDevice_t *fdevice) +static void w25m_eraseCompletely(flashDevice_t *fdevice) { for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) { w25m_dieSelect(fdevice->io.handle.dev, dieNumber); @@ -199,7 +199,7 @@ void w25m_eraseCompletely(flashDevice_t *fdevice) static uint32_t currentWriteAddress; static int currentWriteDie; -void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) +static void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) { currentWriteDie = address / dieSize; w25m_dieSelect(fdevice->io.handle.dev, currentWriteDie); @@ -207,21 +207,21 @@ void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*call dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], address, callback); } -uint32_t w25m_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) +static uint32_t w25m_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) { UNUSED(fdevice); return dieDevice[currentWriteDie].vTable->pageProgramContinue(&dieDevice[currentWriteDie], buffers, bufferSizes, bufferCount); } -void w25m_pageProgramFinish(flashDevice_t *fdevice) +static void w25m_pageProgramFinish(flashDevice_t *fdevice) { UNUSED(fdevice); dieDevice[currentWriteDie].vTable->pageProgramFinish(&dieDevice[currentWriteDie]); } -void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) +static void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) { w25m_pageProgramBegin(fdevice, address, callback); @@ -230,7 +230,7 @@ void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *d w25m_pageProgramFinish(fdevice); } -int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) +static int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) { int rlen; // remaining length int tlen; // transfer length for a round @@ -258,7 +258,7 @@ int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, ui return length; } -const flashGeometry_t* w25m_getGeometry(flashDevice_t *fdevice) +static const flashGeometry_t* w25m_getGeometry(flashDevice_t *fdevice) { return &fdevice->geometry; } diff --git a/src/main/drivers/flash/flash_w25n.c b/src/main/drivers/flash/flash_w25n.c index f91c87d70d..685b8fb66f 100644 --- a/src/main/drivers/flash/flash_w25n.c +++ b/src/main/drivers/flash/flash_w25n.c @@ -288,7 +288,7 @@ static void w25n_deviceReset(flashDevice_t *fdevice) w25n_writeRegister(io, W25N_CONF_REG, W25N_CONFIG_ECC_ENABLE|W25N_CONFIG_BUFFER_READ_MODE); } -bool w25n_isReady(flashDevice_t *fdevice) +static bool w25n_isReady(flashDevice_t *fdevice) { // If we're waiting on DMA completion, then SPI is busy if (fdevice->io.mode == FLASHIO_SPI) { @@ -372,7 +372,7 @@ bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID) static void w25n_deviceInit(flashDevice_t *flashdev); -void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +static void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { return; @@ -404,7 +404,7 @@ void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags) /** * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. */ -void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address) +static void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address) { w25n_waitForReady(fdevice); @@ -420,7 +420,7 @@ void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address) // W25N01G does not support full chip erase. // Call eraseSector repeatedly. -void w25n_eraseCompletely(flashDevice_t *fdevice) +static void w25n_eraseCompletely(flashDevice_t *fdevice) { for (uint32_t block = 0; block < fdevice->geometry.sectors; block++) { w25n_eraseSector(fdevice, W25N_BLOCK_TO_LINEAR(block)); @@ -537,7 +537,7 @@ bool bufferDirty = false; // Called in ISR context // Check if the status was busy and if so repeat the poll -busStatus_e w25n_callbackReady(uint32_t arg) +static busStatus_e w25n_callbackReady(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; extDevice_t *dev = fdevice->io.handle.dev; @@ -557,7 +557,7 @@ busStatus_e w25n_callbackReady(uint32_t arg) #ifdef USE_QUADSPI bool isProgramming = false; -void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) +static void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) { fdevice->callback = callback; @@ -579,7 +579,7 @@ void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*call } } -uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) +static uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) { if (bufferCount < 1) { fdevice->callback(0); @@ -612,7 +612,7 @@ uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffer static uint32_t currentPage = UINT32_MAX; -void w25n_pageProgramFinish(flashDevice_t *fdevice) +static void w25n_pageProgramFinish(flashDevice_t *fdevice) { if (bufferDirty && W25N_LINEAR_TO_COLUMN(programLoadAddress) == 0) { @@ -627,7 +627,7 @@ void w25n_pageProgramFinish(flashDevice_t *fdevice) } } #else -void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) +static void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) { fdevice->callback = callback; fdevice->currentWriteAddress = address; @@ -638,7 +638,7 @@ static uint32_t currentPage = UINT32_MAX; // Called in ISR context // A write enable has just been issued -busStatus_e w25n_callbackWriteEnable(uint32_t arg) +static busStatus_e w25n_callbackWriteEnable(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; @@ -650,7 +650,7 @@ busStatus_e w25n_callbackWriteEnable(uint32_t arg) // Called in ISR context // Write operation has just completed -busStatus_e w25n_callbackWriteComplete(uint32_t arg) +static busStatus_e w25n_callbackWriteComplete(uint32_t arg) { flashDevice_t *fdevice = (flashDevice_t *)arg; @@ -663,7 +663,7 @@ busStatus_e w25n_callbackWriteComplete(uint32_t arg) return BUS_READY; } -uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) +static uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) { if (bufferCount < 1) { fdevice->callback(0); @@ -771,7 +771,7 @@ uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffer return fdevice->callbackArg; } -void w25n_pageProgramFinish(flashDevice_t *fdevice) +static void w25n_pageProgramFinish(flashDevice_t *fdevice) { UNUSED(fdevice); } @@ -793,14 +793,14 @@ void w25n_pageProgramFinish(flashDevice_t *fdevice) * break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call. */ -void w25n_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) +static void w25n_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) { w25n_pageProgramBegin(fdevice, address, callback); w25n_pageProgramContinue(fdevice, &data, &length, 1); w25n_pageProgramFinish(fdevice); } -void w25n_flush(flashDevice_t *fdevice) +static void w25n_flush(flashDevice_t *fdevice) { if (bufferDirty) { currentPage = W25N_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written @@ -811,7 +811,7 @@ void w25n_flush(flashDevice_t *fdevice) } } -void w25n_addError(uint32_t address, uint8_t code) +static void w25n_addError(uint32_t address, uint8_t code) { UNUSED(address); UNUSED(code); @@ -837,7 +837,7 @@ void w25n_addError(uint32_t address, uint8_t code) // (3) Issue READ_DATA on column address. // (4) Return transferLength. -int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) +static int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) { uint32_t targetPage = W25N_LINEAR_TO_PAGE(address); @@ -928,7 +928,7 @@ int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, ui return transferLength; } -int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length) +LOCAL_UNUSED_FUNCTION static int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length) { if (!w25n_waitForReady(fdevice)) { @@ -981,7 +981,7 @@ int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b * * Can be called before calling w25n_init() (the result would have totalSize = 0). */ -const flashGeometry_t* w25n_getGeometry(flashDevice_t *fdevice) +static const flashGeometry_t* w25n_getGeometry(flashDevice_t *fdevice) { return &fdevice->geometry; } @@ -1010,7 +1010,7 @@ typedef volatile struct cb_context_s { // Called in ISR context // Read of BBLUT entry has just completed -busStatus_e w25n_readBBLUTCallback(uint32_t arg) +static busStatus_e w25n_readBBLUTCallback(uint32_t arg) { cb_context_t *cb_context = (cb_context_t *)arg; flashDevice_t *fdevice = cb_context->fdevice; @@ -1027,7 +1027,7 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg) return BUS_READY; // All done } -void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) +LOCAL_UNUSED_FUNCTION static void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) { cb_context_t cb_context; uint8_t in[4]; @@ -1078,7 +1078,7 @@ void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) #endif } -void w25n_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba) +LOCAL_UNUSED_FUNCTION static void w25n_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba) { w25n_waitForReady(fdevice); diff --git a/src/main/drivers/flash/flash_w25q128fv.c b/src/main/drivers/flash/flash_w25q128fv.c index 4205c5a8de..59e282003e 100644 --- a/src/main/drivers/flash/flash_w25q128fv.c +++ b/src/main/drivers/flash/flash_w25q128fv.c @@ -228,7 +228,7 @@ static void w25q128fv_deviceReset(flashDevice_t *fdevice) #endif } -MMFLASH_CODE bool w25q128fv_isReady(flashDevice_t *fdevice) +static MMFLASH_CODE bool w25q128fv_isReady(flashDevice_t *fdevice) { uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG); @@ -246,7 +246,7 @@ MMFLASH_CODE static bool w25q128fv_isWritable(flashDevice_t *fdevice) return writable; } -MMFLASH_CODE bool w25q128fv_hasTimedOut(flashDevice_t *fdevice) +static MMFLASH_CODE bool w25q128fv_hasTimedOut(flashDevice_t *fdevice) { uint32_t nowMs = microsISR() / 1000; if (cmp32(nowMs, fdevice->timeoutAt) >= 0) { @@ -335,7 +335,7 @@ MMFLASH_CODE_NOINLINE bool w25q128fv_identify(flashDevice_t *fdevice, uint32_t j return true; } -void w25q128fv_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +static void w25q128fv_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { return; @@ -437,7 +437,7 @@ MMFLASH_CODE static void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t w25q128fv_pageProgramFinish(fdevice); } -MMFLASH_CODE void w25q128fv_flush(flashDevice_t *fdevice) +static MMFLASH_CODE void w25q128fv_flush(flashDevice_t *fdevice) { UNUSED(fdevice); } @@ -473,7 +473,7 @@ MMFLASH_CODE static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t add return length; } -const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice) +static const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice) { return &fdevice->geometry; } diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index fcd8cb4c79..7c8dc12203 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -31,10 +31,6 @@ struct ioPortDef_s { rccPeriphTag_t rcc; }; -#if defined(SITL) -const struct ioPortDef_s ioPortDefs[] = { 0 }; -#endif - ioRec_t* IO_Rec(IO_t io) { return io; @@ -52,10 +48,12 @@ uint16_t IO_Pin(IO_t io) return ioRec->pin; } +#if defined(STM32F4) || defined(APM32F4) int IO_EXTI_PortSourceGPIO(IO_t io) { return IO_GPIOPortIdx(io); } +#endif int IO_GPIO_PortSource(IO_t io) { @@ -71,10 +69,12 @@ int IO_GPIOPinIdx(IO_t io) return 31 - __builtin_clz(IO_Pin(io)); } +#if defined(STM32F4) || defined(APM32F4) int IO_EXTI_PinSource(IO_t io) { return IO_GPIOPinIdx(io); } +#endif int IO_GPIO_PinSource(IO_t io) { diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 6c15b34dcf..e0be78bd97 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -23,10 +23,12 @@ #include "pg/pg_ids.h" #include "drivers/io.h" -#include "io_impl.h" +#include "drivers/io_impl.h" #include "light_led.h" +#if !(defined(UNIT_TEST) || defined(USE_VIRTUAL_LED)) + PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0); static IO_t leds[STATUS_LED_NUMBER]; @@ -91,3 +93,4 @@ void ledSet(int led, bool on) const bool inverted = (1 << (led)) & ledInversion; IOWrite(leds[led], on ? inverted : !inverted); } +#endif diff --git a/src/main/drivers/light_led.h b/src/main/drivers/light_led.h index 13834f93a4..0543f0478d 100644 --- a/src/main/drivers/light_led.h +++ b/src/main/drivers/light_led.h @@ -31,8 +31,6 @@ typedef struct statusLedConfig_s { uint8_t inversion; } statusLedConfig_t; -PG_DECLARE(statusLedConfig_t, statusLedConfig); - // Helpful macros #if defined(UNIT_TEST) || defined(USE_VIRTUAL_LED) @@ -50,6 +48,8 @@ PG_DECLARE(statusLedConfig_t, statusLedConfig); #else +PG_DECLARE(statusLedConfig_t, statusLedConfig); + #define LED0_TOGGLE ledToggle(0) #define LED0_OFF ledSet(0, false) #define LED0_ON ledSet(0, true) diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 42341a4ff1..f5963daae6 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -281,7 +281,7 @@ static void max7456ClearLayer(displayPortLayer_e layer) memset(getLayerBuffer(layer), 0x20, VIDEO_BUFFER_CHARS_PAL); } -void max7456ReInit(void) +static void max7456ReInit(void) { uint8_t srdata = 0; @@ -612,7 +612,7 @@ bool max7456ReInitIfRequired(bool forceStallCheck) } // Called in ISR context -busStatus_e max7456_callbackReady(uint32_t arg) +static busStatus_e max7456_callbackReady(uint32_t arg) { UNUSED(arg); diff --git a/src/main/drivers/pin_pull_up_down.h b/src/main/drivers/pin_pull_up_down.h index 36a458c5db..c259a11c60 100644 --- a/src/main/drivers/pin_pull_up_down.h +++ b/src/main/drivers/pin_pull_up_down.h @@ -28,4 +28,4 @@ struct pinPullUpDownConfig_s; -void pinPullupPulldownInit(); +void pinPullupPulldownInit(void); diff --git a/src/main/drivers/rangefinder/rangefinder_hcsr04.c b/src/main/drivers/rangefinder/rangefinder_hcsr04.c index a8192c08ca..72d3e201b8 100644 --- a/src/main/drivers/rangefinder/rangefinder_hcsr04.c +++ b/src/main/drivers/rangefinder/rangefinder_hcsr04.c @@ -61,7 +61,7 @@ static IO_t echoIO; static IO_t triggerIO; #if !defined(UNIT_TEST) -void hcsr04_extiHandler(extiCallbackRec_t* cb) +static void hcsr04_extiHandler(extiCallbackRec_t* cb) { UNUSED(cb); @@ -81,7 +81,7 @@ void hcsr04_extiHandler(extiCallbackRec_t* cb) } #endif -void hcsr04_init(rangefinderDev_t *dev) +static void hcsr04_init(rangefinderDev_t *dev) { UNUSED(dev); } @@ -93,7 +93,7 @@ void hcsr04_init(rangefinderDev_t *dev) * Called periodically by the scheduler * Measurement reading is done asynchronously, using interrupt */ -void hcsr04_start_reading(void) +static void hcsr04_start_reading(void) { #if !defined(UNIT_TEST) IOHi(triggerIO); @@ -102,7 +102,7 @@ void hcsr04_start_reading(void) #endif } -void hcsr04_update(rangefinderDev_t *dev) +static void hcsr04_update(rangefinderDev_t *dev) { UNUSED(dev); @@ -136,7 +136,7 @@ void hcsr04_update(rangefinderDev_t *dev) /** * Get the distance that was measured by the last pulse, in centimeters. */ -int32_t hcsr04_get_distance(rangefinderDev_t *dev) +static int32_t hcsr04_get_distance(rangefinderDev_t *dev) { UNUSED(dev); diff --git a/src/main/drivers/rangefinder/rangefinder_lidarmt.c b/src/main/drivers/rangefinder/rangefinder_lidarmt.c index 8204547d1a..bf9e57dad5 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidarmt.c +++ b/src/main/drivers/rangefinder/rangefinder_lidarmt.c @@ -115,7 +115,7 @@ const MTRangefinderConfig* getMTRangefinderDeviceConf(rangefinderType_e mtRangef return NULL; } -const mtRangefinderData_t * getMTRangefinderData(void) { +static const mtRangefinderData_t * getMTRangefinderData(void) { return &rfSensorData; } diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.c b/src/main/drivers/rangefinder/rangefinder_lidartf.c index 76e97d052b..07d0c330ed 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.c +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.c @@ -128,7 +128,7 @@ static void lidarTFSendCommand(void) } } -void lidarTFInit(rangefinderDev_t *dev) +static void lidarTFInit(rangefinderDev_t *dev) { UNUSED(dev); @@ -136,7 +136,7 @@ void lidarTFInit(rangefinderDev_t *dev) tfReceivePosition = 0; } -void lidarTFUpdate(rangefinderDev_t *dev) +static void lidarTFUpdate(rangefinderDev_t *dev) { UNUSED(dev); static timeMs_t lastFrameReceivedMs = 0; @@ -232,7 +232,7 @@ void lidarTFUpdate(rangefinderDev_t *dev) // Return most recent device output in cm -int32_t lidarTFGetDistance(rangefinderDev_t *dev) +static int32_t lidarTFGetDistance(rangefinderDev_t *dev) { UNUSED(dev); diff --git a/src/main/drivers/rx/rx_cc2500.c b/src/main/drivers/rx/rx_cc2500.c index 487b2eb780..db3b6e14b0 100644 --- a/src/main/drivers/rx/rx_cc2500.c +++ b/src/main/drivers/rx/rx_cc2500.c @@ -48,12 +48,12 @@ void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len) rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len); } -void cc2500WriteCommand(uint8_t command, uint8_t data) +static void cc2500WriteCommand(uint8_t command, uint8_t data) { rxSpiWriteCommand(command, data); } -void cc2500WriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length) +static void cc2500WriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length) { rxSpiWriteCommandMulti(command, data, length); } diff --git a/src/main/drivers/rx/rx_pwm.c b/src/main/drivers/rx/rx_pwm.c index c42c7d3c67..5042c73445 100644 --- a/src/main/drivers/rx/rx_pwm.c +++ b/src/main/drivers/rx/rx_pwm.c @@ -125,12 +125,15 @@ void resetPPMDataReceivedState(void) #define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4 -#ifdef DEBUG_PPM_ISR typedef enum { SOURCE_OVERFLOW = 0, SOURCE_EDGE = 1 } eventSource_e; +static void ppmISREvent(eventSource_e source, uint32_t capture); + +#ifdef DEBUG_PPM_ISR + typedef struct ppmISREvent_s { uint32_t capture; eventSource_e source; @@ -139,7 +142,7 @@ typedef struct ppmISREvent_s { static ppmISREvent_t ppmEvents[20]; static uint8_t ppmEventIndex = 0; -void ppmISREvent(eventSource_e source, uint32_t capture) +static void ppmISREvent(eventSource_e source, uint32_t capture) { ppmEventIndex = (ppmEventIndex + 1) % ARRAYLEN(ppmEvents); @@ -147,7 +150,7 @@ void ppmISREvent(eventSource_e source, uint32_t capture) ppmEvents[ppmEventIndex].capture = capture; } #else -void ppmISREvent(eventSource_e source, uint32_t capture) {} +static void ppmISREvent(eventSource_e source, uint32_t capture) {} #endif static void ppmResetDevice(void) @@ -403,7 +406,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig) #define FIRST_PWM_PORT 0 #ifdef USE_PWM_OUTPUT -void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer) +static void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer) { pwmOutputPort_t *motors = pwmGetMotors(); for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) { diff --git a/src/main/drivers/rx/rx_spi.c b/src/main/drivers/rx/rx_spi.c index e21dd78fcd..05c6e803ea 100644 --- a/src/main/drivers/rx/rx_spi.c +++ b/src/main/drivers/rx/rx_spi.c @@ -75,7 +75,7 @@ void rxSpiDevicePreinit(const rxSpiConfig_t *rxSpiConfig) ioPreinitByTag(rxSpiConfig->csnTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH); } -void rxSpiExtiHandler(extiCallbackRec_t* callback) +static void rxSpiExtiHandler(extiCallbackRec_t* callback) { UNUSED(callback); diff --git a/src/main/drivers/rx/rx_spi.h b/src/main/drivers/rx/rx_spi.h index ab51a760cc..92e1ab0dcc 100644 --- a/src/main/drivers/rx/rx_spi.h +++ b/src/main/drivers/rx/rx_spi.h @@ -35,8 +35,8 @@ extDevice_t *rxSpiGetDevice(void); void rxSpiDevicePreinit(const struct rxSpiConfig_s *rxSpiConfig); bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig); void rxSpiSetNormalSpeedMhz(uint32_t mhz); -void rxSpiNormalSpeed(); -void rxSpiStartupSpeed(); +void rxSpiNormalSpeed(void); +void rxSpiStartupSpeed(void); void rxSpiDmaEnable(bool enable); uint8_t rxSpiTransferByte(uint8_t data); void rxSpiWriteByte(uint8_t data); diff --git a/src/main/drivers/rx/rx_sx1280.c b/src/main/drivers/rx/rx_sx1280.c index 38d1ff1b6c..1e3c4b05f9 100644 --- a/src/main/drivers/rx/rx_sx1280.c +++ b/src/main/drivers/rx/rx_sx1280.c @@ -591,7 +591,7 @@ void sx1280GetLastPacketStats(int8_t *rssi, int8_t *snr) } } -void sx1280DoFHSS(void) +LOCAL_UNUSED_FUNCTION static void sx1280DoFHSS(void) { return; } diff --git a/src/main/drivers/rx/rx_sx1280.h b/src/main/drivers/rx/rx_sx1280.h index 11d38cd609..5dc496a374 100644 --- a/src/main/drivers/rx/rx_sx1280.h +++ b/src/main/drivers/rx/rx_sx1280.h @@ -353,7 +353,7 @@ void sx1280SetDioIrqParams(const uint16_t irqMask, const uint16_t dio1Mask, cons void sx1280ClearIrqStatus(const uint16_t irqMask); void sx1280GetIrqReason(void); -void sx1280HandleFromTock(); +void sx1280HandleFromTock(void); void sx1280TransmitData(const uint8_t *data, const uint8_t length); void sx1280ReceiveData(uint8_t *data, const uint8_t length); diff --git a/src/main/drivers/sdcard_sdio_baremetal.c b/src/main/drivers/sdcard_sdio_baremetal.c index 3342e3bc14..772223cd30 100644 --- a/src/main/drivers/sdcard_sdio_baremetal.c +++ b/src/main/drivers/sdcard_sdio_baremetal.c @@ -48,7 +48,7 @@ uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4))); uint32_t cacheCount = 0; -void cache_write(uint8_t *buffer) +static void cache_write(uint8_t *buffer) { if (cacheCount == sizeof(writeCache)) { // Prevents overflow @@ -58,12 +58,12 @@ void cache_write(uint8_t *buffer) cacheCount += 512; } -uint16_t cache_getCount(void) +static uint16_t cache_getCount(void) { return (cacheCount / 512); } -void cache_reset(void) +static void cache_reset(void) { cacheCount = 0; } diff --git a/src/main/drivers/sdcard_spi.c b/src/main/drivers/sdcard_spi.c index 40c9a646b1..b09698df91 100644 --- a/src/main/drivers/sdcard_spi.c +++ b/src/main/drivers/sdcard_spi.c @@ -112,7 +112,7 @@ static void sdcard_reset(void) // Called in ISR context // Wait until idle indicated by a read value of SDCARD_IDLE_TOKEN -busStatus_e sdcard_callbackIdle(uint32_t arg) +static busStatus_e sdcard_callbackIdle(uint32_t arg) { sdcard_t *sdcard = (sdcard_t *)arg; extDevice_t *dev = &sdcard->dev; @@ -135,7 +135,7 @@ busStatus_e sdcard_callbackIdle(uint32_t arg) // Called in ISR context // Wait until idle is no longer indicated by a read value of SDCARD_IDLE_TOKEN -busStatus_e sdcard_callbackNotIdle(uint32_t arg) +static busStatus_e sdcard_callbackNotIdle(uint32_t arg) { sdcard_t *sdcard = (sdcard_t *)arg; extDevice_t *dev = &sdcard->dev; @@ -340,7 +340,7 @@ typedef enum { /// Called in ISR context // Wait until the arrival of the SDCARD_SINGLE_BLOCK_READ_START_TOKEN token -busStatus_e sdcard_callbackNotIdleDataBlock(uint32_t arg) +static busStatus_e sdcard_callbackNotIdleDataBlock(uint32_t arg) { sdcard_t *sdcard = (sdcard_t *)arg; extDevice_t *dev = &sdcard->dev; @@ -536,7 +536,7 @@ static bool sdcard_checkInitDone(void) return status == 0x00; } -void sdcardSpi_preinit(const sdcardConfig_t *config) +static void sdcardSpi_preinit(const sdcardConfig_t *config) { ioPreinitByTag(config->chipSelectTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH); } diff --git a/src/main/drivers/sdio.h b/src/main/drivers/sdio.h index cd60548123..2464e1594d 100644 --- a/src/main/drivers/sdio.h +++ b/src/main/drivers/sdio.h @@ -30,6 +30,6 @@ typedef enum { #define SDIODEV_COUNT 2 #if defined(STM32H7) -void sdioPinConfigure(); +void sdioPinConfigure(void); void SDIO_GPIO_Init(void); #endif diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index 1dc1a39146..f5f21bb74e 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -73,7 +73,7 @@ typedef enum { #define CTRL_LINE_STATE_RTS (1 << 1) typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app -typedef void (*serialIdleCallbackPtr)(); +typedef void (*serialIdleCallbackPtr)(void); typedef struct serialPort_s { diff --git a/src/main/drivers/serial_impl.h b/src/main/drivers/serial_impl.h index 029eed4147..f9d8f03c3b 100644 --- a/src/main/drivers/serial_impl.h +++ b/src/main/drivers/serial_impl.h @@ -23,6 +23,9 @@ #include +#include "drivers/resource.h" +#include "io/serial.h" + /* * common functions related to serial port implementation */ diff --git a/src/main/drivers/serial_pinconfig.c b/src/main/drivers/serial_pinconfig.c index d72c8dbbff..97ce26bb58 100644 --- a/src/main/drivers/serial_pinconfig.c +++ b/src/main/drivers/serial_pinconfig.c @@ -24,7 +24,7 @@ #include "platform.h" -#if defined(USE_UART) || defined(USE_LPUART) || defined(USE_SOFTSERIAL) +#if SERIAL_TRAIT_PIN_CONFIG #include "build/build_config.h" diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index dbaf5d75e6..13fe8bb682 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -195,7 +195,7 @@ static void resetBuffers(softSerial_t *softSerial) softSerial->port.txBufferHead = 0; } -softSerial_t* softSerialFromIdentifier(serialPortIdentifier_e identifier) +static softSerial_t* softSerialFromIdentifier(serialPortIdentifier_e identifier) { if (identifier >= SERIAL_PORT_SOFTSERIAL_FIRST && identifier < SERIAL_PORT_SOFTSERIAL_FIRST + SERIAL_SOFTSERIAL_COUNT) { return &softSerialPorts[identifier - SERIAL_PORT_SOFTSERIAL_FIRST]; @@ -330,7 +330,7 @@ serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCal * Serial Engine */ -void processTxState(softSerial_t *softSerial) +static void processTxState(softSerial_t *softSerial) { if (!softSerial->isTransmittingData) { if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) { @@ -387,7 +387,7 @@ enum { LEADING }; -void applyChangedBits(softSerial_t *softSerial) +static void applyChangedBits(softSerial_t *softSerial) { if (softSerial->rxEdge == TRAILING) { for (unsigned bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex; bitToSet++) { @@ -396,7 +396,7 @@ void applyChangedBits(softSerial_t *softSerial) } } -void prepareForNextRxByte(softSerial_t *softSerial) +static void prepareForNextRxByte(softSerial_t *softSerial) { // prepare for next byte softSerial->rxBitIndex = 0; @@ -411,7 +411,7 @@ void prepareForNextRxByte(softSerial_t *softSerial) #define STOP_BIT_MASK (1 << 0) #define START_BIT_MASK (1 << (RX_TOTAL_BITS - 1)) -void extractAndStoreRxByte(softSerial_t *softSerial) +static void extractAndStoreRxByte(softSerial_t *softSerial) { if ((softSerial->port.mode & MODE_RX) == 0) { return; @@ -435,7 +435,7 @@ void extractAndStoreRxByte(softSerial_t *softSerial) } } -void processRxState(softSerial_t *softSerial) +static void processRxState(softSerial_t *softSerial) { if (softSerial->isSearchingForStartBit) { return; @@ -597,7 +597,7 @@ void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) serialTimerConfigureTimebase(softSerial->timerHardware, baudRate); } -void softSerialSetMode(serialPort_t *instance, portMode_e mode) +static void softSerialSetMode(serialPort_t *instance, portMode_e mode) { instance->mode = mode; } diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index bc6f6d37ff..a922cc7674 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -158,7 +158,7 @@ serialPort_t *serTcpOpen(serialPortIdentifier_e identifier, serialReceiveCallbac return (serialPort_t *)s; } -uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) +static uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) { tcpPort_t *s = (tcpPort_t*)instance; uint32_t count; @@ -173,7 +173,7 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) return count; } -uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) +static uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) { tcpPort_t *s = (tcpPort_t*)instance; uint32_t bytesUsed; @@ -190,7 +190,7 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) return bytesFree; } -bool isTcpTransmitBufferEmpty(const serialPort_t *instance) +static bool isTcpTransmitBufferEmpty(const serialPort_t *instance) { tcpPort_t *s = (tcpPort_t *)instance; pthread_mutex_lock(&s->txLock); @@ -199,7 +199,7 @@ bool isTcpTransmitBufferEmpty(const serialPort_t *instance) return isEmpty; } -uint8_t tcpRead(serialPort_t *instance) +static uint8_t tcpRead(serialPort_t *instance) { uint8_t ch; tcpPort_t *s = (tcpPort_t *)instance; @@ -216,7 +216,7 @@ uint8_t tcpRead(serialPort_t *instance) return ch; } -void tcpWrite(serialPort_t *instance, uint8_t ch) +static void tcpWrite(serialPort_t *instance, uint8_t ch) { tcpPort_t *s = (tcpPort_t *)instance; pthread_mutex_lock(&s->txLock); diff --git a/src/main/drivers/vtx_rtc6705_soft_spi.c b/src/main/drivers/vtx_rtc6705_soft_spi.c index 6adc3606f9..d16ff2348d 100644 --- a/src/main/drivers/vtx_rtc6705_soft_spi.c +++ b/src/main/drivers/vtx_rtc6705_soft_spi.c @@ -31,6 +31,8 @@ #include "drivers/time.h" #include "drivers/vtx_rtc6705.h" +#include "vtx_rtc6705_soft_spi.h" + #define DP_5G_MASK 0x7000 #define PA5G_BS_MASK 0x0E00 #define PA5G_PW_MASK 0x0180 diff --git a/src/main/drivers/vtx_table.c b/src/main/drivers/vtx_table.c index 5e29e5a548..b97e93c59c 100644 --- a/src/main/drivers/vtx_table.c +++ b/src/main/drivers/vtx_table.c @@ -159,7 +159,7 @@ void vtxTableConfigClearChannels(vtxTableConfig_t *config, int band, int channel } // Clear a channel name for "channel" -void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel) +static void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel) { tfp_sprintf(config->channelNames[channel], "%d", channel + 1); } diff --git a/src/main/fc/board_info.c b/src/main/fc/board_info.c index 729b93d84a..f66ab3acca 100644 --- a/src/main/fc/board_info.c +++ b/src/main/fc/board_info.c @@ -25,6 +25,7 @@ #if defined(USE_BOARD_INFO) #include "pg/board.h" +#include "board_info.h" #if !defined(BOARD_NAME) static bool boardInformationSet = false; diff --git a/src/main/fc/board_info.h b/src/main/fc/board_info.h index b855d50c59..c7ec54fa27 100644 --- a/src/main/fc/board_info.h +++ b/src/main/fc/board_info.h @@ -22,16 +22,16 @@ void initBoardInformation(void); -char *getBoardName(void); -char *getManufacturerId(void); +const char *getBoardName(void); +const char *getManufacturerId(void); bool boardInformationIsSet(void); -bool setBoardName(char *newBoardName); -bool setManufacturerId(char *newManufacturerId); +bool setBoardName(const char *newBoardName); +bool setManufacturerId(const char *newManufacturerId); bool persistBoardInformation(void); -uint8_t * getSignature(void); +const uint8_t * getSignature(void); bool signatureIsSet(void); -bool setSignature(uint8_t *newSignature); +bool setSignature(const uint8_t *newSignature); bool persistSignature(void); diff --git a/src/main/fc/core.c b/src/main/fc/core.c index 75bd3100d0..fc123e52a5 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -197,7 +197,7 @@ static bool isCalibrating(void) } #ifdef USE_LAUNCH_CONTROL -bool canUseLaunchControl(void) +static bool canUseLaunchControl(void) { if (!isFixedWing() && !isUsingSticksForArming() // require switch arming for safety @@ -212,7 +212,7 @@ bool canUseLaunchControl(void) #endif #ifdef USE_DSHOT -void setMotorSpinDirection(uint8_t spinDirection) +static void setMotorSpinDirection(uint8_t spinDirection) { if (isMotorProtocolDshot() && !featureIsEnabled(FEATURE_3D)) { dshotCommandWrite(ALL_MOTORS, getMotorCount(), spinDirection, DSHOT_CMD_TYPE_INLINE); diff --git a/src/main/fc/core.h b/src/main/fc/core.h index a7aefac35a..45988459e1 100644 --- a/src/main/fc/core.h +++ b/src/main/fc/core.h @@ -91,10 +91,10 @@ int8_t calculateThrottlePercent(void); uint8_t calculateThrottlePercentAbs(void); bool areSticksActive(uint8_t stickPercentLimit); void runawayTakeoffTemporaryDisable(uint8_t disableFlag); -bool wasThrottleRaised(); +bool wasThrottleRaised(void); timeUs_t getLastDisarmTimeUs(void); -bool isTryingToArm(); -void resetTryingToArm(); +bool isTryingToArm(void); +void resetTryingToArm(void); void subTaskTelemetryPollSensors(timeUs_t currentTimeUs); diff --git a/src/main/fc/gps_lap_timer.c b/src/main/fc/gps_lap_timer.c index dc13c930d5..438d64cfdd 100644 --- a/src/main/fc/gps_lap_timer.c +++ b/src/main/fc/gps_lap_timer.c @@ -69,7 +69,7 @@ void gpsLapTimerStartSetGate(void) gpsLapTimerData.numberOfSetReadings = 0; } -void gpsLapTimerProcessSettingGate(void) +static void gpsLapTimerProcessSettingGate(void) { if (gpsLapTimerData.numberOfSetReadings < MAX_GATE_SET_READINGS){ gateSetLatReadings += gpsSol.llh.lat; diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 8e1646411b..bc0726fbbc 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -521,22 +521,7 @@ void init(void) uartPinConfigure(serialPinConfig()); #endif -#if defined(AVOID_UART1_FOR_PWM_PPM) -# define SERIALPORT_TO_AVOID SERIAL_PORT_USART1 -#elif defined(AVOID_UART2_FOR_PWM_PPM) -# define SERIALPORT_TO_AVOID SERIAL_PORT_USART2 -#elif defined(AVOID_UART3_FOR_PWM_PPM) -# define SERIALPORT_TO_AVOID SERIAL_PORT_USART3 -#endif - { - serialPortIdentifier_e serialPortToAvoid = SERIAL_PORT_NONE; -#if defined(SERIALPORT_TO_AVOID) - if (featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) { - serialPortToAvoid = SERIALPORT_TO_AVOID; - } -#endif - serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), serialPortToAvoid); - } + serialInit(featureIsEnabled(FEATURE_SOFTSERIAL)); mixerInit(mixerConfig()->mixerMode); @@ -545,20 +530,24 @@ void init(void) * may send spurious pulses to esc's causing their early initialization. Also ppm * receiver may share timer with motors so motors MUST be initialized here. */ motorDevInit(getMotorCount()); + // TODO: add check here that motors actually initialised correctly systemState |= SYSTEM_STATE_MOTORS_READY; #endif - if (0) {} + do { #if defined(USE_RX_PPM) - else if (featureIsEnabled(FEATURE_RX_PPM)) { - ppmRxInit(ppmConfig()); - } + if (featureIsEnabled(FEATURE_RX_PPM)) { + ppmRxInit(ppmConfig()); + break; + } #endif #if defined(USE_RX_PWM) - else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) { - pwmRxInit(pwmConfig()); - } + if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) { + pwmRxInit(pwmConfig()); + break; + } #endif + } while (false); #ifdef USE_BEEPER beeperInit(beeperDevConfig()); diff --git a/src/main/fc/rc.c b/src/main/fc/rc.c index e2485640a5..80c284191a 100644 --- a/src/main/fc/rc.c +++ b/src/main/fc/rc.c @@ -166,7 +166,7 @@ STATIC_ASSERT(CONTROL_RATE_CONFIG_RATE_LIMIT_MAX <= (uint16_t)SETPOINT_RATE_LIMI #define RC_RATE_INCREMENTAL 14.54f -float applyBetaflightRates(const int axis, float rcCommandf, const float rcCommandfAbs) +static float applyBetaflightRates(const int axis, float rcCommandf, const float rcCommandfAbs) { if (currentControlRateProfile->rcExpo[axis]) { const float expof = currentControlRateProfile->rcExpo[axis] / 100.0f; @@ -186,7 +186,7 @@ float applyBetaflightRates(const int axis, float rcCommandf, const float rcComma return angleRate; } -float applyRaceFlightRates(const int axis, float rcCommandf, const float rcCommandfAbs) +static float applyRaceFlightRates(const int axis, float rcCommandf, const float rcCommandfAbs) { // -1.0 to 1.0 ranged and curved rcCommandf = ((1.0f + 0.01f * currentControlRateProfile->rcExpo[axis] * (rcCommandf * rcCommandf - 1.0f)) * rcCommandf); @@ -197,7 +197,7 @@ float applyRaceFlightRates(const int axis, float rcCommandf, const float rcComma return angleRate; } -float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs) +static float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs) { const float rcCurvef = currentControlRateProfile->rcExpo[axis] / 100.0f; @@ -208,7 +208,7 @@ float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs return kissAngle; } -float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs) +static float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs) { float expof = currentControlRateProfile->rcExpo[axis] / 100.0f; expof = rcCommandfAbs * (power5(rcCommandf) * expof + rcCommandf * (1 - expof)); @@ -220,7 +220,7 @@ float applyActualRates(const int axis, float rcCommandf, const float rcCommandfA return angleRate; } -float applyQuickRates(const int axis, float rcCommandf, const float rcCommandfAbs) +static float applyQuickRates(const int axis, float rcCommandf, const float rcCommandfAbs) { const uint16_t rcRate = currentControlRateProfile->rcRates[axis] * 2; const uint16_t maxDPS = MAX(currentControlRateProfile->rates[axis] * 10, rcRate); @@ -322,7 +322,7 @@ bool getRxRateValid(void) // Initialize or update the filters base on either the manually selected cutoff, or // the auto-calculated cutoff frequency based on detected rx frame rate. -FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothingData) +static FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothingData) { // in auto mode, calculate the RC smoothing cutoff from the smoothed Rx link frequency const uint16_t oldSetpointCutoff = smoothingData->setpointCutoffFrequency; @@ -518,7 +518,7 @@ static FAST_CODE void processRcSmoothingFilter(void) #endif // USE_RC_SMOOTHING_FILTER #ifdef USE_FEEDFORWARD -FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dynamics_index_t axis) +static FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dynamics_index_t axis) { const float rxInterval = currentRxIntervalUs * 1e-6f; // seconds float rxRate = currentRxRateHz; // 1e6f / currentRxIntervalUs; diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 52ffce90f4..70a3657d02 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -139,7 +139,7 @@ PG_DECLARE(armingConfig_t, armingConfig); bool areUsingSticksToArm(void); throttleStatus_e calculateThrottleStatus(void); -void processRcStickPositions(); +void processRcStickPositions(void); bool isUsingSticksForArming(void); diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c index 6407db0fce..03d7433aa6 100644 --- a/src/main/fc/rc_modes.c +++ b/src/main/fc/rc_modes.c @@ -99,7 +99,7 @@ bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) * T F - all previous AND macs active, no previous active OR macs * T T - at least 1 previous inactive AND mac, no previous active OR macs */ -void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask, bool bActive) +static void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask, bool bActive) { if (bitArrayGet(andMask, mac->modeId) || !bitArrayGet(newMask, mac->modeId)) { bool bAnd = mac->modeLogic == MODELOGIC_AND; @@ -118,7 +118,7 @@ void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMa } } -void updateMasksForStickyModes(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask) +static void updateMasksForStickyModes(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask) { if (IS_RC_MODE_ACTIVE(mac->modeId)) { bitArrayClr(andMask, mac->modeId); diff --git a/src/main/fc/tasks.c b/src/main/fc/tasks.c index 62885df0fa..5be00a3ee2 100644 --- a/src/main/fc/tasks.c +++ b/src/main/fc/tasks.c @@ -289,7 +289,7 @@ static void taskCalculateAltitude(timeUs_t currentTimeUs) #endif // USE_BARO || USE_GPS #if defined(USE_RANGEFINDER) -void taskUpdateRangefinder(timeUs_t currentTimeUs) +static void taskUpdateRangefinder(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); @@ -304,7 +304,7 @@ void taskUpdateRangefinder(timeUs_t currentTimeUs) #endif #ifdef USE_OPTICALFLOW -void taskUpdateOpticalflow(timeUs_t currentTimeUs) +static void taskUpdateOpticalflow(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); diff --git a/src/main/fc/tasks.h b/src/main/fc/tasks.h index 1d6b409ede..05280be2ef 100644 --- a/src/main/fc/tasks.h +++ b/src/main/fc/tasks.h @@ -26,5 +26,5 @@ void tasksInitData(void); void tasksInit(void); task_t *getTask(unsigned taskId); -bool taskUpdateRxMainInProgress(); +bool taskUpdateRxMainInProgress(void); diff --git a/src/main/flight/alt_hold_multirotor.c b/src/main/flight/alt_hold_multirotor.c index e1547638f7..68db59a12c 100644 --- a/src/main/flight/alt_hold_multirotor.c +++ b/src/main/flight/alt_hold_multirotor.c @@ -52,7 +52,7 @@ typedef struct { altHoldState_t altHold; -void altHoldReset(void) +static void altHoldReset(void) { resetAltitudeControl(); altHold.targetAltitudeCm = getAltitudeCm(); @@ -68,7 +68,7 @@ void altHoldInit(void) altHoldReset(); } -void altHoldProcessTransitions(void) { +static void altHoldProcessTransitions(void) { if (FLIGHT_MODE(ALT_HOLD_MODE)) { if (!altHold.isActive) { @@ -90,7 +90,7 @@ void altHoldProcessTransitions(void) { // user throttle must be not more than half way out from hover for a stable hold } -void altHoldUpdateTargetAltitude(void) +static void altHoldUpdateTargetAltitude(void) { // User can adjust the target altitude with throttle, but only when // - throttle is outside deadband, and @@ -133,7 +133,7 @@ void altHoldUpdateTargetAltitude(void) } } -void altHoldUpdate(void) +static void altHoldUpdate(void) { // check if the user has changed the target altitude using sticks if (altHoldConfig()->alt_hold_adjust_rate) { diff --git a/src/main/flight/alt_hold_wing.c b/src/main/flight/alt_hold_wing.c index 05b0db18c2..c2fb806c8b 100644 --- a/src/main/flight/alt_hold_wing.c +++ b/src/main/flight/alt_hold_wing.c @@ -39,7 +39,7 @@ #include "alt_hold.h" -void altHoldReset(void) +LOCAL_UNUSED_FUNCTION static void altHoldReset(void) { } diff --git a/src/main/flight/autopilot_multirotor.c b/src/main/flight/autopilot_multirotor.c index c70635599a..00eff1555b 100644 --- a/src/main/flight/autopilot_multirotor.c +++ b/src/main/flight/autopilot_multirotor.c @@ -98,7 +98,7 @@ static void resetEFAxisFilters(efPidAxis_t* efAxis, const float vaGain) pt1FilterInit(&efAxis->accelerationLpf, vaGain); } -void resetEFAxisParams(efPidAxis_t *efAxis, const float vaGain) +static void resetEFAxisParams(efPidAxis_t *efAxis, const float vaGain) { // at start only resetEFAxisFilters(efAxis, vaGain); @@ -223,7 +223,7 @@ void setSticksActiveStatus(bool areSticksActive) ap.sticksActive = areSticksActive; } -void setTargetLocationByAxis(const gpsLocation_t* newTargetLocation, axisEF_e efAxisIdx) +static void setTargetLocationByAxis(const gpsLocation_t* newTargetLocation, axisEF_e efAxisIdx) // not used at present but needed by upcoming GPS code { if (efAxisIdx == LON) { diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 28af2d6aac..41f7c9d243 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -219,7 +219,7 @@ void failsafeCheckDataFailurePeriod(void) } } -uint32_t failsafeFailurePeriodMs(void) +LOCAL_UNUSED_FUNCTION static uint32_t failsafeFailurePeriodMs(void) { return failsafeState.rxDataFailurePeriod; } diff --git a/src/main/flight/gps_rescue_multirotor.c b/src/main/flight/gps_rescue_multirotor.c index c88295d9dc..cfb3b83feb 100644 --- a/src/main/flight/gps_rescue_multirotor.c +++ b/src/main/flight/gps_rescue_multirotor.c @@ -617,7 +617,7 @@ static bool checkGPSRescueIsAvailable(void) return result; } -void disarmOnImpact(void) +static void disarmOnImpact(void) { if (acc.accMagnitude > rescueState.intent.disarmThreshold) { setArmingDisabled(ARMING_DISABLED_ARM_SWITCH); @@ -626,7 +626,7 @@ void disarmOnImpact(void) } } -void descend(bool newGpsData) +static void descend(bool newGpsData) { if (newGpsData) { // consider landing area to be a circle half landing height around home, to avoid overshooting home point @@ -672,7 +672,7 @@ void descend(bool newGpsData) rescueState.intent.targetAltitudeCm -= altitudeStepCm; } -void initialiseRescueValues (void) +static void initialiseRescueValues (void) { rescueState.intent.secondsFailing = 0; // reset the sanity check timer rescueState.intent.yawAttenuator = 0.0f; // no yaw in the climb diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 894658f368..2b77a36871 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -854,7 +854,7 @@ bool imuQuaternionHeadfreeOffsetSet(void) } } -void imuQuaternionMultiplication(quaternion_t *q1, quaternion_t *q2, quaternion_t *result) +static void imuQuaternionMultiplication(quaternion_t *q1, quaternion_t *q2, quaternion_t *result) { const float A = (q1->w + q1->x) * (q2->w + q2->x); const float B = (q1->z - q1->y) * (q2->y - q2->z); diff --git a/src/main/flight/mixer_init.c b/src/main/flight/mixer_init.c index b3124be593..be226230f8 100644 --- a/src/main/flight/mixer_init.c +++ b/src/main/flight/mixer_init.c @@ -396,7 +396,7 @@ void mixerResetRpmLimiter(void) // Create a custom mixer for launch control based on the current settings // but disable the front motors. We don't care about roll or yaw because they // are limited in the PID controller. -void loadLaunchControlMixer(void) +static void loadLaunchControlMixer(void) { for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { mixerRuntime.launchControlMixer[i] = mixerRuntime.currentMixer[i]; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 2635692f1a..dbc9b08da0 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -416,7 +416,7 @@ static float wingAdjustSetpoint(float currentPidSetpoint, int axis) #endif // USE_WING } -float getTpaFactorClassic(float tpaArgument) +static float getTpaFactorClassic(float tpaArgument) { static bool isTpaLowFaded = false; bool isThrottlePastTpaLowBreakpoint = (tpaArgument >= pidRuntime.tpaLowBreakpoint || pidRuntime.tpaLowBreakpoint <= 0.01f); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8c217dd03c..360a805370 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -584,7 +584,7 @@ float pidCompensateThrustLinearization(float throttle); #ifdef USE_AIRMODE_LPF void pidUpdateAirmodeLpf(float currentOffset); -float pidGetAirmodeThrottleOffset(); +float pidGetAirmodeThrottleOffset(void); #endif #ifdef UNIT_TEST @@ -602,8 +602,8 @@ float calcHorizonLevelStrength(void); void dynLpfDTermUpdate(float throttle); void pidSetItermReset(bool enabled); float pidGetPreviousSetpoint(int axis); -float pidGetDT(); -float pidGetPidFrequency(); +float pidGetDT(void); +float pidGetPidFrequency(void); float dynLpfCutoffFreq(float throttle, uint16_t dynLpfMin, uint16_t dynLpfMax, uint8_t expo); #ifdef USE_CHIRP diff --git a/src/main/flight/pid_init.c b/src/main/flight/pid_init.c index d8dc0484a2..799ee18605 100644 --- a/src/main/flight/pid_init.c +++ b/src/main/flight/pid_init.c @@ -69,7 +69,7 @@ static void pidSetTargetLooptime(uint32_t pidLooptime) } #ifdef USE_WING -void tpaSpeedBasicInit(const pidProfile_t *pidProfile) +static void tpaSpeedBasicInit(const pidProfile_t *pidProfile) { // basic model assumes prop pitch speed is inf const float gravityFactor = pidProfile->tpa_speed_basic_gravity / 100.0f; @@ -82,7 +82,7 @@ void tpaSpeedBasicInit(const pidProfile_t *pidProfile) pidRuntime.tpaSpeed.inversePropMaxSpeed = 0.0f; } -void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile) +static void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile) { // Advanced model uses prop pitch speed, and is quite limited when craft speed is far above prop pitch speed. pidRuntime.tpaSpeed.twr = (float)pidProfile->tpa_speed_adv_thrust / (float)pidProfile->tpa_speed_adv_mass; @@ -109,7 +109,7 @@ void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile) UNUSED(pidProfile); } -void tpaSpeedInit(const pidProfile_t *pidProfile) +static void tpaSpeedInit(const pidProfile_t *pidProfile) { pidRuntime.tpaSpeed.speed = 0.0f; pidRuntime.tpaSpeed.maxVoltage = pidProfile->tpa_speed_max_voltage / 100.0f; @@ -334,7 +334,7 @@ void pidInitFilters(const pidProfile_t *pidProfile) } #ifdef USE_ADVANCED_TPA -float tpaCurveHyperbolicFunction(float x, void *args) +static float tpaCurveHyperbolicFunction(float x, void *args) { const pidProfile_t *pidProfile = (const pidProfile_t*)args; @@ -356,13 +356,13 @@ float tpaCurveHyperbolicFunction(float x, void *args) return pidThr0 / divisor; } -void tpaCurveHyperbolicInit(const pidProfile_t *pidProfile) +static void tpaCurveHyperbolicInit(const pidProfile_t *pidProfile) { pwlInitialize(&pidRuntime.tpaCurvePwl, pidRuntime.tpaCurvePwl_yValues, TPA_CURVE_PWL_SIZE, 0.0f, 1.0f); pwlFill(&pidRuntime.tpaCurvePwl, tpaCurveHyperbolicFunction, (void*)pidProfile); } -void tpaCurveInit(const pidProfile_t *pidProfile) +static void tpaCurveInit(const pidProfile_t *pidProfile) { pidRuntime.tpaCurveType = pidProfile->tpa_curve_type; switch (pidRuntime.tpaCurveType) { diff --git a/src/main/flight/pos_hold_multirotor.c b/src/main/flight/pos_hold_multirotor.c index a3723885e4..de4147a2df 100644 --- a/src/main/flight/pos_hold_multirotor.c +++ b/src/main/flight/pos_hold_multirotor.c @@ -55,7 +55,7 @@ void posHoldInit(void) posHold.useStickAdjustment = posHoldConfig()->pos_hold_deadband; } -void posHoldCheckSticks(void) +static void posHoldCheckSticks(void) { // if failsafe is active, eg landing mode, don't update the original start point if (!failsafeIsActive() && posHold.useStickAdjustment) { @@ -64,7 +64,7 @@ void posHoldCheckSticks(void) } } -bool sensorsOk(void) +static bool sensorsOk(void) { if (!STATE(GPS_FIX)) { return false; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index bbc3b22c81..31a49fac9d 100644 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -204,7 +204,7 @@ const mixerRules_t servoMixers[] = { { 0, NULL }, }; -int16_t determineServoMiddleOrForwardFromChannel(servoIndex_e servoIndex) +static int16_t determineServoMiddleOrForwardFromChannel(servoIndex_e servoIndex) { const uint8_t channelToForwardFrom = servoParams(servoIndex)->forwardFromChannel; diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c index a76d858001..e685b04971 100644 --- a/src/main/io/dashboard.c +++ b/src/main/io/dashboard.c @@ -131,7 +131,7 @@ static void resetDisplay(void) dashboardPresent = ug2864hsweg01InitI2C(dev); } -void LCDprint(uint8_t i) +static void LCDprint(uint8_t i) { i2c_OLED_send_char(dev, i); } @@ -628,7 +628,7 @@ static const pageEntry_t pages[PAGE_COUNT] = { #endif }; -void dashboardSetPage(pageId_e pageId) +static void dashboardSetPage(pageId_e pageId) { for (int i = 0; i < PAGE_COUNT; i++) { const pageEntry_t *candidatePage = &pages[i]; diff --git a/src/main/io/displayport_hott.c b/src/main/io/displayport_hott.c index 8b163f537e..0a84f3e9fd 100644 --- a/src/main/io/displayport_hott.c +++ b/src/main/io/displayport_hott.c @@ -30,6 +30,8 @@ #include "cms/cms.h" #include "telemetry/hott.h" +#include "displayport_hott.h" + displayPort_t hottDisplayPort; static bool hottDrawScreen(displayPort_t *displayPort) diff --git a/src/main/io/displayport_hott.h b/src/main/io/displayport_hott.h index 6814bc32e3..affef31fd3 100644 --- a/src/main/io/displayport_hott.h +++ b/src/main/io/displayport_hott.h @@ -21,6 +21,6 @@ #pragma once #include "drivers/display.h" -void hottDisplayportRegister(); -void hottCmsOpen(); +void hottDisplayportRegister(void); +void hottCmsOpen(void); void hottSetCmsKey(uint8_t hottKey, bool esc); diff --git a/src/main/io/displayport_max7456.c b/src/main/io/displayport_max7456.c index 3e937a14ef..aa342773bc 100644 --- a/src/main/io/displayport_max7456.c +++ b/src/main/io/displayport_max7456.c @@ -185,7 +185,7 @@ static bool checkReady(displayPort_t *displayPort, bool rescan) return true; } -void setBackgroundType(displayPort_t *displayPort, displayPortBackground_e backgroundType) +static void setBackgroundType(displayPort_t *displayPort, displayPortBackground_e backgroundType) { UNUSED(displayPort); max7456SetBackgroundType(backgroundType); diff --git a/src/main/io/displayport_oled.c b/src/main/io/displayport_oled.c index 96087c95b7..b590c1b8ce 100644 --- a/src/main/io/displayport_oled.c +++ b/src/main/io/displayport_oled.c @@ -28,6 +28,8 @@ #include "drivers/display.h" #include "drivers/display_ug2864hsweg01.h" +#include "displayport_oled.h" + static displayPort_t oledDisplayPort; static int oledGrab(displayPort_t *displayPort) diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 1c84fef9c2..fc84c83a76 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -282,7 +282,7 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta) * * Returns the number of bytes written */ -void flashfsWriteCallback(uint32_t arg) +static void flashfsWriteCallback(uint32_t arg) { // Advance the cursor in the file system to match the bytes we wrote flashfsSetTailAddress(tailAddress + arg); diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 8401c5f4b0..129592a005 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -958,7 +958,7 @@ static void setSatInfoMessageRate(uint8_t divisor) #endif // USE_GPS_UBLOX #ifdef USE_GPS_NMEA -void gpsConfigureNmea(void) +static void gpsConfigureNmea(void) { // minimal support for NMEA, we only: // - set the FC's GPS port to the user's configured rate, and @@ -1031,7 +1031,7 @@ void gpsConfigureNmea(void) #ifdef USE_GPS_UBLOX -void gpsConfigureUblox(void) +static void gpsConfigureUblox(void) { // Wait until GPS transmit buffer is empty @@ -1302,7 +1302,7 @@ void gpsConfigureUblox(void) } #endif // USE_GPS_UBLOX -void gpsConfigureHardware(void) +static void gpsConfigureHardware(void) { switch (gpsConfig()->provider) { case GPS_NMEA: @@ -2628,7 +2628,7 @@ void GPS_distance_cm_bearing(const gpsLocation_t *from, const gpsLocation_t* to, } } -void GPS_calculateDistanceAndDirectionToHome(void) +static void GPS_calculateDistanceAndDirectionToHome(void) { if (STATE(GPS_FIX_HOME)) { uint32_t dist; diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 03dd8b4bf7..74917f1c87 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -286,7 +286,7 @@ enum ledBarIds { }; static uint8_t ledBarStates[LED_BAR_COUNT] = {0}; -void updateLedBars(void) +static void updateLedBars(void) { memset(ledBarStates, 0, sizeof(ledBarStates)); for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) { @@ -1193,7 +1193,7 @@ static applyLayerFn_timed* layerTable[] = { [timRing] = &applyLedThrustRingLayer }; -bool isOverlayTypeUsed(ledOverlayId_e overlayType) +static bool isOverlayTypeUsed(ledOverlayId_e overlayType) { for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) { const ledConfig_t *ledConfig = &ledStripStatusModeConfig()->ledConfigs[ledIndex]; diff --git a/src/main/io/pidaudio.c b/src/main/io/pidaudio.c index 26be198290..88ade28418 100644 --- a/src/main/io/pidaudio.c +++ b/src/main/io/pidaudio.c @@ -44,12 +44,12 @@ void pidAudioInit(void) audioSetupIO(); } -void pidAudioStart(void) +static void pidAudioStart(void) { audioGenerateWhiteNoise(); } -void pidAudioStop(void) +static void pidAudioStop(void) { audioSilence(); } diff --git a/src/main/io/rcdevice.h b/src/main/io/rcdevice.h index 80e786f462..b57a468432 100644 --- a/src/main/io/rcdevice.h +++ b/src/main/io/rcdevice.h @@ -172,4 +172,4 @@ void runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device, rcdev void runcamDeviceSendAttitude(runcamDevice_t *device); -runcamDeviceRequest_t* rcdeviceGetRequest(); +runcamDeviceRequest_t* rcdeviceGetRequest(void); diff --git a/src/main/io/serial.c b/src/main/io/serial.c index a97d8260a5..516915e56b 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -338,7 +338,7 @@ serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identi return NULL; } -serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort) +static serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort) { for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) { if (usage->serialPort == serialPort) { @@ -572,41 +572,26 @@ void closeSerialPort(serialPort_t *serialPort) serialPortUsage->serialPort = NULL; } -void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable) +void serialInit(bool softserialEnabled) { -#if !defined(USE_SOFTSERIAL) - UNUSED(softserialEnabled); -#endif - memset(&serialPortUsageList, 0, sizeof(serialPortUsageList)); for (int index = 0; index < SERIAL_PORT_COUNT; index++) { serialPortUsageList[index].identifier = serialPortIdentifiers[index]; - if (serialPortToDisable != SERIAL_PORT_NONE - && serialPortUsageList[index].identifier == serialPortToDisable) { - serialPortUsageList[index].identifier = SERIAL_PORT_NONE; - continue; // this index is deleted +#if SERIAL_TRAIT_PIN_CONFIG + const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier); + if (resourceIndex >= 0 && !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) { + // resource exists but no pin is assigned + serialPortUsageList[index].identifier = SERIAL_PORT_NONE; + continue; } - { -#if !defined(SIMULATOR_BUILD) // no serialPinConfig on SITL - const int resourceIndex = serialResourceIndex(serialPortUsageList[index].identifier); - if (resourceIndex >= 0 // resource exists - && !(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) { - serialPortUsageList[index].identifier = SERIAL_PORT_NONE; - continue; - } #endif - } - if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL) { - if (true -#ifdef USE_SOFTSERIAL - && !softserialEnabled -#endif - ) { - serialPortUsageList[index].identifier = SERIAL_PORT_NONE; - continue; - } + + if (serialType(serialPortUsageList[index].identifier) == SERIALTYPE_SOFTSERIAL && !softserialEnabled) { + // soft serial is not enabled, or not built into the firmware + serialPortUsageList[index].identifier = SERIAL_PORT_NONE; + continue; } } } diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 4943597eaa..3c583574ee 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -171,7 +171,7 @@ typedef void serialConsumer(uint8_t); // // configuration // -void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable); +void serialInit(bool softserialEnabled); void serialRemovePort(serialPortIdentifier_e identifier); bool serialIsPortAvailable(serialPortIdentifier_e identifier); bool isSerialConfigValid(serialConfig_t *serialConfig); @@ -184,7 +184,6 @@ const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function); bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction); -void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier); int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier); serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(const char *portName, const char *candidate)); diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 5dda23f3b9..552fc5d58c 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -318,7 +318,7 @@ void esc4wayRelease(void) CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) +static uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) { int i; diff --git a/src/main/io/serial_resource.c b/src/main/io/serial_resource.c index 878968d0bf..b353d1daff 100644 --- a/src/main/io/serial_resource.c +++ b/src/main/io/serial_resource.c @@ -25,6 +25,8 @@ #include "platform.h" +#include "drivers/serial_impl.h" + #include "io/serial.h" // convert identifier into port type diff --git a/src/main/io/spektrum_rssi.c b/src/main/io/spektrum_rssi.c index a9d65caef7..77519691cd 100644 --- a/src/main/io/spektrum_rssi.c +++ b/src/main/io/spektrum_rssi.c @@ -50,7 +50,7 @@ static uint16_t spek_fade_last_sec_count = 0; // Stores the fade count at the la #endif // Linear mapping and interpolation function -int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max) +static int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max) { return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; } diff --git a/src/main/io/spektrum_vtx_control.c b/src/main/io/spektrum_vtx_control.c index 910fcf5257..3582c3ec68 100644 --- a/src/main/io/spektrum_vtx_control.c +++ b/src/main/io/spektrum_vtx_control.c @@ -98,7 +98,7 @@ const uint8_t vtxSaPi[SPEKTRUM_VTX_POWER_COUNT] = { }; #endif // USE_VTX_SMARTAUDIO -uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower) +static uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower) { uint8_t devicePower = 0; diff --git a/src/main/io/statusindicator.c b/src/main/io/statusindicator.c index 137535c444..fcd1bb58f7 100644 --- a/src/main/io/statusindicator.c +++ b/src/main/io/statusindicator.c @@ -38,7 +38,7 @@ typedef enum { static warningLedState_e warningLedState = WARNING_LED_OFF; -void warningLedResetTimer(void) +LOCAL_UNUSED_FUNCTION static void warningLedResetTimer(void) { uint32_t now = millis(); warningLedTimer = now + 500000; diff --git a/src/main/io/usb_cdc_hid.h b/src/main/io/usb_cdc_hid.h index ca65b8cffc..fa0c1dc255 100644 --- a/src/main/io/usb_cdc_hid.h +++ b/src/main/io/usb_cdc_hid.h @@ -21,6 +21,6 @@ #pragma once void sendRcDataToHid(void); -bool cdcDeviceIsMayBeActive(); +bool cdcDeviceIsMayBeActive(void); void sendReport(uint8_t *report, uint8_t len); uint8_t usbIsConnected(void); diff --git a/src/main/io/usb_msc.c b/src/main/io/usb_msc.c index 524f40f791..5ec1d2826f 100644 --- a/src/main/io/usb_msc.c +++ b/src/main/io/usb_msc.c @@ -27,6 +27,7 @@ #include "drivers/sdcard.h" #include "io/flashfs.h" +#include "usb_msc.h" #if defined(USE_USB_MSC) diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 6e9d3ea362..df3a48fc6c 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -854,7 +854,7 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs) #ifdef USE_VTX_COMMON // Interface to common VTX API -vtxDevType_e vtxSAGetDeviceType(const vtxDevice_t *vtxDevice) +static vtxDevType_e vtxSAGetDeviceType(const vtxDevice_t *vtxDevice) { UNUSED(vtxDevice); return VTXDEV_SMARTAUDIO; diff --git a/src/main/io/vtx_tramp.h b/src/main/io/vtx_tramp.h index a56410490f..cf04bb3f2a 100644 --- a/src/main/io/vtx_tramp.h +++ b/src/main/io/vtx_tramp.h @@ -29,5 +29,5 @@ bool vtxTrampInit(void); -uint16_t vtxTrampGetCurrentActualPower(); -uint16_t vtxTrampGetCurrentTemp(); +uint16_t vtxTrampGetCurrentActualPower(void); +uint16_t vtxTrampGetCurrentTemp(void); diff --git a/src/main/msc/emfat.c b/src/main/msc/emfat.c index f1db3b6cc8..7e7bfe7c26 100644 --- a/src/main/msc/emfat.c +++ b/src/main/msc/emfat.c @@ -217,7 +217,7 @@ typedef struct #pragma pack(pop) -bool emfat_init_entries(emfat_entry_t *entries) +static bool emfat_init_entries(emfat_entry_t *entries) { emfat_entry_t *e; int i, n; @@ -339,7 +339,7 @@ bool emfat_init(emfat_t *emfat, const char *label, emfat_entry_t *entries) return true; } -void read_mbr_sector(const emfat_t *emfat, uint8_t *sect) +static void read_mbr_sector(const emfat_t *emfat, uint8_t *sect) { mbr_t *mbr; memset(sect, 0, SECT); @@ -356,7 +356,7 @@ void read_mbr_sector(const emfat_t *emfat, uint8_t *sect) mbr->BootSignature[1] = 0xAA; } -void read_boot_sector(const emfat_t *emfat, uint8_t *sect) +static void read_boot_sector(const emfat_t *emfat, uint8_t *sect) { boot_sector *bs; memset(sect, 0, SECT); @@ -398,7 +398,7 @@ void read_boot_sector(const emfat_t *emfat, uint8_t *sect) #define IS_CLUST_OF(clust, entry) ((clust) >= (entry)->priv.first_clust && (clust) <= (entry)->priv.last_reserved) -emfat_entry_t *find_entry(const emfat_t *emfat, uint32_t clust, emfat_entry_t *nearest) +static emfat_entry_t *find_entry(const emfat_t *emfat, uint32_t clust, emfat_entry_t *nearest) { if (nearest == NULL) { nearest = emfat->priv.entries; @@ -420,7 +420,7 @@ emfat_entry_t *find_entry(const emfat_t *emfat, uint32_t clust, emfat_entry_t *n return NULL; } -void read_fsinfo_sector(const emfat_t *emfat, uint8_t *sect) +static void read_fsinfo_sector(const emfat_t *emfat, uint8_t *sect) { UNUSED(emfat); @@ -436,7 +436,7 @@ void read_fsinfo_sector(const emfat_t *emfat, uint8_t *sect) info->signature3 = 0xAA550000; } -void read_fat_sector(emfat_t *emfat, uint8_t *sect, uint32_t index) +static void read_fat_sector(emfat_t *emfat, uint8_t *sect, uint32_t index) { emfat_entry_t *le; uint32_t *values; @@ -489,7 +489,7 @@ void read_fat_sector(emfat_t *emfat, uint8_t *sect, uint32_t index) emfat->priv.last_entry = le; } -void fill_entry(dir_entry *entry, const char *name, uint8_t attr, uint32_t clust, const uint32_t cma[3], uint32_t size) +static void fill_entry(dir_entry *entry, const char *name, uint8_t attr, uint32_t clust, const uint32_t cma[3], uint32_t size) { int i, l, l1, l2; int dot_pos; @@ -553,7 +553,7 @@ void fill_entry(dir_entry *entry, const char *name, uint8_t attr, uint32_t clust return; } -void fill_dir_sector(emfat_t *emfat, uint8_t *data, emfat_entry_t *entry, uint32_t rel_sect) +static void fill_dir_sector(emfat_t *emfat, uint8_t *data, emfat_entry_t *entry, uint32_t rel_sect) { dir_entry *de; uint32_t avail; @@ -600,7 +600,7 @@ void fill_dir_sector(emfat_t *emfat, uint8_t *data, emfat_entry_t *entry, uint32 } } -void read_data_sector(emfat_t *emfat, uint8_t *data, uint32_t rel_sect) +static void read_data_sector(emfat_t *emfat, uint8_t *data, uint32_t rel_sect) { emfat_entry_t *le; uint32_t cluster; @@ -659,7 +659,7 @@ void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors) } } -void write_data_sector(emfat_t *emfat, const uint8_t *data, uint32_t rel_sect) +LOCAL_UNUSED_FUNCTION static void write_data_sector(emfat_t *emfat, const uint8_t *data, uint32_t rel_sect) { emfat_entry_t *le; uint32_t cluster; diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index fdb95d7cd1..df8e717cb9 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -398,7 +398,7 @@ static void mspRebootFn(serialPort_t *serialPort) #define MSP_DISPATCH_DELAY_US 1000000 -void mspReboot(dispatchEntry_t* self) +static void mspReboot(dispatchEntry_t* self) { UNUSED(self); @@ -413,7 +413,7 @@ dispatchEntry_t mspRebootEntry = { mspReboot, 0, NULL, false }; -void writeReadEeprom(dispatchEntry_t* self) +static void writeReadEeprom(dispatchEntry_t* self) { UNUSED(self); diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 00601c56b9..4cf5b6d46e 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -483,7 +483,7 @@ static void mspSerialProcessReceivedReply(mspPort_t *msp, mspProcessReplyFnPtr m mspProcessReplyFn(&reply); } -void mspProcessPacket(mspPort_t *mspPort, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn) +static void mspProcessPacket(mspPort_t *mspPort, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn) { mspPostProcessFnPtr mspPostProcessFn = NULL; diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 3b65452492..7e4ab9057b 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -278,7 +278,7 @@ bool osdWarnGetState(uint8_t warningIndex) } #ifdef USE_OSD_PROFILES -void setOsdProfile(uint8_t value) +static void setOsdProfile(uint8_t value) { // 1 ->> 001 // 2 ->> 010 @@ -1279,7 +1279,7 @@ STATIC_UNIT_TESTED bool osdProcessStats1(timeUs_t currentTimeUs) return refreshStatsRequired; } -void osdProcessStats2(timeUs_t currentTimeUs) +static void osdProcessStats2(timeUs_t currentTimeUs) { displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); @@ -1307,7 +1307,7 @@ void osdProcessStats2(timeUs_t currentTimeUs) #endif } -void osdProcessStats3(void) +static void osdProcessStats3(void) { #if defined(USE_ACC) osdGForce = 0.0f; diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index 99cc5484f4..07844d0ea2 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -644,7 +644,7 @@ char osdGetSpeedToSelectedUnitSymbol(void) } } -char osdGetVarioToSelectedUnitSymbol(void) +MAYBE_UNUSED static char osdGetVarioToSelectedUnitSymbol(void) { switch (osdConfig()->units) { case UNIT_IMPERIAL: diff --git a/src/main/pg/bus_i2c.c b/src/main/pg/bus_i2c.c index 1e70c23ccd..20ce63365d 100644 --- a/src/main/pg/bus_i2c.c +++ b/src/main/pg/bus_i2c.c @@ -39,6 +39,8 @@ #include "pg/bus_i2c.h" +PG_REGISTER_ARRAY_WITH_RESET_FN(i2cConfig_t, I2CDEV_COUNT, i2cConfig, PG_I2C_CONFIG, 1); + #ifndef I2C1_SCL_PIN #define I2C1_SCL_PIN NONE #endif @@ -100,6 +102,4 @@ void pgResetFn_i2cConfig(i2cConfig_t *i2cConfig) } } -PG_REGISTER_ARRAY_WITH_RESET_FN(i2cConfig_t, I2CDEV_COUNT, i2cConfig, PG_I2C_CONFIG, 1); - #endif // defined(USE_I2C) && !defined(USE_SOFT_I2C) diff --git a/src/main/pg/pg.h b/src/main/pg/pg.h index d7a2333e5b..8159a443d7 100644 --- a/src/main/pg/pg.h +++ b/src/main/pg/pg.h @@ -139,7 +139,7 @@ extern const uint8_t __pg_resetdata_end[]; /**/ #define PG_REGISTER_WITH_RESET_FN(_type, _name, _pgn, _version) \ - extern void pgResetFn_ ## _name(_type *); \ + static void pgResetFn_ ## _name(_type *); \ PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.fn = (pgResetFunc*)&pgResetFn_ ## _name }) \ /**/ diff --git a/src/main/rx/cc2500_frsky_x.c b/src/main/rx/cc2500_frsky_x.c index 133a10ea81..63dfb48ee1 100644 --- a/src/main/rx/cc2500_frsky_x.c +++ b/src/main/rx/cc2500_frsky_x.c @@ -298,7 +298,7 @@ void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet) } } -bool isValidPacket(const uint8_t *packet) +static bool isValidPacket(const uint8_t *packet) { bool useBindTxId2 = false; diff --git a/src/main/rx/cc2500_redpine.c b/src/main/rx/cc2500_redpine.c index 7d96f338ea..44bcb5e742 100644 --- a/src/main/rx/cc2500_redpine.c +++ b/src/main/rx/cc2500_redpine.c @@ -86,7 +86,7 @@ static void initBindTuneRx(void); static bool tuneRx1(uint8_t *packet); static bool tuneRx2(uint8_t *packet); static bool tuneRx3(uint8_t *packet); -static void nextChannel(); +static void nextChannel(void); static bool redpineRxPacketBind(uint8_t *packet); static bool isRedpineFast(void); @@ -389,7 +389,7 @@ static bool isRedpineFast(void) return (redpineFast); } -void switchRedpineMode(void) +static void switchRedpineMode(void) { redpineFast = !redpineFast; } diff --git a/src/main/rx/cc2500_sfhss.c b/src/main/rx/cc2500_sfhss.c index 640dd646d7..ac1ef25368 100644 --- a/src/main/rx/cc2500_sfhss.c +++ b/src/main/rx/cc2500_sfhss.c @@ -188,7 +188,7 @@ static bool sfhssPacketParse(uint8_t *packet, bool check_txid) return true; } -void sfhssRx(void) +static void sfhssRx(void) { cc2500Strobe(CC2500_SIDLE); cc2500WriteReg(CC2500_23_FSCAL3, calData[sfhss_channel][0]); @@ -278,7 +278,7 @@ static bool tune3Rx(uint8_t *packet) return false; } -void sfhssnextChannel(void) +static void sfhssnextChannel(void) { do { sfhss_channel += sfhss_code + 2; diff --git a/src/main/rx/cyrf6936_spektrum.c b/src/main/rx/cyrf6936_spektrum.c index b23a261e8e..d368ba920f 100644 --- a/src/main/rx/cyrf6936_spektrum.c +++ b/src/main/rx/cyrf6936_spektrum.c @@ -506,7 +506,7 @@ static bool isValidPacket(const uint8_t *packet) return true; } -rx_spi_received_e spektrumReadPacket(uint8_t *payload, const uint32_t timeStamp) +static rx_spi_received_e spektrumReadPacket(uint8_t *payload, const uint32_t timeStamp) { rx_spi_received_e result = RX_SPI_RECEIVED_NONE; diff --git a/src/main/rx/expresslrs.c b/src/main/rx/expresslrs.c index c71a196933..514c662f90 100644 --- a/src/main/rx/expresslrs.c +++ b/src/main/rx/expresslrs.c @@ -520,7 +520,7 @@ void expressLrsOnTimerTockISR(void) static uint16_t lostConnectionCounter = 0; -void lostConnection(void) +static void lostConnection(void) { lostConnectionCounter++; diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index e17029d976..4cbcf158f8 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -102,7 +102,7 @@ uint16_t jetiExBusCalcCRC16(const uint8_t *pt, uint8_t msgLen) return(crc16_data); } -void jetiExBusDecodeChannelFrame(uint8_t *exBusFrame) +static void jetiExBusDecodeChannelFrame(uint8_t *exBusFrame) { uint16_t value; uint8_t frameAddr; @@ -123,7 +123,7 @@ void jetiExBusDecodeChannelFrame(uint8_t *exBusFrame) } } -void jetiExBusFrameReset(void) +static void jetiExBusFrameReset(void) { jetiExBusFramePosition = 0; jetiExBusFrameLength = EXBUS_MAX_CHANNEL_FRAME_SIZE; diff --git a/src/main/rx/msp.h b/src/main/rx/msp.h index cb80ac4c30..601af9d917 100644 --- a/src/main/rx/msp.h +++ b/src/main/rx/msp.h @@ -25,4 +25,4 @@ struct rxRuntimeState_s; float rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan); void rxMspInit(const struct rxConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState); void rxMspFrameReceive(const uint16_t *frame, int channelCount); -uint8_t rxMspOverrideFrameStatus(); +uint8_t rxMspOverrideFrameStatus(void); diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 77fdf27ca8..b063da354d 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -682,7 +682,7 @@ static void readRxChannelsApplyRanges(void) } } -void detectAndApplySignalLossBehaviour(void) +static void detectAndApplySignalLossBehaviour(void) { const uint32_t currentTimeMs = millis(); const bool boxFailsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index f291bb5fec..4889499a45 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -190,7 +190,7 @@ static float spektrumReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t c #ifdef USE_SPEKTRUM_BIND -bool spekShouldBind(uint8_t spektrum_sat_bind) +static bool spekShouldBind(uint8_t spektrum_sat_bind) { #ifdef USE_SPEKTRUM_BIND_PLUG IO_t BindPlug = IOGetByTag(rxConfig()->spektrum_bind_plug_ioTag); diff --git a/src/main/rx/spektrum.h b/src/main/rx/spektrum.h index 256b42053c..c35a8c2f6b 100644 --- a/src/main/rx/spektrum.h +++ b/src/main/rx/spektrum.h @@ -50,6 +50,6 @@ extern uint8_t rssi_channel; // Stores the RX RSSI channel. void spektrumBind(rxConfig_t *rxConfig); bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState); -bool srxlTelemetryBufferEmpty(); +bool srxlTelemetryBufferEmpty(void); void srxlRxWriteTelemetryData(const void *data, int len); bool srxlRxIsActive(void); diff --git a/src/main/rx/srxl2.c b/src/main/rx/srxl2.c index 1b5366fc22..d12a2792d6 100644 --- a/src/main/rx/srxl2.c +++ b/src/main/rx/srxl2.c @@ -124,7 +124,7 @@ uint8_t globalResult = 0; // if 50ms with not activity, go to default baudrate and to step 1 -bool srxl2ProcessHandshake(const Srxl2Header* header) +static bool srxl2ProcessHandshake(const Srxl2Header* header) { const Srxl2HandshakeSubHeader* handshake = (Srxl2HandshakeSubHeader*)(header + 1); if (handshake->destinationDeviceId == Broadcast) { @@ -164,7 +164,7 @@ bool srxl2ProcessHandshake(const Srxl2Header* header) return true; } -void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeState_t *rxRuntimeState) +static void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeState_t *rxRuntimeState) { globalResult = RX_FRAME_COMPLETE; @@ -191,7 +191,7 @@ void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntim DEBUG_PRINTF("channel data: %d %d %x\r\n", channelData_header->rssi, channelData_header->frameLosses, channelData_header->channelMask.u32); } -bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState) +static bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState) { const Srxl2ControlDataSubHeader* controlData = (Srxl2ControlDataSubHeader*)(header + 1); const uint8_t ownId = (FlightController << 4) | unitId; @@ -237,7 +237,7 @@ bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeState_t *rxRunt return true; } -bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState) +static bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState) { switch (header->packetType) { case Handshake: @@ -253,7 +253,7 @@ bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeSt } // @note assumes packet is fully there -void srxl2Process(rxRuntimeState_t *rxRuntimeState) +static void srxl2Process(rxRuntimeState_t *rxRuntimeState) { if (processBufferPtr->packet.header.id != SRXL2_ID || processBufferPtr->len != processBufferPtr->packet.header.length) { DEBUG_PRINTF("invalid header id: %x, or length: %x received vs %x expected \r\n", processBufferPtr->packet.header.id, processBufferPtr->len, processBufferPtr->packet.header.length); diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index ffac17ec45..70a947a666 100644 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -136,14 +136,14 @@ static timeMs_t lastFailsafeCheckMs = 0; #endif STATIC_UNIT_TESTED FAST_DATA_ZERO_INIT task_t* taskQueueArray[TASK_COUNT + 1 + TASK_QUEUE_RESERVE]; // extra item for NULL pointer at end of queue (+ overflow check in UNTT_TEST) -void queueClear(void) +STATIC_UNIT_TESTED void queueClear(void) { memset(taskQueueArray, 0, sizeof(taskQueueArray)); taskQueuePos = 0; taskQueueSize = 0; } -bool queueContains(const task_t *task) +static bool queueContains(const task_t *task) { for (int ii = 0; ii < taskQueueSize; ++ii) { if (taskQueueArray[ii] == task) { @@ -153,7 +153,7 @@ bool queueContains(const task_t *task) return false; } -bool queueAdd(task_t *task) +STATIC_UNIT_TESTED bool queueAdd(task_t *task) { if ((taskQueueSize >= TASK_COUNT) || queueContains(task)) { return false; @@ -169,7 +169,7 @@ bool queueAdd(task_t *task) return false; } -bool queueRemove(task_t *task) +STATIC_UNIT_TESTED bool queueRemove(task_t *task) { for (int ii = 0; ii < taskQueueSize; ++ii) { if (taskQueueArray[ii] == task) { @@ -184,7 +184,7 @@ bool queueRemove(task_t *task) /* * Returns first item queue or NULL if queue empty */ -FAST_CODE task_t *queueFirst(void) +STATIC_UNIT_TESTED FAST_CODE task_t *queueFirst(void) { taskQueuePos = 0; return taskQueueArray[0]; // guaranteed to be NULL if queue is empty @@ -193,7 +193,7 @@ FAST_CODE task_t *queueFirst(void) /* * Returns next item in queue or NULL if at end of queue */ -FAST_CODE task_t *queueNext(void) +STATIC_UNIT_TESTED FAST_CODE task_t *queueNext(void) { return taskQueueArray[++taskQueuePos]; // guaranteed to be NULL at end of queue } diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 9e190994cc..8728c16b26 100644 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -242,10 +242,10 @@ void getTaskInfo(taskId_e taskId, taskInfo_t *taskInfo); void rescheduleTask(taskId_e taskId, timeDelta_t newPeriodUs); void setTaskEnabled(taskId_e taskId, bool newEnabledState); timeDelta_t getTaskDeltaTimeUs(taskId_e taskId); -void schedulerIgnoreTaskStateTime(); -void schedulerIgnoreTaskExecRate(); -void schedulerIgnoreTaskExecTime(); -bool schedulerGetIgnoreTaskExecTime(); +void schedulerIgnoreTaskStateTime(void); +void schedulerIgnoreTaskExecRate(void); +void schedulerIgnoreTaskExecTime(void); +bool schedulerGetIgnoreTaskExecTime(void); void schedulerResetTaskStatistics(taskId_e taskId); void schedulerResetTaskMaxExecutionTime(taskId_e taskId); void schedulerResetCheckFunctionMaxExecutionTime(void); diff --git a/src/main/sensors/acceleration_init.c b/src/main/sensors/acceleration_init.c index 812ab21f6d..1488b8b28a 100644 --- a/src/main/sensors/acceleration_init.c +++ b/src/main/sensors/acceleration_init.c @@ -99,7 +99,7 @@ bool accHasBeenCalibrated(void) #endif } -void accResetRollAndPitchTrims(void) +LOCAL_UNUSED_FUNCTION static void accResetRollAndPitchTrims(void) { resetRollAndPitchTrims(&accelerometerConfigMutable()->accelerometerTrims); } @@ -112,7 +112,7 @@ static void resetFlightDynamicsTrims(flightDynamicsTrims_t *accZero) accZero->values.calibrationCompleted = 0; } -void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance) +static void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance) { RESET_CONFIG_2(accelerometerConfig_t, instance, .acc_lpf_hz = 25, // ATTITUDE/IMU runs at 100Hz (acro) or 500Hz (level modes) so we need to set 50 Hz (or lower) to avoid aliasing @@ -130,7 +130,7 @@ extern bool AccInflightCalibrationMeasurementDone; extern bool AccInflightCalibrationSavetoEEProm; extern bool AccInflightCalibrationActive; -bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) +static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) { accelerationSensor_e accHardware = ACC_NONE; diff --git a/src/main/sensors/adcinternal.c b/src/main/sensors/adcinternal.c index cad059dc89..908d1d9ed8 100644 --- a/src/main/sensors/adcinternal.c +++ b/src/main/sensors/adcinternal.c @@ -23,6 +23,8 @@ #include "platform.h" +#include "adcinternal.h" + #if defined(USE_ADC_INTERNAL) #include "build/debug.h" @@ -38,7 +40,7 @@ typedef struct movingAverageStateUint16_s { uint8_t pos; } movingAverageStateUint16_t; -uint16_t updateMovingAverageUint16(movingAverageStateUint16_t *state, uint16_t newValue) +static uint16_t updateMovingAverageUint16(movingAverageStateUint16_t *state, uint16_t newValue) { state->sum -= state->values[state->pos]; state->values[state->pos] = newValue; diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 62b684466f..43e7463a66 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -246,7 +246,7 @@ void batteryUpdatePresence(void) } } -void batteryUpdateWhDrawn(void) +static void batteryUpdateWhDrawn(void) { static int32_t mAhDrawnPrev = 0; const int32_t mAhDrawnCurrent = getMAhDrawn(); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 2ca1b0f689..281aa27ba7 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -156,7 +156,7 @@ void compassPreInit(void) } #if !defined(SIMULATOR_BUILD) -bool compassDetect(magDev_t *magDev, uint8_t *alignment) +static bool compassDetect(magDev_t *magDev, uint8_t *alignment) { #ifdef MAG_ALIGN *alignment = MAG_ALIGN; @@ -340,7 +340,7 @@ bool compassDetect(magDev_t *magDev, uint8_t *alignment) return true; } #else -bool compassDetect(magDev_t *dev, sensor_align_e *alignment) +static bool compassDetect(magDev_t *dev, sensor_align_e *alignment) { UNUSED(dev); UNUSED(alignment); diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 067a889c1c..5a43c91eb9 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -147,7 +147,7 @@ static bool isFrameComplete(void) return bufferPosition == bufferSize; } -bool isEscSensorActive(void) +LOCAL_UNUSED_FUNCTION static bool isEscSensorActive(void) { return escSensorPort != NULL; } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 659028559c..26b8d6a26c 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -132,7 +132,7 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig) gyroConfig->simplified_gyro_filter_multiplier = SIMPLIFIED_TUNING_DEFAULT; } -bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor) +static bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor) { return gyroSensor->calibration.cyclesRemaining == 0; } @@ -259,7 +259,7 @@ STATIC_UNIT_TESTED NOINLINE void performGyroCalibration(gyroSensor_t *gyroSensor } #if defined(USE_GYRO_SLEW_LIMITER) -FAST_CODE int32_t gyroSlewLimiter(gyroSensor_t *gyroSensor, int axis) +static FAST_CODE int32_t gyroSlewLimiter(gyroSensor_t *gyroSensor, int axis) { int32_t ret = (int32_t)gyroSensor->gyroDev.gyroADCRaw[axis]; if (gyroConfig()->checkOverflow || gyro.gyroHasOverflowProtection) { @@ -546,7 +546,7 @@ float gyroGetFilteredDownsampled(int axis) return gyroFilteredDownsampled[axis]; } -int16_t gyroReadSensorTemperature(gyroSensor_t gyroSensor) +static int16_t gyroReadSensorTemperature(gyroSensor_t gyroSensor) { if (gyroSensor.gyroDev.temperatureFn) { gyroSensor.gyroDev.temperatureFn(&gyroSensor.gyroDev, &gyroSensor.gyroDev.temperature); diff --git a/src/main/sensors/gyro_init.c b/src/main/sensors/gyro_init.c index 4ebc9153e7..4e09d73c18 100644 --- a/src/main/sensors/gyro_init.c +++ b/src/main/sensors/gyro_init.c @@ -69,6 +69,8 @@ #include "sensors/gyro.h" #include "sensors/sensors.h" +#include "gyro_init.h" + #ifdef USE_MULTI_GYRO #define ACTIVE_GYRO ((gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_2) ? &gyro.gyroSensor2 : &gyro.gyroSensor1) #else diff --git a/src/main/sensors/opticalflow.c b/src/main/sensors/opticalflow.c index 37f45161a7..27dc57e970 100644 --- a/src/main/sensors/opticalflow.c +++ b/src/main/sensors/opticalflow.c @@ -186,7 +186,7 @@ static void applyLPF(vector2_t * flowRates) { flowRates->y = pt2FilterApply(&yFlowLpf, flowRates->y); } -const opticalflow_t * getLatestFlowOpticalflowData(void) { +LOCAL_UNUSED_FUNCTION static const opticalflow_t * getLatestFlowOpticalflowData(void) { return &opticalflow; } diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index 16bf42b000..62790f036d 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -243,7 +243,7 @@ void rangefinderUpdate(void) } } -bool isSurfaceAltitudeValid(void) +static bool isSurfaceAltitudeValid(void) { /* diff --git a/src/main/sensors/voltage.c b/src/main/sensors/voltage.c index d0c5728962..7af2caa091 100644 --- a/src/main/sensors/voltage.c +++ b/src/main/sensors/voltage.c @@ -127,7 +127,7 @@ voltageMeterADCState_t voltageMeterADCStates[MAX_VOLTAGE_SENSOR_ADC]; static bool sagCompensationConfigured; -voltageMeterADCState_t *getVoltageMeterADC(uint8_t index) +LOCAL_UNUSED_FUNCTION static voltageMeterADCState_t *getVoltageMeterADC(uint8_t index) { return &voltageMeterADCStates[index]; } diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 48140efae8..0c095d7087 100644 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -133,7 +133,7 @@ uint32_t getCrsfCachedBaudrate(void) return CRSF_BAUDRATE; } -bool checkCrsfCustomizedSpeed(void) +static bool checkCrsfCustomizedSpeed(void) { return crsfSpeed.index < BAUD_COUNT ? true : false; } @@ -246,7 +246,7 @@ uint16_t GPS heading ( degree / 100 ) uint16 Altitude ( meter ­1000m offset ) uint8_t Satellites in use ( counter ) */ -void crsfFrameGps(sbuf_t *dst) +MAYBE_UNUSED static void crsfFrameGps(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, CRSF_FRAME_GPS_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); @@ -265,7 +265,7 @@ void crsfFrameGps(sbuf_t *dst) Payload: int16_t Vertical speed ( cm/s ) */ -void crsfFrameVarioSensor(sbuf_t *dst) +MAYBE_UNUSED static void crsfFrameVarioSensor(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, CRSF_FRAME_VARIO_SENSOR_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); @@ -281,7 +281,7 @@ uint16_t Current ( mA * 100 ) uint24_t Fuel ( drawn mAh ) uint8_t Battery remaining ( percent ) */ -void crsfFrameBatterySensor(sbuf_t *dst) +static void crsfFrameBatterySensor(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); @@ -359,7 +359,8 @@ static void crsfFrameAltitude(sbuf_t *dst) Payload: int16_t origin_add ( Origin Device address ) */ -void crsfFrameHeartbeat(sbuf_t *dst) + +MAYBE_UNUSED static void crsfFrameHeartbeat(sbuf_t *dst) { sbufWriteU8(dst, CRSF_FRAME_HEARTBEAT_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); sbufWriteU8(dst, CRSF_FRAMETYPE_HEARTBEAT); @@ -372,7 +373,8 @@ Payload: int8_t destination_add ( Destination Device address ) int8_t origin_add ( Origin Device address ) */ -void crsfFramePing(sbuf_t *dst) + +MAYBE_UNUSED static void crsfFramePing(sbuf_t *dst) { sbufWriteU8(dst, CRSF_FRAME_DEVICE_PING_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); sbufWriteU8(dst, CRSF_FRAMETYPE_DEVICE_PING); @@ -424,7 +426,7 @@ static int16_t decidegrees2Radians10000(int16_t angle_decidegree) } // fill dst buffer with crsf-attitude telemetry frame -void crsfFrameAttitude(sbuf_t *dst) +static void crsfFrameAttitude(sbuf_t *dst) { sbufWriteU8(dst, CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); sbufWriteU8(dst, CRSF_FRAMETYPE_ATTITUDE); @@ -438,7 +440,7 @@ void crsfFrameAttitude(sbuf_t *dst) Payload: char[] Flight mode ( Null terminated string ) */ -void crsfFrameFlightMode(sbuf_t *dst) +static void crsfFrameFlightMode(sbuf_t *dst) { // write zero for frame length, since we don't know it yet uint8_t *lengthPtr = sbufPtr(dst); @@ -499,7 +501,7 @@ uint32_t Null Bytes uint8_t 255 (Max MSP Parameter) uint8_t 0x01 (Parameter version 1) */ -void crsfFrameDeviceInfo(sbuf_t *dst) +static void crsfFrameDeviceInfo(sbuf_t *dst) { char buff[30]; tfp_sprintf(buff, "%s %s: %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, systemConfig()->boardIdentifier); @@ -519,7 +521,7 @@ void crsfFrameDeviceInfo(sbuf_t *dst) } #if defined(USE_CRSF_V3) -void crsfFrameSpeedNegotiationResponse(sbuf_t *dst, bool reply) +static void crsfFrameSpeedNegotiationResponse(sbuf_t *dst, bool reply) { uint8_t *lengthPtr = sbufPtr(dst); sbufWriteU8(dst, 0); @@ -547,7 +549,7 @@ static void crsfProcessSpeedNegotiationCmd(const uint8_t *frameStart) crsfSpeed.index = ii; } -void crsfScheduleSpeedNegotiationResponse(void) +static void crsfScheduleSpeedNegotiationResponse(void) { crsfSpeed.hasPendingReply = true; crsfSpeed.isNewSpeedValid = false; diff --git a/src/main/telemetry/frsky_hub.c b/src/main/telemetry/frsky_hub.c index 88b369dc93..06e8aa5bbe 100644 --- a/src/main/telemetry/frsky_hub.c +++ b/src/main/telemetry/frsky_hub.c @@ -478,7 +478,7 @@ bool initFrSkyHubTelemetryExternal(frSkyHubWriteByteFn *frSkyHubWriteByteExterna return false; } -void freeFrSkyHubTelemetryPort(void) +static void freeFrSkyHubTelemetryPort(void) { closeSerialPort(frSkyHubPort); frSkyHubPort = NULL; diff --git a/src/main/telemetry/ghst.c b/src/main/telemetry/ghst.c index d90b0947a9..ea4315c7d0 100644 --- a/src/main/telemetry/ghst.c +++ b/src/main/telemetry/ghst.c @@ -96,7 +96,7 @@ static void ghstFinalize(sbuf_t *dst) } // Battery (Pack) status -void ghstFramePackTelemetry(sbuf_t *dst) +static void ghstFramePackTelemetry(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, GHST_FRAME_PACK_PAYLOAD_SIZE + GHST_FRAME_LENGTH_CRC + GHST_FRAME_LENGTH_TYPE); @@ -119,7 +119,7 @@ void ghstFramePackTelemetry(sbuf_t *dst) } // GPS data, primary, positional data -void ghstFrameGpsPrimaryTelemetry(sbuf_t *dst) +MAYBE_UNUSED static void ghstFrameGpsPrimaryTelemetry(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, GHST_FRAME_GPS_PAYLOAD_SIZE + GHST_FRAME_LENGTH_CRC + GHST_FRAME_LENGTH_TYPE); @@ -138,7 +138,7 @@ void ghstFrameGpsPrimaryTelemetry(sbuf_t *dst) } // GPS data, secondary, auxiliary data -void ghstFrameGpsSecondaryTelemetry(sbuf_t *dst) +MAYBE_UNUSED static void ghstFrameGpsSecondaryTelemetry(sbuf_t *dst) { // use sbufWrite since CRC does not include frame length sbufWriteU8(dst, GHST_FRAME_GPS_PAYLOAD_SIZE + GHST_FRAME_LENGTH_CRC + GHST_FRAME_LENGTH_TYPE); @@ -162,7 +162,7 @@ void ghstFrameGpsSecondaryTelemetry(sbuf_t *dst) } // Mag, Baro (and Vario) data -void ghstFrameMagBaro(sbuf_t *dst) +static void ghstFrameMagBaro(sbuf_t *dst) { int16_t vario = 0; int16_t altitude = 0; diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 343777bfe0..fa0d8a325f 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -181,7 +181,7 @@ static void initialiseMessages(void) } #ifdef USE_GPS -void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude) +STATIC_UNIT_TESTED void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude) { int16_t deg = latitude / GPS_DEGREES_DIVIDER; int32_t sec = (latitude - (deg * GPS_DEGREES_DIVIDER)) * 6; @@ -311,7 +311,7 @@ static inline void hottEAMUpdateClimbrate(HOTT_EAM_MSG_t *hottEAMMessage) } #endif -void hottPrepareEAMResponse(HOTT_EAM_MSG_t *hottEAMMessage) +static void hottPrepareEAMResponse(HOTT_EAM_MSG_t *hottEAMMessage) { // Reset alarms hottEAMMessage->warning_beeps = 0x0; diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h index a2e446d3ca..81d43b2c2d 100644 --- a/src/main/telemetry/hott.h +++ b/src/main/telemetry/hott.h @@ -499,9 +499,9 @@ void configureHoTTTelemetryPort(void); void freeHoTTTelemetryPort(void); #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS) -bool hottTextmodeIsAlive(); -void hottTextmodeGrab(); -void hottTextmodeExit(); +bool hottTextmodeIsAlive(void); +void hottTextmodeGrab(void); +void hottTextmodeExit(void); void hottTextmodeWriteChar(uint8_t column, uint8_t row, char c); #endif diff --git a/src/main/telemetry/jetiexbus.c b/src/main/telemetry/jetiexbus.c index 07dc7fe2e6..e76a19e16e 100644 --- a/src/main/telemetry/jetiexbus.c +++ b/src/main/telemetry/jetiexbus.c @@ -181,7 +181,7 @@ static uint8_t sendJetiExBusTelemetry(uint8_t packetID, uint8_t item); static uint8_t getNextActiveSensor(uint8_t currentSensor); // Jeti Ex Telemetry CRC calculations for a frame -uint8_t calcCRC8(const uint8_t *pt, uint8_t msgLen) +static uint8_t calcCRC8(const uint8_t *pt, uint8_t msgLen) { uint8_t crc=0; for (uint8_t mlen = 0; mlen < msgLen; mlen++) { @@ -191,7 +191,7 @@ uint8_t calcCRC8(const uint8_t *pt, uint8_t msgLen) return(crc); } -void enableGpsTelemetry(bool enable) +static void enableGpsTelemetry(bool enable) { if (enable) { bitArraySet(&exSensorEnabled, EX_GPS_SATS); @@ -269,7 +269,7 @@ void initJetiExBusTelemetry(void) firstActiveSensor = getNextActiveSensor(0); // find the first active sensor } -void createExTelemetryTextMessage(uint8_t *exMessage, uint8_t messageID, const exBusSensor_t *sensor) +static void createExTelemetryTextMessage(uint8_t *exMessage, uint8_t messageID, const exBusSensor_t *sensor) { uint8_t labelLength = strlen(sensor->label); uint8_t unitLength = strlen(sensor->unit); @@ -285,7 +285,7 @@ void createExTelemetryTextMessage(uint8_t *exMessage, uint8_t messageID, const e exMessage[exMessage[EXTEL_HEADER_TYPE_LEN] + EXTEL_CRC_LEN] = calcCRC8(&exMessage[EXTEL_HEADER_TYPE_LEN], exMessage[EXTEL_HEADER_TYPE_LEN]); } -uint32_t calcGpsDDMMmmm(int32_t value, bool isLong) +static uint32_t calcGpsDDMMmmm(int32_t value, bool isLong) { uint32_t absValue = abs(value); uint16_t deg16 = absValue / GPS_DEGREES_DIVIDER; @@ -300,7 +300,7 @@ uint32_t calcGpsDDMMmmm(int32_t value, bool isLong) return exGps.vInt; } -int32_t getSensorValue(uint8_t sensor) +static int32_t getSensorValue(uint8_t sensor) { switch (sensor) { case EX_VOLTAGE: @@ -407,7 +407,7 @@ uint8_t getNextActiveSensor(uint8_t currentSensor) return currentSensor; } -uint8_t createExTelemetryValueMessage(uint8_t *exMessage, uint8_t item) +static uint8_t createExTelemetryValueMessage(uint8_t *exMessage, uint8_t item) { uint8_t startItem = item; uint8_t sensorItemMaxGroup = (item & 0xF0) + 0x10; @@ -452,7 +452,7 @@ uint8_t createExTelemetryValueMessage(uint8_t *exMessage, uint8_t item) return item; // return the next item } -void createExBusMessage(uint8_t *exBusMessage, const uint8_t *exMessage, uint8_t packetID) +static void createExBusMessage(uint8_t *exBusMessage, const uint8_t *exMessage, uint8_t packetID) { uint16_t crc16; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 9fd41091af..497f29e75a 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -200,7 +200,7 @@ void checkMAVLinkTelemetryState(void) } } -void mavlinkSendSystemStatus(void) +static void mavlinkSendSystemStatus(void) { uint16_t msgLength; @@ -265,7 +265,7 @@ void mavlinkSendSystemStatus(void) mavlinkSerialWrite(mavBuffer, msgLength); } -void mavlinkSendRCChannelsAndRSSI(void) +static void mavlinkSendRCChannelsAndRSSI(void) { uint16_t msgLength; mavlink_msg_rc_channels_raw_pack(0, 200, &mavMsg, @@ -296,7 +296,7 @@ void mavlinkSendRCChannelsAndRSSI(void) } #if defined(USE_GPS) -void mavlinkSendPosition(void) +static void mavlinkSendPosition(void) { uint16_t msgLength; uint8_t gpsFixType = 0; @@ -376,7 +376,7 @@ void mavlinkSendPosition(void) } #endif -void mavlinkSendAttitude(void) +static void mavlinkSendAttitude(void) { uint16_t msgLength; mavlink_msg_attitude_pack(0, 200, &mavMsg, @@ -398,7 +398,7 @@ void mavlinkSendAttitude(void) mavlinkSerialWrite(mavBuffer, msgLength); } -void mavlinkSendHUDAndHeartbeat(void) +static void mavlinkSendHUDAndHeartbeat(void) { uint16_t msgLength; float mavAltitude = 0; @@ -508,7 +508,7 @@ void mavlinkSendHUDAndHeartbeat(void) mavlinkSerialWrite(mavBuffer, msgLength); } -void processMAVLinkTelemetry(void) +static void processMAVLinkTelemetry(void) { // is executed @ TELEMETRY_MAVLINK_MAXRATE rate if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS)) { diff --git a/src/main/telemetry/msp_shared.c b/src/main/telemetry/msp_shared.c index b0993d175c..42670e69d4 100644 --- a/src/main/telemetry/msp_shared.c +++ b/src/main/telemetry/msp_shared.c @@ -159,7 +159,7 @@ static void processMspPacket(void) sbufSwitchToReader(&responsePacket.buf, responseBuffer); } -void sendMspErrorResponse(uint8_t error, int16_t cmd) +static void sendMspErrorResponse(uint8_t error, int16_t cmd) { responsePacket.cmd = cmd; responsePacket.result = 0; diff --git a/src/main/telemetry/srxl.c b/src/main/telemetry/srxl.c index 304b670bd1..c349da7e74 100644 --- a/src/main/telemetry/srxl.c +++ b/src/main/telemetry/srxl.c @@ -141,7 +141,7 @@ typedef struct #define STRU_TELE_QOS_EMPTY_FIELDS_COUNT 14 #define STRU_TELE_QOS_EMPTY_FIELDS_VALUE 0xff -bool srxlFrameQos(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameQos(sbuf_t *dst, timeUs_t currentTimeUs) { UNUSED(currentTimeUs); @@ -181,7 +181,7 @@ typedef struct #define SPEKTRUM_MIN_RPM 999 // Min RPM to show the user, indicating RPM is really below 999 #define SPEKTRUM_MAX_RPM 60000000 -uint16_t getMotorAveragePeriod(void) +static uint16_t getMotorAveragePeriod(void) { #if defined( USE_ESC_SENSOR_TELEMETRY) || defined( USE_DSHOT_TELEMETRY) @@ -214,7 +214,7 @@ uint16_t getMotorAveragePeriod(void) #endif } -bool srxlFrameRpm(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameRpm(sbuf_t *dst, timeUs_t currentTimeUs) { int16_t coreTemp = SPEKTRUM_TEMP_UNUSED; #if defined(USE_ADC_INTERNAL) @@ -290,7 +290,7 @@ typedef struct #define GPS_FLAGS_3D_FIX_BIT 0x20 #define GPS_FLAGS_NEGATIVE_ALT_BIT 0x80 -bool srxlFrameGpsLoc(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameGpsLoc(sbuf_t *dst, timeUs_t currentTimeUs) { UNUSED(currentTimeUs); gpsCoordinateDDDMMmmmm_t coordinate; @@ -358,7 +358,7 @@ typedef struct #define STRU_TELE_GPS_STAT_EMPTY_FIELDS_COUNT 6 #define SPEKTRUM_TIME_UNKNOWN 0xFFFFFFFF -bool srxlFrameGpsStat(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameGpsStat(sbuf_t *dst, timeUs_t currentTimeUs) { UNUSED(currentTimeUs); uint32_t timeBcd; @@ -431,7 +431,7 @@ typedef struct #define FP_MAH_KEEPALIVE_TIME_OUT 2000000 // 2s -bool srxlFrameFlightPackCurrent(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameFlightPackCurrent(sbuf_t *dst, timeUs_t currentTimeUs) { uint16_t amps = getAmperage() / 10; uint16_t mah = getMAhDrawn(); @@ -505,7 +505,7 @@ int spektrumTmTextGenPutChar(uint8_t col, uint8_t row, char c) } //************************************************************************** -bool srxlFrameText(sbuf_t *dst, timeUs_t currentTimeUs) +static bool srxlFrameText(sbuf_t *dst, timeUs_t currentTimeUs) { UNUSED(currentTimeUs); static uint8_t lineNo = 0; diff --git a/src/platform/APM32/adc_apm32f4xx.c b/src/platform/APM32/adc_apm32f4xx.c index 3359b90678..2b93c1eba6 100644 --- a/src/platform/APM32/adc_apm32f4xx.c +++ b/src/platform/APM32/adc_apm32f4xx.c @@ -97,7 +97,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA7, ADC_DEVICES_12, ADC_CHANNEL_7 }, }; -void adcInitDevice(adcDevice_t *adcdev, int channelCount) +static void adcInitDevice(adcDevice_t *adcdev, int channelCount) { ADC_HandleTypeDef *hadc = &adcdev->ADCHandle; @@ -133,7 +133,7 @@ static adcDevice_t adc; static adcDevice_t adcInternal; static ADC_HandleTypeDef *adcInternalHandle; -void adcInitInternalInjected(adcDevice_t *adcdev) +static void adcInitInternalInjected(adcDevice_t *adcdev) { adcInternalHandle = &adcdev->ADCHandle; diff --git a/src/platform/APM32/dshot_bitbang_ddl.c b/src/platform/APM32/dshot_bitbang_ddl.c index 50d53cf7e8..dc7301c491 100644 --- a/src/platform/APM32/dshot_bitbang_ddl.c +++ b/src/platform/APM32/dshot_bitbang_ddl.c @@ -114,7 +114,7 @@ void bbTimerChannelInit(bbPort_t *bbPort) } #ifdef USE_DMA_REGISTER_CACHE -void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) +static void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) { ((DMA_ARCH_TYPE *)dmaResource)->SCFG = dmaRegCache->SCFG; ((DMA_ARCH_TYPE *)dmaResource)->FCTRL = dmaRegCache->FCTRL; diff --git a/src/platform/APM32/eint_apm32.c b/src/platform/APM32/eint_apm32.c index fd39b93094..151dd437d2 100644 --- a/src/platform/APM32/eint_apm32.c +++ b/src/platform/APM32/eint_apm32.c @@ -165,7 +165,7 @@ void EXTIDisable(IO_t io) #define EXTI_EVENT_MASK 0xFFFF // first 16 bits only, see also definition of extiChannelRecs. -void EXTI_IRQHandler(uint32_t mask) +static void EXTI_IRQHandler(uint32_t mask) { uint32_t exti_active = (EXTI_REG_IMR & EXTI_REG_PR) & mask; diff --git a/src/platform/APM32/light_ws2811strip_apm32.c b/src/platform/APM32/light_ws2811strip_apm32.c index 676f719470..2ef5cbcb30 100644 --- a/src/platform/APM32/light_ws2811strip_apm32.c +++ b/src/platform/APM32/light_ws2811strip_apm32.c @@ -43,7 +43,7 @@ static IO_t ws2811IO = IO_NONE; static TMR_HandleTypeDef TmrHandle; static uint16_t timerChannel = 0; -FAST_IRQ_HANDLER void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +static FAST_IRQ_HANDLER void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) { DAL_DMA_IRQHandler(TmrHandle.hdma[descriptor->userParam]); TIM_DMACmd(&TmrHandle, timerChannel, DISABLE); diff --git a/src/platform/APM32/persistent_apm32.c b/src/platform/APM32/persistent_apm32.c index 20a367ad6f..0a9bda61f0 100644 --- a/src/platform/APM32/persistent_apm32.c +++ b/src/platform/APM32/persistent_apm32.c @@ -59,7 +59,7 @@ void persistentObjectWrite(persistentObjectId_e id, uint32_t value) #endif } -void persistentObjectRTCEnable(void) +static void persistentObjectRTCEnable(void) { RTC_HandleTypeDef rtcHandle = { .Instance = RTC }; diff --git a/src/platform/APM32/platform_mcu.h b/src/platform/APM32/platform_mcu.h index 2962b97218..10299b6d5c 100644 --- a/src/platform/APM32/platform_mcu.h +++ b/src/platform/APM32/platform_mcu.h @@ -192,6 +192,7 @@ #define PLATFORM_TRAIT_RCC 1 #define UART_TRAIT_AF_PORT 1 +#define SERIAL_TRAIT_PIN_CONFIG 1 #define UARTHARDWARE_MAX_PINS 4 diff --git a/src/platform/APM32/pwm_output_apm32.c b/src/platform/APM32/pwm_output_apm32.c index a49c58d748..d3de5ba53a 100644 --- a/src/platform/APM32/pwm_output_apm32.c +++ b/src/platform/APM32/pwm_output_apm32.c @@ -92,7 +92,7 @@ static void pwmWriteStandard(uint8_t index, float value) *motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset); } -void pwmShutdownPulsesForAllMotors(void) +static void pwmShutdownPulsesForAllMotors(void) { for (int index = 0; index < pwmMotorCount; index++) { // Set the compare register to 0, which stops the output pulsing if the timer overflows @@ -102,19 +102,19 @@ void pwmShutdownPulsesForAllMotors(void) } } -void pwmDisableMotors(void) +static void pwmDisableMotors(void) { pwmShutdownPulsesForAllMotors(); } static motorVTable_t motorPwmVTable; -bool pwmEnableMotors(void) +static bool pwmEnableMotors(void) { /* check motors can be enabled */ return pwmMotorCount > 0; } -bool pwmIsMotorEnabled(unsigned index) +static bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } diff --git a/src/platform/APM32/startup/system_apm32f4xx.c b/src/platform/APM32/startup/system_apm32f4xx.c index bdebc6cc7d..02a935aa8e 100644 --- a/src/platform/APM32/startup/system_apm32f4xx.c +++ b/src/platform/APM32/startup/system_apm32f4xx.c @@ -343,7 +343,7 @@ void DAL_ErrorHandler(void) } } -void AssertFailedHandler(uint8_t *file, uint32_t line) +LOCAL_UNUSED_FUNCTION static void AssertFailedHandler(uint8_t *file, uint32_t line) { /* When the function is needed, this function could be implemented in the user file diff --git a/src/platform/APM32/timer_apm32.c b/src/platform/APM32/timer_apm32.c index df3aff9adb..b113bc5f07 100644 --- a/src/platform/APM32/timer_apm32.c +++ b/src/platform/APM32/timer_apm32.c @@ -321,7 +321,7 @@ uint8_t timerInputIrq(const TMR_TypeDef *tim) return 0; } -void timerNVICConfigure(uint8_t irq) +static void timerNVICConfigure(uint8_t irq) { DAL_NVIC_SetPriority(irq, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER)); DAL_NVIC_EnableIRQ(irq); diff --git a/src/platform/AT32/adc_at32f43x.c b/src/platform/AT32/adc_at32f43x.c index 9cc7ea6225..31b6a45b55 100644 --- a/src/platform/AT32/adc_at32f43x.c +++ b/src/platform/AT32/adc_at32f43x.c @@ -130,7 +130,7 @@ static volatile DMA_DATA uint32_t adcConversionBuffer[ADC_CHANNEL_COUNT]; * @param channelCount how many channels to repeat over * */ -void adcInitDevice(const adc_type *dev, const int channelCount) +static void adcInitDevice(const adc_type *dev, const int channelCount) { adc_base_config_type adc_base_struct; @@ -150,7 +150,7 @@ void adcInitDevice(const adc_type *dev, const int channelCount) * @param tag the ioTag to search for * @return the index in adcTagMap corresponding to the given ioTag or -1 if not found */ -int adcFindTagMapEntry(const ioTag_t tag) +static int adcFindTagMapEntry(const ioTag_t tag) { for (int i = 0; i < ADC_TAG_MAP_COUNT; i++) { if (adcTagMap[i].tag == tag) { @@ -174,7 +174,7 @@ int adcFindTagMapEntry(const ioTag_t tag) * the datasheet when defining those values, so here we have to convert to what's expected in * adcInternalComputeTemperature. */ -void setScalingFactors(void) +static void setScalingFactors(void) { // The expected reading for 1.2V internal reference if external vref+ was 3.3V adcVREFINTCAL = VREFINT_EXPECTED; @@ -448,7 +448,7 @@ void adcInternalStartConversion(void) /** * Reads a given channel from the DMA buffer */ -uint16_t adcInternalRead(int channel) +static uint16_t adcInternalRead(int channel) { const int dmaIndex = adcOperatingConfig[channel].dmaIndex; return adcConversionBuffer[dmaIndex]; diff --git a/src/platform/AT32/dshot_bitbang_stdperiph.c b/src/platform/AT32/dshot_bitbang_stdperiph.c index 927eae2684..972b090fdd 100644 --- a/src/platform/AT32/dshot_bitbang_stdperiph.c +++ b/src/platform/AT32/dshot_bitbang_stdperiph.c @@ -117,7 +117,7 @@ void bbTimerChannelInit(bbPort_t *bbPort) #ifdef USE_DMA_REGISTER_CACHE -void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) +static void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) { ((DMA_ARCH_TYPE *)dmaResource)->ctrl = dmaRegCache->CCR; ((DMA_ARCH_TYPE *)dmaResource)->dtcnt = dmaRegCache->CNDTR; diff --git a/src/platform/AT32/exti_at32.c b/src/platform/AT32/exti_at32.c index 5bbe0bde50..c0e2d3dafc 100644 --- a/src/platform/AT32/exti_at32.c +++ b/src/platform/AT32/exti_at32.c @@ -155,7 +155,7 @@ void EXTIDisable(IO_t io) #define EXTI_EVENT_MASK 0xFFFF -void EXTI_IRQHandler(uint32_t mask) +static void EXTI_IRQHandler(uint32_t mask) { uint32_t exti_active = (EXTI_REG_IMR & EXTI_REG_PR) & mask; diff --git a/src/platform/AT32/persistent_at32bsp.c b/src/platform/AT32/persistent_at32bsp.c index b79c5b67ad..691bc564cf 100644 --- a/src/platform/AT32/persistent_at32bsp.c +++ b/src/platform/AT32/persistent_at32bsp.c @@ -45,7 +45,7 @@ void persistentObjectWrite(persistentObjectId_e id, uint32_t value) ertc_write_protect_enable(); } -void persistentObjectRTCEnable(void) +static void persistentObjectRTCEnable(void) { crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); pwc_battery_powered_domain_access(TRUE); diff --git a/src/platform/AT32/platform_mcu.h b/src/platform/AT32/platform_mcu.h index 7dbc1c7adf..dc2e81e248 100644 --- a/src/platform/AT32/platform_mcu.h +++ b/src/platform/AT32/platform_mcu.h @@ -147,6 +147,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define PLATFORM_TRAIT_RCC 1 #define UART_TRAIT_AF_PIN 1 #define UART_TRAIT_PINSWAP 1 +#define SERIAL_TRAIT_PIN_CONFIG 1 #define UARTHARDWARE_MAX_PINS 5 diff --git a/src/platform/AT32/pwm_output_at32bsp.c b/src/platform/AT32/pwm_output_at32bsp.c index 382dbd0925..8ebc593340 100644 --- a/src/platform/AT32/pwm_output_at32bsp.c +++ b/src/platform/AT32/pwm_output_at32bsp.c @@ -83,7 +83,7 @@ static void pwmWriteStandard(uint8_t index, float value) *motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset); } -void pwmShutdownPulsesForAllMotors(void) +static void pwmShutdownPulsesForAllMotors(void) { for (int index = 0; index < pwmMotorCount; index++) { // Set the compare register to 0, which stops the output pulsing if the timer overflows @@ -93,19 +93,19 @@ void pwmShutdownPulsesForAllMotors(void) } } -void pwmDisableMotors(void) +static void pwmDisableMotors(void) { pwmShutdownPulsesForAllMotors(); } static motorVTable_t motorPwmVTable; -bool pwmEnableMotors(void) +static bool pwmEnableMotors(void) { /* check motors can be enabled */ return (pwmMotorDevice->vTable); } -bool pwmIsMotorEnabled(unsigned index) +static bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } diff --git a/src/platform/AT32/pwm_output_dshot.c b/src/platform/AT32/pwm_output_dshot.c index 57b88f8efd..2d4722da04 100644 --- a/src/platform/AT32/pwm_output_dshot.c +++ b/src/platform/AT32/pwm_output_dshot.c @@ -57,7 +57,7 @@ * * @see TIM_CH_TO_SELCHANNEL macro */ -tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNChannel) +static tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNChannel) { tmr_channel_select_type result = TMR_SELECT_CHANNEL_1; // XXX I don't like using ch 1 as a default result, but what to do? if (useNChannel) diff --git a/src/platform/AT32/serial_usb_vcp_at32f4.c b/src/platform/AT32/serial_usb_vcp_at32f4.c index f0fc0ce44d..0cb3288b71 100644 --- a/src/platform/AT32/serial_usb_vcp_at32f4.c +++ b/src/platform/AT32/serial_usb_vcp_at32f4.c @@ -93,7 +93,7 @@ void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), v ctrlLineStateCb = cb; } -void usb_clock48m_select(usb_clk48_s clk_s) +static void usb_clock48m_select(usb_clk48_s clk_s) { if(clk_s == USB_CLK_HICK) { @@ -174,7 +174,7 @@ void usb_clock48m_select(usb_clk48_s clk_s) } } -void usb_gpio_config(void) +static void usb_gpio_config(void) { gpio_init_type gpio_init_struct; @@ -256,7 +256,7 @@ uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength) return sendLength; } -void TxTimerConfig(void) +static void TxTimerConfig(void) { tmr_base_init(usbTxTmr, (CDC_POLLING_INTERVAL - 1), ((system_core_clock)/1000 - 1)); tmr_clock_source_div_set(usbTxTmr, TMR_CLOCK_DIV1); diff --git a/src/platform/AT32/system_at32f43x.c b/src/platform/AT32/system_at32f43x.c index 8f4f7d76af..ccde9850f6 100644 --- a/src/platform/AT32/system_at32f43x.c +++ b/src/platform/AT32/system_at32f43x.c @@ -122,7 +122,7 @@ typedef struct isrVector_s { resetHandler_t *resetHandler; } isrVector_t; -void checkForBootLoaderRequest(void) +static void checkForBootLoaderRequest(void) { volatile uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); diff --git a/src/platform/AT32/timer_at32bsp.c b/src/platform/AT32/timer_at32bsp.c index b0a584b83e..f76a417152 100644 --- a/src/platform/AT32/timer_at32bsp.c +++ b/src/platform/AT32/timer_at32bsp.c @@ -321,7 +321,7 @@ uint8_t timerInputIrq(const tmr_type *tim) return 0; } -void timerNVICConfigure(uint8_t irq) +static void timerNVICConfigure(uint8_t irq) { nvic_irq_enable(irq,NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER),NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER)); } @@ -676,10 +676,6 @@ void timerInit(void) { memset(timerConfig, 0, sizeof(timerConfig)); -#if defined(PARTIAL_REMAP_TIM3) - GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE); -#endif - #ifdef USE_TIMER_MGMT /* enable the timer peripherals */ for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) { diff --git a/src/platform/AT32/usb_msc_at32f43x.c b/src/platform/AT32/usb_msc_at32f43x.c index 007dd07b0b..fefe8049b1 100644 --- a/src/platform/AT32/usb_msc_at32f43x.c +++ b/src/platform/AT32/usb_msc_at32f43x.c @@ -55,12 +55,13 @@ #include "usbd_int.h" #include "msc_class.h" #include "msc_desc.h" +#include "msc_diskio.h" #include "drivers/usb_io.h" extern otg_core_type otg_core_struct; -void msc_usb_gpio_config(void) +static void msc_usb_gpio_config(void) { gpio_init_type gpio_init_struct; @@ -95,7 +96,7 @@ void msc_usb_gpio_config(void) } -void msc_usb_clock48m_select(usb_clk48_s clk_s) +static void msc_usb_clock48m_select(usb_clk48_s clk_s) { if(clk_s == USB_CLK_HICK) { crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_HICK); diff --git a/src/platform/SIMULATOR/platform_mcu.h b/src/platform/SIMULATOR/platform_mcu.h index 5e9fb85ac6..be11284f04 100644 --- a/src/platform/SIMULATOR/platform_mcu.h +++ b/src/platform/SIMULATOR/platform_mcu.h @@ -30,3 +30,6 @@ #define IOCFG_IN_FLOATING 0 #define SPIDEV_COUNT 0 + +// no serial pins are defined for the simulator +#define SERIAL_TRAIT_PIN_CONFIG 0 diff --git a/src/platform/SIMULATOR/sitl.c b/src/platform/SIMULATOR/sitl.c index f4c9980d63..bd52fe2564 100644 --- a/src/platform/SIMULATOR/sitl.c +++ b/src/platform/SIMULATOR/sitl.c @@ -30,12 +30,16 @@ #include "common/maths.h" +#include "build/debug.h" + +#include "drivers/adc_impl.h" #include "drivers/io.h" #include "drivers/dma.h" #include "drivers/motor_impl.h" #include "drivers/serial.h" #include "drivers/serial_tcp.h" #include "drivers/system.h" +#include "drivers/time.h" #include "drivers/pwm_output.h" #include "drivers/light_led.h" @@ -49,6 +53,8 @@ #include "config/feature.h" #include "config/config.h" #include "config/config_streamer.h" +#include "config/config_streamer_impl.h" +#include "config/config_eeprom_impl.h" #include "scheduler/scheduler.h" @@ -56,6 +62,7 @@ #include "pg/motor.h" #include "rx/rx.h" +#include "rx/spektrum.h" #include "io/gps.h" #include "io/gps_virtual.h" @@ -110,12 +117,12 @@ int lockMainPID(void) #define ACC_SCALE (256 / 9.80665) #define GYRO_SCALE (16.4) -void sendMotorUpdate(void) +static void sendMotorUpdate(void) { udpSend(&pwmLink, &pwmPkt, sizeof(servo_packet)); } -void updateState(const fdm_packet* pkt) +static void updateState(const fdm_packet* pkt) { static double last_timestamp = 0; // in seconds static uint64_t last_realtime = 0; // in uS @@ -469,7 +476,7 @@ uint32_t getCycleCounter(void) return (uint32_t) (micros64() & 0xFFFFFFFF); } -void microsleep(uint32_t usec) +static void microsleep(uint32_t usec) { struct timespec ts; ts.tv_sec = 0; @@ -590,7 +597,7 @@ static void pwmShutdownPulsesForAllMotors(void) pwmMotorDevice.enabled = false; } -bool pwmIsMotorEnabled(unsigned index) +static bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } diff --git a/src/platform/STM32/adc_stm32f4xx.c b/src/platform/STM32/adc_stm32f4xx.c index 0ce2a8e075..1a9de8f69d 100644 --- a/src/platform/STM32/adc_stm32f4xx.c +++ b/src/platform/STM32/adc_stm32f4xx.c @@ -126,7 +126,7 @@ const adcTagMap_t adcTagMap[] = { #define TS_CAL1_ADDR 0x1FFF7A2C #define TS_CAL2_ADDR 0x1FFF7A2E -void adcInitDevice(ADC_TypeDef *adcdev, int channelCount) +static void adcInitDevice(ADC_TypeDef *adcdev, int channelCount) { ADC_InitTypeDef ADC_InitStructure; @@ -150,7 +150,7 @@ void adcInitDevice(ADC_TypeDef *adcdev, int channelCount) } #ifdef USE_ADC_INTERNAL -void adcInitInternalInjected(const adcConfig_t *config) +static void adcInitInternalInjected(const adcConfig_t *config) { ADC_TempSensorVrefintCmd(ENABLE); ADC_InjectedDiscModeCmd(ADC1, DISABLE); diff --git a/src/platform/STM32/adc_stm32f7xx.c b/src/platform/STM32/adc_stm32f7xx.c index b26e0295bc..f631543c47 100644 --- a/src/platform/STM32/adc_stm32f7xx.c +++ b/src/platform/STM32/adc_stm32f7xx.c @@ -95,7 +95,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA7, ADC_DEVICES_12, ADC_CHANNEL_7 }, }; -void adcInitDevice(adcDevice_t *adcdev, int channelCount) +static void adcInitDevice(adcDevice_t *adcdev, int channelCount) { adcdev->ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8; adcdev->ADCHandle.Init.ContinuousConvMode = ENABLE; @@ -130,7 +130,7 @@ static adcDevice_t adc; static adcDevice_t adcInternal; static ADC_HandleTypeDef *adcInternalHandle; -void adcInitInternalInjected(adcDevice_t *adcdev) +static void adcInitInternalInjected(adcDevice_t *adcdev) { adcInternalHandle = &adcdev->ADCHandle; diff --git a/src/platform/STM32/adc_stm32g4xx.c b/src/platform/STM32/adc_stm32g4xx.c index 34aa689edf..26e6ac9e6b 100644 --- a/src/platform/STM32/adc_stm32g4xx.c +++ b/src/platform/STM32/adc_stm32g4xx.c @@ -199,7 +199,7 @@ static void handleError(void) // Temperature sensor has minimum sample time of 9us. // With prescaler = 4 at 200MHz (AHB1), fADC = 50MHz (tcycle = 0.02us), 9us = 450cycles < 810 -void adcInitDevice(adcDevice_t *adcdev, int channelCount) +static void adcInitDevice(adcDevice_t *adcdev, int channelCount) { ADC_HandleTypeDef *hadc = &adcdev->ADCHandle; // For clarity @@ -232,7 +232,7 @@ void adcInitDevice(adcDevice_t *adcdev, int channelCount) } } -int adcFindTagMapEntry(ioTag_t tag) +static int adcFindTagMapEntry(ioTag_t tag) { for (int i = 0; i < ADC_TAG_MAP_COUNT; i++) { if (adcTagMap[i].tag == tag) { @@ -242,7 +242,7 @@ int adcFindTagMapEntry(ioTag_t tag) return -1; } -void adcInitCalibrationValues(void) +static void adcInitCalibrationValues(void) { adcVREFINTCAL = *(uint16_t *)VREFINT_CAL_ADDR; adcTSCAL1 = *TEMPSENSOR_CAL1_ADDR; @@ -504,7 +504,7 @@ void adcInternalStartConversion(void) return; } -uint16_t adcInternalRead(int channel) +static uint16_t adcInternalRead(int channel) { int dmaIndex = adcOperatingConfig[channel].dmaIndex; diff --git a/src/platform/STM32/adc_stm32h7xx.c b/src/platform/STM32/adc_stm32h7xx.c index 8f17237e55..643fff600e 100644 --- a/src/platform/STM32/adc_stm32h7xx.c +++ b/src/platform/STM32/adc_stm32h7xx.c @@ -192,7 +192,7 @@ static void errorHandler(void) { while (1) { } } // Temperature sensor has minimum sample time of 9us. // With prescaler = 4 at 200MHz (AHB1), fADC = 50MHz (tcycle = 0.02us), 9us = 450cycles < 810 -void adcInitDevice(adcDevice_t *adcdev, int channelCount) +static void adcInitDevice(adcDevice_t *adcdev, int channelCount) { ADC_HandleTypeDef *hadc = &adcdev->ADCHandle; // For clarity @@ -240,7 +240,7 @@ void adcInitDevice(adcDevice_t *adcdev, int channelCount) } } -int adcFindTagMapEntry(ioTag_t tag) +static int adcFindTagMapEntry(ioTag_t tag) { for (int i = 0; i < ADC_TAG_MAP_COUNT; i++) { if (adcTagMap[i].tag == tag) { @@ -260,7 +260,7 @@ int adcFindTagMapEntry(ioTag_t tag) #error Unknown MCU #endif -void adcInitCalibrationValues(void) +static void adcInitCalibrationValues(void) { adcVREFINTCAL = *VREFINT_CAL_ADDR >> VREFINT_CAL_SHIFT; adcTSCAL1 = *TEMPSENSOR_CAL1_ADDR >> VREFINT_CAL_SHIFT; @@ -560,7 +560,7 @@ void adcInternalStartConversion(void) return; } -uint16_t adcInternalRead(int channel) +static uint16_t adcInternalRead(int channel) { int dmaIndex = adcOperatingConfig[channel].dmaIndex; diff --git a/src/platform/STM32/bus_i2c_stm32f4xx.c b/src/platform/STM32/bus_i2c_stm32f4xx.c index 26ea2e5d96..34a0c02802 100644 --- a/src/platform/STM32/bus_i2c_stm32f4xx.c +++ b/src/platform/STM32/bus_i2c_stm32f4xx.c @@ -212,7 +212,7 @@ bool i2cBusy(I2CDevice device, bool *error) return state->busy; } -bool i2cWait(I2CDevice device) +static bool i2cWait(I2CDevice device) { i2cState_t *state = &i2cDevice[device].state; timeUs_t timeoutStartUs = microsISR(); diff --git a/src/platform/STM32/bus_octospi_stm32h7xx.c b/src/platform/STM32/bus_octospi_stm32h7xx.c index 484283f45b..ffd803f49f 100644 --- a/src/platform/STM32/bus_octospi_stm32h7xx.c +++ b/src/platform/STM32/bus_octospi_stm32h7xx.c @@ -113,7 +113,7 @@ #define OSPI_SIOO_INST_EVERY_CMD ((uint32_t)0x00000000U) #define OSPI_SIOO_INST_ONLY_FIRST_CMD ((uint32_t)OCTOSPI_CCR_SIOO) -MMFLASH_CODE_NOINLINE static void Error_Handler(void) { +static MMFLASH_CODE_NOINLINE void Error_Handler(void) { while (1) { NOOP; } @@ -303,7 +303,7 @@ MMFLASH_CODE_NOINLINE static ErrorStatus octoSpiConfigureCommand(OCTOSPI_TypeDef return status; } -MMFLASH_CODE_NOINLINE ErrorStatus octoSpiCommand(OCTOSPI_TypeDef *instance, OSPI_Command_t *cmd) +static MMFLASH_CODE_NOINLINE ErrorStatus octoSpiCommand(OCTOSPI_TypeDef *instance, OSPI_Command_t *cmd) { octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); @@ -325,7 +325,7 @@ MMFLASH_CODE_NOINLINE ErrorStatus octoSpiCommand(OCTOSPI_TypeDef *instance, OSPI * * Call optoSpiCommand first to configure the transaction stages. */ -MMFLASH_CODE_NOINLINE ErrorStatus octoSpiTransmit(OCTOSPI_TypeDef *instance, uint8_t *data) +static MMFLASH_CODE_NOINLINE ErrorStatus octoSpiTransmit(OCTOSPI_TypeDef *instance, uint8_t *data) { if (data == NULL) { return ERROR; @@ -357,7 +357,7 @@ MMFLASH_CODE_NOINLINE ErrorStatus octoSpiTransmit(OCTOSPI_TypeDef *instance, uin * * Call optoSpiCommand first to configure the transaction stages. */ -MMFLASH_CODE_NOINLINE ErrorStatus octoSpiReceive(OCTOSPI_TypeDef *instance, uint8_t *data) +static MMFLASH_CODE_NOINLINE ErrorStatus octoSpiReceive(OCTOSPI_TypeDef *instance, uint8_t *data) { if (data == NULL) { return ERROR; @@ -415,7 +415,7 @@ typedef struct octoSpiMemoryMappedModeConfigurationRegisterBackup_t ospiMMMCRBackups[OCTOSPI_INTERFACE_COUNT]; -void octoSpiBackupMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) +static void octoSpiBackupMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) { OCTOSPIDevice device = octoSpiDeviceByInstance(instance); if (device == OCTOSPIINVALID) { @@ -435,7 +435,7 @@ void octoSpiBackupMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) ospiMMMCRBackup->ABR = instance->ABR; } -MMFLASH_CODE_NOINLINE void octoSpiRestoreMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) +static MMFLASH_CODE_NOINLINE void octoSpiRestoreMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) { OCTOSPIDevice device = octoSpiDeviceByInstance(instance); if (device == OCTOSPIINVALID) { @@ -516,7 +516,7 @@ MMFLASH_CODE_NOINLINE void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instan octoSpiRestoreMemoryMappedModeConfiguration(instance); } -MMFLASH_CODE_NOINLINE void octoSpiTestEnableDisableMemoryMappedMode(octoSpiDevice_t *octoSpi) +static MMFLASH_CODE_NOINLINE void octoSpiTestEnableDisableMemoryMappedMode(octoSpiDevice_t *octoSpi) { OCTOSPI_TypeDef *instance = octoSpi->dev; diff --git a/src/platform/STM32/bus_quadspi_hal.c b/src/platform/STM32/bus_quadspi_hal.c index 5c93f1f3a6..bc119ee796 100644 --- a/src/platform/STM32/bus_quadspi_hal.c +++ b/src/platform/STM32/bus_quadspi_hal.c @@ -37,7 +37,7 @@ #include "pg/bus_quadspi.h" -static void Error_Handler(void) { while (1) { } } +static void Error_Handler(void) { while (1); } void quadSpiInitDevice(QUADSPIDevice device) { @@ -134,7 +134,7 @@ static uint32_t quadSpi_addressSizeFromValue(uint8_t addressSize) /** * Return true if the bus is currently in the middle of a transmission. */ -bool quadSpiIsBusBusy(QUADSPI_TypeDef *instance) +LOCAL_UNUSED_FUNCTION static bool quadSpiIsBusBusy(QUADSPI_TypeDef *instance) { QUADSPIDevice device = quadSpiDeviceByInstance(instance); if(quadSpiDevice[device].hquadSpi.State == HAL_QSPI_STATE_BUSY) @@ -145,7 +145,7 @@ bool quadSpiIsBusBusy(QUADSPI_TypeDef *instance) #define QUADSPI_DEFAULT_TIMEOUT 10 -void quadSpiSelectDevice(QUADSPI_TypeDef *instance) +static void quadSpiSelectDevice(QUADSPI_TypeDef *instance) { QUADSPIDevice device = quadSpiDeviceByInstance(instance); @@ -174,7 +174,7 @@ void quadSpiSelectDevice(QUADSPI_TypeDef *instance) } } -void quadSpiDeselectDevice(QUADSPI_TypeDef *instance) +static void quadSpiDeselectDevice(QUADSPI_TypeDef *instance) { QUADSPIDevice device = quadSpiDeviceByInstance(instance); diff --git a/src/platform/STM32/dma_stm32f4xx.c b/src/platform/STM32/dma_stm32f4xx.c index 97311e2c06..6f948a039e 100644 --- a/src/platform/STM32/dma_stm32f4xx.c +++ b/src/platform/STM32/dma_stm32f4xx.c @@ -82,7 +82,7 @@ void dmaEnable(dmaIdentifier_e identifier) #define RETURN_TCIF_FLAG(s, n) if (s == DMA1_Stream ## n || s == DMA2_Stream ## n) return DMA_IT_TCIF ## n -uint32_t dmaFlag_IT_TCIF(const dmaResource_t *stream) +static uint32_t dmaFlag_IT_TCIF(const dmaResource_t *stream) { RETURN_TCIF_FLAG((DMA_ARCH_TYPE *)stream, 0); RETURN_TCIF_FLAG((DMA_ARCH_TYPE *)stream, 1); diff --git a/src/platform/STM32/dshot_bitbang_ll.c b/src/platform/STM32/dshot_bitbang_ll.c index dffd0ed77c..8a39c2d3b8 100644 --- a/src/platform/STM32/dshot_bitbang_ll.c +++ b/src/platform/STM32/dshot_bitbang_ll.c @@ -124,7 +124,7 @@ void bbTimerChannelInit(bbPort_t *bbPort) } #ifdef USE_DMA_REGISTER_CACHE -void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) +static void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) { #if defined(STM32F7) || defined(STM32H7) ((DMA_ARCH_TYPE *)dmaResource)->CR = dmaRegCache->CR; diff --git a/src/platform/STM32/dshot_bitbang_stdperiph.c b/src/platform/STM32/dshot_bitbang_stdperiph.c index 122f2f5718..32fdffa28a 100644 --- a/src/platform/STM32/dshot_bitbang_stdperiph.c +++ b/src/platform/STM32/dshot_bitbang_stdperiph.c @@ -107,7 +107,7 @@ void bbTimerChannelInit(bbPort_t *bbPort) #ifdef USE_DMA_REGISTER_CACHE -void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) +static void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache) { ((DMA_Stream_TypeDef *)dmaResource)->CR = dmaRegCache->CR; ((DMA_Stream_TypeDef *)dmaResource)->FCR = dmaRegCache->FCR; diff --git a/src/platform/STM32/exti.c b/src/platform/STM32/exti.c index bc9c6c464c..3f76ab8987 100644 --- a/src/platform/STM32/exti.c +++ b/src/platform/STM32/exti.c @@ -88,12 +88,6 @@ void EXTIInit(void) #if defined(STM32F4) /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); -#ifdef REMAP_TIM16_DMA - SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM16, ENABLE); -#endif -#ifdef REMAP_TIM17_DMA - SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, ENABLE); -#endif #endif memset(extiChannelRecs, 0, sizeof(extiChannelRecs)); memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority)); @@ -211,7 +205,7 @@ void EXTIDisable(IO_t io) #define EXTI_EVENT_MASK 0xFFFF // first 16 bits only, see also definition of extiChannelRecs. -void EXTI_IRQHandler(uint32_t mask) +static void EXTI_IRQHandler(uint32_t mask) { uint32_t exti_active = (EXTI_REG_IMR & EXTI_REG_PR) & mask; diff --git a/src/platform/STM32/light_ws2811strip_hal.c b/src/platform/STM32/light_ws2811strip_hal.c index 6a654f4ea6..bdb9487851 100644 --- a/src/platform/STM32/light_ws2811strip_hal.c +++ b/src/platform/STM32/light_ws2811strip_hal.c @@ -42,7 +42,7 @@ static IO_t ws2811IO = IO_NONE; static TIM_HandleTypeDef TimHandle; static uint16_t timerChannel = 0; -FAST_IRQ_HANDLER void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +static FAST_IRQ_HANDLER void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) { HAL_DMA_IRQHandler(TimHandle.hdma[descriptor->userParam]); TIM_DMACmd(&TimHandle, timerChannel, DISABLE); diff --git a/src/platform/STM32/mk/STM32H5.mk b/src/platform/STM32/mk/STM32H5.mk index 90a30cc32b..13c5a59cb3 100644 --- a/src/platform/STM32/mk/STM32H5.mk +++ b/src/platform/STM32/mk/STM32H5.mk @@ -112,22 +112,18 @@ DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h563_2m.ld STARTUP_SRC = STM32/startup/startup_stm32h563xx.s MCU_FLASH_SIZE := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 - # end H563xx - +else +$(error Unknown MCU for STM32H5 target) +endif ifneq ($(DEBUG),GDB) OPTIMISE_DEFAULT := -Os OPTIMISE_SPEED := -Os OPTIMISE_SIZE := -Os - LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) endif -else -$(error Unknown MCU for STM32H5 target) -endif - ifeq ($(LD_SCRIPT),) LD_SCRIPT = $(DEFAULT_LD_SCRIPT) endif diff --git a/src/platform/STM32/platform_mcu.h b/src/platform/STM32/platform_mcu.h index 69522ba54a..9dd2114b98 100644 --- a/src/platform/STM32/platform_mcu.h +++ b/src/platform/STM32/platform_mcu.h @@ -417,4 +417,5 @@ extern uint8_t _dmaram_end__; #define DMA_TRAIT_CHANNEL 1 #endif +#define SERIAL_TRAIT_PIN_CONFIG 1 #define USB_DP_PIN PA12 diff --git a/src/platform/STM32/pwm_output_hw.c b/src/platform/STM32/pwm_output_hw.c index 67284840cb..99a2a3ce69 100644 --- a/src/platform/STM32/pwm_output_hw.c +++ b/src/platform/STM32/pwm_output_hw.c @@ -113,7 +113,7 @@ static void pwmWriteStandard(uint8_t index, float value) *motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset); } -void pwmShutdownPulsesForAllMotors(void) +static void pwmShutdownPulsesForAllMotors(void) { for (int index = 0; pwmMotorCount; index++) { // Set the compare register to 0, which stops the output pulsing if the timer overflows @@ -123,18 +123,18 @@ void pwmShutdownPulsesForAllMotors(void) } } -void pwmDisableMotors(void) +static void pwmDisableMotors(void) { pwmShutdownPulsesForAllMotors(); } -bool pwmEnableMotors(void) +static bool pwmEnableMotors(void) { /* check motors can be enabled */ return pwmMotorCount > 0; } -bool pwmIsMotorEnabled(unsigned index) +static bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } diff --git a/src/platform/STM32/sdio_f4xx.c b/src/platform/STM32/sdio_f4xx.c index 6f9b7cd1fe..6b944a020b 100644 --- a/src/platform/STM32/sdio_f4xx.c +++ b/src/platform/STM32/sdio_f4xx.c @@ -1113,7 +1113,7 @@ static SD_Error_t SD_WideBusOperationConfig(uint32_t WideMode) * This API must be used after "Transfer State" * @retval SD Card error state */ -SD_Error_t SD_HighSpeed(void) +static SD_Error_t SD_HighSpeed(void) { SD_Error_t ErrorState; uint8_t SD_hs[64] = {0}; @@ -1192,7 +1192,7 @@ SD_Error_t SD_HighSpeed(void) * @brief Gets the current card's data status. * @retval Data Transfer state */ -SD_Error_t SD_GetStatus(void) +static SD_Error_t SD_GetStatus(void) { SD_Error_t ErrorState; uint32_t Response1; @@ -1697,7 +1697,7 @@ SD_Error_t SD_Init(void) /** * @brief This function handles SD card interrupt request. */ -void SDIO_IRQHandler(void) +LOCAL_UNUSED_FUNCTION static void SDIO_IRQHandler(void) { // Check for SDIO interrupt flags if ((SDIO->STA & SDIO_STA_DATAEND) != 0) { diff --git a/src/platform/STM32/sdio_f7xx.c b/src/platform/STM32/sdio_f7xx.c index d3edd83df8..2f1bc62b5c 100644 --- a/src/platform/STM32/sdio_f7xx.c +++ b/src/platform/STM32/sdio_f7xx.c @@ -1178,7 +1178,7 @@ SD_Error_t HAL_SD_HighSpeed(void) * @brief Gets the current card's data status. * @retval Data Transfer state */ -SD_Error_t SD_GetStatus(void) +static SD_Error_t SD_GetStatus(void) { SD_Error_t ErrorState; uint32_t Response1; diff --git a/src/platform/STM32/startup/system_stm32f4xx.c b/src/platform/STM32/startup/system_stm32f4xx.c index dc8306d008..59283846c4 100644 --- a/src/platform/STM32/startup/system_stm32f4xx.c +++ b/src/platform/STM32/startup/system_stm32f4xx.c @@ -460,7 +460,7 @@ static const pllConfig_t overclockLevels[] = { #define PLL_R 7 // PLL_R output is not used, can be any descent number #endif -void SystemInitPLLParameters(void) +static void SystemInitPLLParameters(void) { /* PLL setting for overclocking */ diff --git a/src/platform/STM32/startup/system_stm32h7xx.c b/src/platform/STM32/startup/system_stm32h7xx.c index 312f3569aa..809bbea326 100644 --- a/src/platform/STM32/startup/system_stm32h7xx.c +++ b/src/platform/STM32/startup/system_stm32h7xx.c @@ -76,6 +76,8 @@ #include "drivers/memprot.h" #include "drivers/system.h" +#include "system_stm32f7xx.h" + #define HSI_FREQ ((uint32_t)64000000) // Frequency of HSI is 64Mhz on all H7 variants. // If `HSE_VALUE` isn't specified, use HSI. This allows HSI to be selected as the PLL source @@ -176,7 +178,7 @@ static void ErrorHandler(void) while (1); } -void HandleStuckSysTick(void) +static void HandleStuckSysTick(void) { uint32_t tickStart = HAL_GetTick(); uint32_t tickEnd = 0; @@ -707,7 +709,7 @@ void CRS_IRQHandler(void) } #endif -void initialiseD2MemorySections(void) +static void initialiseD2MemorySections(void) { /* Load DMA_DATA variable intializers into D2 RAM */ extern uint8_t _sdmaram_bss; diff --git a/src/platform/STM32/system_stm32g4xx.c b/src/platform/STM32/system_stm32g4xx.c index 313ff9dcdc..b05e6f66d7 100644 --- a/src/platform/STM32/system_stm32g4xx.c +++ b/src/platform/STM32/system_stm32g4xx.c @@ -110,7 +110,7 @@ typedef struct isrVector_s { resetHandler_t *resetHandler; } isrVector_t; -void systemJumpToBootloader(void) +static void systemJumpToBootloader(void) { //DeInit all used peripherals HAL_RCC_DeInit(); diff --git a/src/platform/STM32/system_stm32h7xx.c b/src/platform/STM32/system_stm32h7xx.c index 29ae3bef79..69871c1695 100644 --- a/src/platform/STM32/system_stm32h7xx.c +++ b/src/platform/STM32/system_stm32h7xx.c @@ -30,7 +30,7 @@ void SystemClock_Config(void); -void configureMasterClockOutputs(void) +LOCAL_UNUSED_FUNCTION static void configureMasterClockOutputs(void) { // Initialize pins for MCO1 and MCO2 for clock testing/verification @@ -180,7 +180,7 @@ void systemResetToBootloader(bootloaderRequestType_e requestType) typedef void *(*bootJumpPtr)(void); -void systemJumpToBootloader(void) +static void systemJumpToBootloader(void) { __SYSCFG_CLK_ENABLE(); diff --git a/src/platform/STM32/timer_def.h b/src/platform/STM32/timer_def.h index c8aae1f128..d31af27c39 100644 --- a/src/platform/STM32/timer_def.h +++ b/src/platform/STM32/timer_def.h @@ -747,6 +747,11 @@ #define DEF_TIM_AF__PB14__TCH_TIM12_CH1 D(2, 12) #define DEF_TIM_AF__PB15__TCH_TIM12_CH2 D(2, 12) +#define DEF_TIM_AF__PB0__TCH_TIM8_CH2N D(3, 8) +#define DEF_TIM_AF__PB1__TCH_TIM8_CH3N D(3, 8) +#define DEF_TIM_AF__PB14__TCH_TIM8_CH2N D(3, 8) +#define DEF_TIM_AF__PB15__TCH_TIM8_CH3N D(3, 8) + //PORTC #define DEF_TIM_AF__PC6__TCH_TIM3_CH1 D(2, 3) #define DEF_TIM_AF__PC7__TCH_TIM3_CH2 D(2, 3) @@ -1142,7 +1147,7 @@ #elif defined(STM32H7) -#define FULL_TIMER_CHANNEL_COUNT 87 +#define FULL_TIMER_CHANNEL_COUNT 91 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(12) | TIM_N(13) | TIM_N(14) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) #define HARDWARE_TIMER_DEFINITION_COUNT 17 #define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(6) | BIT(7) | BIT(8) | BIT(15) | BIT(16) | BIT(17) ) diff --git a/src/platform/STM32/timer_hal.c b/src/platform/STM32/timer_hal.c index 242ac89141..9f68624eca 100644 --- a/src/platform/STM32/timer_hal.c +++ b/src/platform/STM32/timer_hal.c @@ -329,7 +329,7 @@ uint8_t timerInputIrq(const TIM_TypeDef *tim) return 0; } -void timerNVICConfigure(uint8_t irq) +static void timerNVICConfigure(uint8_t irq) { HAL_NVIC_SetPriority(irq, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER)); HAL_NVIC_EnableIRQ(irq); diff --git a/src/platform/STM32/timer_stdperiph.c b/src/platform/STM32/timer_stdperiph.c index b225072caa..f12fd5547b 100644 --- a/src/platform/STM32/timer_stdperiph.c +++ b/src/platform/STM32/timer_stdperiph.c @@ -310,7 +310,7 @@ uint8_t timerInputIrq(const TIM_TypeDef *tim) return 0; } -void timerNVICConfigure(uint8_t irq) +static void timerNVICConfigure(uint8_t irq) { NVIC_InitTypeDef NVIC_InitStructure; @@ -837,10 +837,6 @@ void timerInit(void) { memset(timerConfig, 0, sizeof(timerConfig)); -#if defined(PARTIAL_REMAP_TIM3) - GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE); -#endif - /* enable the timer peripherals */ for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) { RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE); diff --git a/src/platform/STM32/timer_stm32h7xx.c b/src/platform/STM32/timer_stm32h7xx.c index 78e066ca8e..3462e9d7f2 100644 --- a/src/platform/STM32/timer_stm32h7xx.c +++ b/src/platform/STM32/timer_stm32h7xx.c @@ -71,10 +71,8 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM5, CH4, PA3, 0, 0, 0), DEF_TIM(TIM3, CH1, PA6, 0, 0, 0), DEF_TIM(TIM3, CH2, PA7, 0, 0, 0), - DEF_TIM(TIM8, CH1N, PA5, 0, 0, 0), DEF_TIM(TIM8, CH1N, PA7, 0, 0, 0), - DEF_TIM(TIM13, CH1, PA6, 0, 0, 0), DEF_TIM(TIM14, CH1, PA7, 0, 0, 0), @@ -104,16 +102,19 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM4, CH2, PB7, 0, 0, 0), DEF_TIM(TIM4, CH3, PB8, 0, 0, 0), DEF_TIM(TIM4, CH4, PB9, 0, 0, 0), - DEF_TIM(TIM12, CH1, PB14, 0, 0, 0), DEF_TIM(TIM12, CH2, PB15, 0, 0, 0), + DEF_TIM(TIM8, CH2N, PB0, 0, 0, 0), + DEF_TIM(TIM8, CH3N, PB1, 0, 0, 0), + DEF_TIM(TIM8, CH2N, PB14, 0, 0, 0), + DEF_TIM(TIM8, CH3N, PB15, 0, 0, 0), + // Port C DEF_TIM(TIM3, CH1, PC6, 0, 0, 0), DEF_TIM(TIM3, CH2, PC7, 0, 0, 0), DEF_TIM(TIM3, CH3, PC8, 0, 0, 0), DEF_TIM(TIM3, CH4, PC9, 0, 0, 0), - DEF_TIM(TIM8, CH1, PC6, 0, 0, 0), DEF_TIM(TIM8, CH2, PC7, 0, 0, 0), DEF_TIM(TIM8, CH3, PC8, 0, 0, 0), @@ -133,7 +134,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM1, CH3N, PE12, 0, 0, 0), DEF_TIM(TIM1, CH3, PE13, 0, 0, 0), DEF_TIM(TIM1, CH4, PE14, 0, 0, 0), - DEF_TIM(TIM15, CH1N, PE4, 0, 0, 0), DEF_TIM(TIM15, CH1, PE5, 0, 0, 0), DEF_TIM(TIM15, CH2, PE6, 0, 0, 0), @@ -143,20 +143,25 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM17, CH1, PF7, 0, 0, 0), DEF_TIM(TIM16, CH1N, PF8, 0, 0, 0), DEF_TIM(TIM17, CH1N, PF9, 0, 0, 0), - DEF_TIM(TIM13, CH1N, PF8, 0, 0, 0), DEF_TIM(TIM14, CH1N, PF9, 0, 0, 0), // Port H -// Port H is not available for LPQFP-100 or 144 and TFBGA-100 package -// DEF_TIM(TIM12, CH1, PH6, 0, 0, 0), -// DEF_TIM(TIM12, CH2, PH9, 0, 0, 0), -// DEF_TIM(TIM5, CH1, PH10, 0, 0, 0), -// DEF_TIM(TIM5, CH2, PH11, 0, 0, 0), -// DEF_TIM(TIM5, CH3, PH12, 0, 0, 0), -// DEF_TIM(TIM8, CH1N, PH13, 0, 0, 0), -// DEF_TIM(TIM8, CH2N, PH14, 0, 0, 0), -// DEF_TIM(TIM8, CH3N, PH15, 0, 0, 0), + DEF_TIM(TIM5, CH1, PH10, 0, 0, 0), + DEF_TIM(TIM5, CH2, PH11, 0, 0, 0), + DEF_TIM(TIM5, CH3, PH12, 0, 0, 0), + DEF_TIM(TIM8, CH1N, PH13, 0, 0, 0), + DEF_TIM(TIM8, CH2N, PH14, 0, 0, 0), + DEF_TIM(TIM8, CH3N, PH15, 0, 0, 0), + DEF_TIM(TIM12, CH1, PH6, 0, 0, 0), + DEF_TIM(TIM12, CH2, PH9, 0, 0, 0), + +// Port I + DEF_TIM(TIM5, CH4, PI0, 0, 0, 0), + DEF_TIM(TIM8, CH4, PI2, 0, 0, 0), + DEF_TIM(TIM8, CH1, PI5, 0, 0, 0), + DEF_TIM(TIM8, CH2, PI6, 0, 0, 0), + DEF_TIM(TIM8, CH3, PI7, 0, 0, 0), }; #endif diff --git a/src/platform/STM32/vcp_hal/usbd_cdc_hid.c b/src/platform/STM32/vcp_hal/usbd_cdc_hid.c index 4727b4a29f..fd17d8ea19 100644 --- a/src/platform/STM32/vcp_hal/usbd_cdc_hid.c +++ b/src/platform/STM32/vcp_hal/usbd_cdc_hid.c @@ -37,6 +37,8 @@ #include "usbd_hid.h" #include "vcp_hal/usbd_cdc_interface.h" +#include "io/usb_cdc_hid.h" + #define USB_HID_CDC_CONFIG_DESC_SIZ (USB_HID_CONFIG_DESC_SIZ - 9 + USB_CDC_CONFIG_DESC_SIZ + 8) #define HID_INTERFACE 0x0 diff --git a/src/platform/STM32/vcp_hal/usbd_conf_stm32g4xx.c b/src/platform/STM32/vcp_hal/usbd_conf_stm32g4xx.c index 3e139a813e..d10ea4f3bd 100644 --- a/src/platform/STM32/vcp_hal/usbd_conf_stm32g4xx.c +++ b/src/platform/STM32/vcp_hal/usbd_conf_stm32g4xx.c @@ -714,7 +714,7 @@ void USBD_LL_Delay(uint32_t Delay) * @param size: Size of allocated memory * @retval None */ -void *USBD_static_malloc(uint32_t size) +LOCAL_UNUSED_FUNCTION static void *USBD_static_malloc(uint32_t size) { UNUSED(size); @@ -727,7 +727,7 @@ void *USBD_static_malloc(uint32_t size) * @param p: Pointer to allocated memory address * @retval None */ -void USBD_static_free(void *p) +LOCAL_UNUSED_FUNCTION static void USBD_static_free(void *p) { UNUSED(p); } diff --git a/src/platform/STM32/vcpf4/usb_bsp.c b/src/platform/STM32/vcpf4/usb_bsp.c index 28da4eff32..af871b15d3 100644 --- a/src/platform/STM32/vcpf4/usb_bsp.c +++ b/src/platform/STM32/vcpf4/usb_bsp.c @@ -30,12 +30,12 @@ #include "drivers/nvic.h" #include "drivers/io.h" -void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) +LOCAL_UNUSED_FUNCTION static void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) { (void)pdev; } -void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) +LOCAL_UNUSED_FUNCTION static void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) { (void)pdev; (void)state; diff --git a/src/platform/STM32/vcpf4/usb_cdc_hid.c b/src/platform/STM32/vcpf4/usb_cdc_hid.c index 8c4b604593..637260fc4b 100644 --- a/src/platform/STM32/vcpf4/usb_cdc_hid.c +++ b/src/platform/STM32/vcpf4/usb_cdc_hid.c @@ -25,6 +25,8 @@ #ifdef USE_USB_CDC_HID #include "vcpf4/usbd_cdc_vcp.h" +#include "io/usb_cdc_hid.h" + #include "usbd_hid_core.h" void sendReport(uint8_t *report, uint8_t len) diff --git a/src/platform/STM32/vcpf4/usbd_cdc_vcp.c b/src/platform/STM32/vcpf4/usbd_cdc_vcp.c index d3c641e020..d27b9589af 100644 --- a/src/platform/STM32/vcpf4/usbd_cdc_vcp.c +++ b/src/platform/STM32/vcpf4/usbd_cdc_vcp.c @@ -101,7 +101,7 @@ static uint16_t VCP_DeInit(void) return USBD_OK; } -void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1) +static void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1) { plc2->bitrate = plc1->bitrate; plc2->format = plc1->format; diff --git a/src/platform/common/stm32/bus_spi_hw.c b/src/platform/common/stm32/bus_spi_hw.c index 653690ecfe..d294455298 100644 --- a/src/platform/common/stm32/bus_spi_hw.c +++ b/src/platform/common/stm32/bus_spi_hw.c @@ -174,10 +174,12 @@ FAST_IRQ_HANDLER static void spiTxIrqHandler(dmaChannelDescriptor_t* descriptor) uint16_t spiCalculateDivider(uint32_t freq) { -#if defined(STM32F4) || defined(STM32G4) || defined(STM32F7) || defined(APM32F4) +#if defined(STM32F4) || defined(STM32F7) || defined(APM32F4) uint32_t spiClk = SystemCoreClock / 2; #elif defined(STM32H7) uint32_t spiClk = 100000000; +#elif defined(STM32G4) + uint32_t spiClk = SystemCoreClock; #elif defined(AT32F4) if(freq > 36000000){ freq = 36000000; diff --git a/src/platform/common/stm32/config_flash.c b/src/platform/common/stm32/config_flash.c index c94fb082b1..4e79ef7a4f 100644 --- a/src/platform/common/stm32/config_flash.c +++ b/src/platform/common/stm32/config_flash.c @@ -24,6 +24,7 @@ #include "platform.h" #include "drivers/system.h" #include "config/config_streamer.h" +#include "config/config_streamer_impl.h" #if defined(CONFIG_IN_FLASH) diff --git a/src/platform/common/stm32/system.c b/src/platform/common/stm32/system.c index d21e0ee956..aa663e2950 100644 --- a/src/platform/common/stm32/system.c +++ b/src/platform/common/stm32/system.c @@ -31,6 +31,7 @@ #include "drivers/nvic.h" #include "drivers/resource.h" #include "drivers/sound_beeper.h" +#include "drivers/time.h" #include "drivers/system.h" diff --git a/src/test/unit/io_serial_unittest.cc b/src/test/unit/io_serial_unittest.cc index 4f5a199894..c0f5975052 100644 --- a/src/test/unit/io_serial_unittest.cc +++ b/src/test/unit/io_serial_unittest.cc @@ -33,7 +33,7 @@ extern "C" { #include "pg/pg_ids.h" #include "pg/rx.h" - void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable); + void serialInit(bool softserialEnabled); PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0); PG_REGISTER(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0); @@ -45,7 +45,7 @@ extern "C" { TEST(IoSerialTest, TestFindPortConfig) { // given - serialInit(false, SERIAL_PORT_NONE); + serialInit(false); // when const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);