diff --git a/make/source.mk b/make/source.mk index d65014603e..d53d2b25ba 100644 --- a/make/source.mk +++ b/make/source.mk @@ -65,7 +65,6 @@ COMMON_SRC = \ pg/beeper_dev.c \ pg/bus_i2c.c \ pg/bus_spi.c \ - pg/flash.c \ pg/max7456.c \ pg/pg.c \ pg/rx_pwm.c \ @@ -203,7 +202,6 @@ else COMMON_SRC := $(COMMON_SRC) $(FC_SRC) $(COMMON_DEVICE_SRC) endif - SPEED_OPTIMISED_SRC := "" SIZE_OPTIMISED_SRC := "" @@ -361,7 +359,8 @@ endif ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) SRC += \ drivers/flash_m25p16.c \ - io/flashfs.c + io/flashfs.c \ + pg/flash.c endif SRC += $(COMMON_SRC) diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 731bde0fa8..3a4e972860 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -42,6 +42,7 @@ #include "config/feature.h" +#include "drivers/flash.h" #include "drivers/time.h" #include "drivers/sdcard.h" diff --git a/src/main/config/feature.c b/src/main/config/feature.c index b5a83fa803..215d0e5ddb 100644 --- a/src/main/config/feature.c +++ b/src/main/config/feature.c @@ -28,6 +28,12 @@ static uint32_t activeFeaturesLatch = 0; +PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); + +PG_RESET_TEMPLATE(featureConfig_t, featureConfig, + .enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE +); + void intFeatureSet(uint32_t mask, uint32_t *features) { *features |= mask; diff --git a/src/main/config/feature.h b/src/main/config/feature.h index 40bcd0ae4b..f340875850 100644 --- a/src/main/config/feature.h +++ b/src/main/config/feature.h @@ -19,6 +19,40 @@ #include "pg/pg.h" +#ifndef DEFAULT_FEATURES +#define DEFAULT_FEATURES 0 +#endif +#ifndef DEFAULT_RX_FEATURE +#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM +#endif + +typedef enum { + FEATURE_RX_PPM = 1 << 0, + FEATURE_INFLIGHT_ACC_CAL = 1 << 2, + FEATURE_RX_SERIAL = 1 << 3, + FEATURE_MOTOR_STOP = 1 << 4, + FEATURE_SERVO_TILT = 1 << 5, + FEATURE_SOFTSERIAL = 1 << 6, + FEATURE_GPS = 1 << 7, + FEATURE_RANGEFINDER = 1 << 9, + FEATURE_TELEMETRY = 1 << 10, + FEATURE_3D = 1 << 12, + FEATURE_RX_PARALLEL_PWM = 1 << 13, + FEATURE_RX_MSP = 1 << 14, + FEATURE_RSSI_ADC = 1 << 15, + FEATURE_LED_STRIP = 1 << 16, + FEATURE_DASHBOARD = 1 << 17, + FEATURE_OSD = 1 << 18, + FEATURE_CHANNEL_FORWARDING = 1 << 20, + FEATURE_TRANSPONDER = 1 << 21, + FEATURE_AIRMODE = 1 << 22, + FEATURE_RX_SPI = 1 << 25, + FEATURE_SOFTSPI = 1 << 26, + FEATURE_ESC_SENSOR = 1 << 27, + FEATURE_ANTI_GRAVITY = 1 << 28, + FEATURE_DYNAMIC_FILTER = 1 << 29, +} features_e; + typedef struct featureConfig_s { uint32_t enabledFeatures; } featureConfig_t; diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 13c939a01f..67c13ebb9b 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -19,15 +19,20 @@ #include #include "platform.h" -#include "common/utils.h" #ifdef USE_ADC +#include "common/utils.h" + #include "build/build_config.h" #include "build/debug.h" +#include "drivers/adc_impl.h" +#include "drivers/io.h" + +#include "pg/adc.h" + #include "adc.h" -#include "adc_impl.h" //#define DEBUG_ADC_CHANNELS @@ -111,11 +116,4 @@ bool adcVerifyPin(ioTag_t tag, ADCDevice device) return false; } - -#else -uint16_t adcGetChannel(uint8_t channel) -{ - UNUSED(channel); - return 0; -} #endif diff --git a/src/main/drivers/bus_i2c_config.c b/src/main/drivers/bus_i2c_config.c index b7d7d5c720..8eed1c1c2b 100644 --- a/src/main/drivers/bus_i2c_config.c +++ b/src/main/drivers/bus_i2c_config.c @@ -82,5 +82,4 @@ void i2cHardwareConfigure(const i2cConfig_t *i2cConfig) } } } - #endif // defined(USE_I2C) && !defined(USE_SOFT_I2C) diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 8ef69ea129..59a13c25df 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -22,6 +22,9 @@ #include "drivers/bus.h" #include "drivers/rcc_types.h" +#include "pg/pg.h" +#include "pg/pg_ids.h" + #if defined(STM32F4) || defined(STM32F3) #define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN) diff --git a/src/main/drivers/display.h b/src/main/drivers/display.h index f8ae22819e..edaafc0e8f 100644 --- a/src/main/drivers/display.h +++ b/src/main/drivers/display.h @@ -18,6 +18,7 @@ #pragma once struct displayPortVTable_s; + typedef struct displayPort_s { const struct displayPortVTable_s *vTable; void *device; @@ -32,6 +33,8 @@ typedef struct displayPort_s { int8_t grabCount; } displayPort_t; +// displayPort_t is used as a parameter group in 'displayport_msp.h' and 'displayport_max7456`.h'. Treat accordingly! + typedef struct displayPortVTable_s { int (*grab)(displayPort_t *displayPort); int (*release)(displayPort_t *displayPort); diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h index 7b7dfc78a7..e2d20f1d40 100644 --- a/src/main/drivers/flash.h +++ b/src/main/drivers/flash.h @@ -18,7 +18,6 @@ #pragma once #include -#include "drivers/io_types.h" typedef struct flashGeometry_s { uint16_t sectors; // Count of the number of erasable blocks on the device diff --git a/src/main/drivers/rangefinder/rangefinder.h b/src/main/drivers/rangefinder/rangefinder.h index d9d8fec4e3..464be5efe5 100644 --- a/src/main/drivers/rangefinder/rangefinder.h +++ b/src/main/drivers/rangefinder/rangefinder.h @@ -24,15 +24,12 @@ #define RANGEFINDER_HARDWARE_FAILURE (-2) #define RANGEFINDER_NO_NEW_DATA (-3) -struct rangefinderDev_s; - typedef struct rangefinderHardwarePins_s { ioTag_t triggerTag; ioTag_t echoTag; } rangefinderHardwarePins_t; struct rangefinderDev_s; - typedef void (*rangefinderOpInitFuncPtr)(struct rangefinderDev_s * dev); typedef void (*rangefinderOpStartFuncPtr)(struct rangefinderDev_s * dev); typedef int32_t (*rangefinderOpReadFuncPtr)(struct rangefinderDev_s * dev); diff --git a/src/main/drivers/rx/rx_pwm.c b/src/main/drivers/rx/rx_pwm.c index 31eba0d427..83873f69f3 100644 --- a/src/main/drivers/rx/rx_pwm.c +++ b/src/main/drivers/rx/rx_pwm.c @@ -402,7 +402,6 @@ void pwmRxInit(const pwmConfig_t *pwmConfig) } } -#define UNUSED_PPM_TIMER_REFERENCE 0 #define FIRST_PWM_PORT 0 void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer) diff --git a/src/main/drivers/rx/rx_pwm.h b/src/main/drivers/rx/rx_pwm.h index 922b33435f..9993ecdfdc 100644 --- a/src/main/drivers/rx/rx_pwm.h +++ b/src/main/drivers/rx/rx_pwm.h @@ -17,8 +17,6 @@ #pragma once -#include "drivers/io_types.h" - typedef enum { INPUT_FILTERING_DISABLED = 0, INPUT_FILTERING_ENABLED diff --git a/src/main/fc/config.c b/src/main/fc/config.c index b630b20e46..920a761a27 100644 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -22,35 +22,12 @@ #include "platform.h" -#include "build/build_config.h" #include "build/debug.h" -#include "blackbox/blackbox_io.h" - -#include "cms/cms.h" - -#include "common/axis.h" -#include "common/color.h" -#include "common/filter.h" -#include "common/maths.h" - #include "config/config_eeprom.h" #include "config/feature.h" -#include "drivers/accgyro/accgyro.h" -#include "drivers/bus_spi.h" -#include "drivers/compass/compass.h" -#include "drivers/inverter.h" -#include "drivers/io.h" -#include "drivers/light_led.h" -#include "drivers/light_ws2811strip.h" -#include "drivers/max7456.h" -#include "drivers/pwm_esc_detect.h" -#include "drivers/pwm_output.h" -#include "drivers/rx/rx_spi.h" -#include "drivers/sensor.h" #include "drivers/system.h" -#include "drivers/timer.h" #include "fc/config.h" #include "fc/controlrate_profile.h" @@ -58,9 +35,7 @@ #include "fc/fc_rc.h" #include "fc/rc_adjustments.h" #include "fc/rc_controls.h" -#include "fc/runtime_config.h" -#include "flight/altitude.h" #include "flight/failsafe.h" #include "flight/imu.h" #include "flight/mixer.h" @@ -69,52 +44,26 @@ #include "flight/servos.h" #include "io/beeper.h" -#include "io/gimbal.h" -#include "io/gps.h" #include "io/ledstrip.h" -#include "io/motors.h" -#include "io/osd.h" #include "io/serial.h" -#include "io/servos.h" -#include "io/vtx_control.h" #include "pg/beeper.h" #include "pg/pg.h" #include "pg/pg_ids.h" #include "rx/rx.h" -#include "rx/rx_spi.h" #include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/battery.h" -#include "sensors/boardalignment.h" -#include "sensors/compass.h" #include "sensors/gyro.h" -#include "sensors/sensors.h" - -#include "telemetry/telemetry.h" #ifndef USE_OSD_SLAVE pidProfile_t *currentPidProfile; #endif -#ifndef DEFAULT_FEATURES -#define DEFAULT_FEATURES 0 -#endif -#ifndef DEFAULT_RX_FEATURE -#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM -#endif #ifndef RX_SPI_DEFAULT_PROTOCOL #define RX_SPI_DEFAULT_PROTOCOL 0 #endif -PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); - -PG_RESET_TEMPLATE(featureConfig_t, featureConfig, - .enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE -); - PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 0); PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig, @@ -123,13 +72,6 @@ PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2); -#ifdef USE_OSD_SLAVE -PG_RESET_TEMPLATE(systemConfig_t, systemConfig, - .debug_mode = DEBUG_MODE, - .task_statistics = true, - .boardIdentifier = TARGET_BOARD_IDENTIFIER -); -#else PG_RESET_TEMPLATE(systemConfig_t, systemConfig, .pidProfileIndex = 0, .activeRateProfile = 0, @@ -139,7 +81,6 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig, .powerOnArmingGraceTime = 5, .boardIdentifier = TARGET_BOARD_IDENTIFIER ); -#endif #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS #define FIRST_PORT_INDEX 1 diff --git a/src/main/fc/config.h b/src/main/fc/config.h index e3e315f45b..96b6065a96 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -22,49 +22,14 @@ #include "pg/pg.h" -#include "drivers/flash.h" -#include "drivers/serial.h" -#include "drivers/bus_i2c.h" - -typedef enum { - FEATURE_RX_PPM = 1 << 0, - FEATURE_INFLIGHT_ACC_CAL = 1 << 2, - FEATURE_RX_SERIAL = 1 << 3, - FEATURE_MOTOR_STOP = 1 << 4, - FEATURE_SERVO_TILT = 1 << 5, - FEATURE_SOFTSERIAL = 1 << 6, - FEATURE_GPS = 1 << 7, - FEATURE_RANGEFINDER = 1 << 9, - FEATURE_TELEMETRY = 1 << 10, - FEATURE_3D = 1 << 12, - FEATURE_RX_PARALLEL_PWM = 1 << 13, - FEATURE_RX_MSP = 1 << 14, - FEATURE_RSSI_ADC = 1 << 15, - FEATURE_LED_STRIP = 1 << 16, - FEATURE_DASHBOARD = 1 << 17, - FEATURE_OSD = 1 << 18, - FEATURE_CHANNEL_FORWARDING = 1 << 20, - FEATURE_TRANSPONDER = 1 << 21, - FEATURE_AIRMODE = 1 << 22, - FEATURE_RX_SPI = 1 << 25, - FEATURE_SOFTSPI = 1 << 26, - FEATURE_ESC_SENSOR = 1 << 27, - FEATURE_ANTI_GRAVITY = 1 << 28, - FEATURE_DYNAMIC_FILTER = 1 << 29, -} features_e; - #define MAX_NAME_LENGTH 16u + typedef struct pilotConfig_s { char name[MAX_NAME_LENGTH + 1]; } pilotConfig_t; -#ifdef USE_OSD_SLAVE -typedef struct systemConfig_s { - uint8_t debug_mode; - uint8_t task_statistics; - char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1]; -} systemConfig_t; -#else +PG_DECLARE(pilotConfig_t, pilotConfig); + typedef struct systemConfig_s { uint8_t pidProfileIndex; uint8_t activeRateProfile; @@ -74,10 +39,7 @@ typedef struct systemConfig_s { uint8_t powerOnArmingGraceTime; // in seconds char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1]; } systemConfig_t; -#endif // USE_OSD_SLAVE - -PG_DECLARE(pilotConfig_t, pilotConfig); PG_DECLARE(systemConfig_t, systemConfig); struct pidProfile_s; diff --git a/src/main/fc/controlrate_profile.h b/src/main/fc/controlrate_profile.h index cafd4f71fd..4534a1108c 100644 --- a/src/main/fc/controlrate_profile.h +++ b/src/main/fc/controlrate_profile.h @@ -21,6 +21,7 @@ #include "pg/pg.h" +#define CONTROL_RATE_PROFILE_COUNT 3 typedef struct controlRateConfig_s { uint8_t rcRate8; @@ -34,7 +35,6 @@ typedef struct controlRateConfig_s { uint16_t tpa_breakpoint; // Breakpoint where TPA is activated } controlRateConfig_t; -#define CONTROL_RATE_PROFILE_COUNT 3 PG_DECLARE_ARRAY(controlRateConfig_t, CONTROL_RATE_PROFILE_COUNT, controlRateProfiles); extern controlRateConfig_t *currentControlRateProfile; diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 92fe07b59c..4c39ac116c 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -35,6 +35,10 @@ #include "cms/cms_types.h" #include "drivers/accgyro/accgyro.h" +#include "drivers/camera_control.h" +#include "drivers/compass/compass.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" #include "drivers/adc.h" #include "drivers/bus.h" #include "drivers/bus_i2c.h" @@ -62,9 +66,10 @@ #include "drivers/time.h" #include "drivers/timer.h" #include "drivers/transponder_ir.h" +#include "drivers/exti.h" #include "drivers/usb_io.h" -#include "drivers/vtx_common.h" #include "drivers/vtx_rtc6705.h" +#include "drivers/vtx_common.h" #include "fc/config.h" #include "fc/fc_init.h" diff --git a/src/main/fc/rc_adjustments.h b/src/main/fc/rc_adjustments.h index f17e1acfcf..c20a804137 100644 --- a/src/main/fc/rc_adjustments.h +++ b/src/main/fc/rc_adjustments.h @@ -66,6 +66,8 @@ typedef struct adjustmentConfig_s { adjustmentData_t data; } adjustmentConfig_t; +#define MAX_ADJUSTMENT_RANGE_COUNT 15 + typedef struct adjustmentRange_s { // when aux channel is in range... uint8_t auxChannelIndex; @@ -79,6 +81,8 @@ typedef struct adjustmentRange_s { uint8_t adjustmentIndex; } adjustmentRange_t; +PG_DECLARE_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges); + #define ADJUSTMENT_INDEX_OFFSET 1 typedef struct adjustmentState_s { @@ -91,13 +95,9 @@ typedef struct adjustmentState_s { #define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 4 // enough for 4 x 3position switches / 4 aux channel #endif -#define MAX_ADJUSTMENT_RANGE_COUNT 15 - extern const char *adjustmentRangeName; extern int adjustmentRangeValue; -PG_DECLARE_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges); - void resetAdjustmentStates(void); void updateAdjustmentStates(void); struct controlRateConfig_s; diff --git a/src/main/flight/altitude.c b/src/main/flight/altitude.c index f098b96d14..59466fca15 100644 --- a/src/main/flight/altitude.c +++ b/src/main/flight/altitude.c @@ -27,6 +27,7 @@ #include "common/axis.h" #include "common/maths.h" +#include "common/utils.h" #include "pg/pg.h" #include "pg/pg_ids.h" diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index db43133fd2..0d9e7a51ee 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -81,6 +81,8 @@ typedef enum { #define SERVO_FLAPPERONS_MIN SERVO_FLAPPERON_1 #define SERVO_FLAPPERONS_MAX SERVO_FLAPPERON_2 +#define MAX_SERVO_RULES (2 * MAX_SUPPORTED_SERVOS) + typedef struct servoMixer_s { uint8_t targetChannel; // servo that receives the output of the rule uint8_t inputSource; // input channel for this rule @@ -91,12 +93,11 @@ typedef struct servoMixer_s { uint8_t box; // active rule if box is enabled, range [0;3], 0=no box, 1=BOXSERVO1, 2=BOXSERVO2, 3=BOXSERVO3 } servoMixer_t; -#define MAX_SERVO_RULES (2 * MAX_SUPPORTED_SERVOS) +PG_DECLARE_ARRAY(servoMixer_t, MAX_SERVO_RULES, customServoMixers); + #define MAX_SERVO_SPEED UINT8_MAX #define MAX_SERVO_BOXES 3 -PG_DECLARE_ARRAY(servoMixer_t, MAX_SERVO_RULES, customServoMixers); - // Custom mixer configuration typedef struct mixerRules_s { uint8_t servoRuleCount; diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index d68e7af490..4287a2a361 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -55,6 +55,7 @@ extern uint8_t __config_end; #include "config/feature.h" #include "drivers/accgyro/accgyro.h" +#include "drivers/adc.h" #include "drivers/buf_writer.h" #include "drivers/bus_spi.h" #include "drivers/compass/compass.h" @@ -69,6 +70,7 @@ extern uint8_t __config_end; #include "drivers/serial.h" #include "drivers/serial_escserial.h" #include "drivers/rangefinder/rangefinder_hcsr04.h" +#include "drivers/sound_beeper.h" #include "drivers/stack_check.h" #include "drivers/system.h" #include "drivers/transponder_ir.h" diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 27b1e4466b..9022475e4d 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -31,8 +31,8 @@ #include "drivers/adc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_spi.h" -#include "drivers/light_led.h" #include "drivers/camera_control.h" +#include "drivers/light_led.h" #include "drivers/vtx_common.h" #include "fc/config.h" diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 44cf0fa343..ede86f16a4 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -24,9 +24,10 @@ #include "config/feature.h" +#include "drivers/io.h" +#include "drivers/pwm_output.h" #include "drivers/sound_beeper.h" #include "drivers/time.h" -#include "drivers/pwm_output.h" #include "flight/mixer.h" diff --git a/src/main/io/ledstrip.h b/src/main/io/ledstrip.h index 9fe25728f8..268e5cccf8 100644 --- a/src/main/io/ledstrip.h +++ b/src/main/io/ledstrip.h @@ -170,12 +170,7 @@ static inline uint8_t ledGetParams(const ledConfig_t *lcfg) { return ((*lcfg static inline bool ledGetOverlayBit(const ledConfig_t *lcfg, int id) { return ((ledGetOverlay(lcfg) >> id) & 1); } static inline bool ledGetDirectionBit(const ledConfig_t *lcfg, int id) { return ((ledGetDirection(lcfg) >> id) & 1); } -/* -PG_DECLARE_ARR(ledConfig_t, LED_MAX_STRIP_LENGTH, ledConfigs); -PG_DECLARE_ARR(hsvColor_t, LED_CONFIGURABLE_COLOR_COUNT, colors); -PG_DECLARE_ARR(modeColorIndexes_t, LED_MODE_COUNT, modeColors); -PG_DECLARE(specialColorIndexes_t, specialColors); -*/ + bool parseColor(int index, const char *colorConfig); bool parseLedStripConfig(int ledIndex, const char *config); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 4f7beed2b7..8b277e3e3f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -51,6 +51,7 @@ #include "config/feature.h" #include "drivers/display.h" +#include "drivers/flash.h" #include "drivers/max7456_symbols.h" #include "drivers/sdcard.h" #include "drivers/time.h" diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 718113043b..608ee9c6e6 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -160,6 +160,8 @@ extern timeUs_t resumeRefreshAt; PG_DECLARE(osdConfig_t, osdConfig); +extern uint32_t resumeRefreshAt; + struct displayPort_s; void osdInit(struct displayPort_s *osdDisplayPort); void osdResetAlarms(void); diff --git a/src/main/io/transponder_ir.h b/src/main/io/transponder_ir.h index aa795bc4e6..23f5a068ab 100644 --- a/src/main/io/transponder_ir.h +++ b/src/main/io/transponder_ir.h @@ -34,10 +34,10 @@ typedef struct transponderRequirement_s { uint16_t transmitJitter; } transponderRequirement_t; -extern const transponderRequirement_t transponderRequirements[TRANSPONDER_PROVIDER_COUNT]; - PG_DECLARE(transponderConfig_t, transponderConfig); +extern const transponderRequirement_t transponderRequirements[TRANSPONDER_PROVIDER_COUNT]; + void transponderInit(void); void transponderUpdate(timeUs_t currentTimeUs); diff --git a/src/main/pg/vcd.c b/src/main/pg/vcd.c index 9a25e68446..258203c71c 100644 --- a/src/main/pg/vcd.c +++ b/src/main/pg/vcd.c @@ -15,6 +15,8 @@ * along with Cleanflight. If not, see . */ +#include "platform.h" + #include "pg/pg.h" #include "pg/pg_ids.h" diff --git a/src/main/pg/vcd.h b/src/main/pg/vcd.h index 12d9b11005..0b7662860d 100644 --- a/src/main/pg/vcd.h +++ b/src/main/pg/vcd.h @@ -17,6 +17,8 @@ #pragma once +#include "pg/pg.h" + // Video Character Display parameters enum VIDEO_SYSTEMS { diff --git a/src/main/sensors/current.c b/src/main/sensors/current.c index 5366ea52e6..99710f7bd6 100644 --- a/src/main/sensors/current.c +++ b/src/main/sensors/current.c @@ -133,11 +133,19 @@ void currentMeterADCInit(void) void currentMeterADCRefresh(int32_t lastUpdateAt) { +#ifdef USE_ADC const uint16_t iBatSample = adcGetChannel(ADC_CURRENT); currentMeterADCState.amperageLatest = currentMeterADCToCentiamps(iBatSample); currentMeterADCState.amperage = currentMeterADCToCentiamps(biquadFilterApply(&adciBatFilter, iBatSample)); updateCurrentmAhDrawnState(¤tMeterADCState.mahDrawnState, currentMeterADCState.amperageLatest, lastUpdateAt); +#else + UNUSED(lastUpdateAt); + UNUSED(currentMeterADCToCentiamps); + + currentMeterADCState.amperageLatest = 0; + currentMeterADCState.amperage = 0; +#endif } void currentMeterADCRead(currentMeter_t *meter) diff --git a/src/main/sensors/rangefinder.h b/src/main/sensors/rangefinder.h index 1ef961be8a..b7532d611e 100644 --- a/src/main/sensors/rangefinder.h +++ b/src/main/sensors/rangefinder.h @@ -18,9 +18,11 @@ #pragma once #include -#include "pg/pg.h" + #include "drivers/rangefinder/rangefinder.h" +#include "pg/pg.h" + typedef enum { RANGEFINDER_NONE = 0, RANGEFINDER_HCSR04 = 1, diff --git a/src/main/sensors/voltage.c b/src/main/sensors/voltage.c index b660a7cfcc..c482559d8a 100644 --- a/src/main/sensors/voltage.c +++ b/src/main/sensors/voltage.c @@ -144,9 +144,10 @@ STATIC_UNIT_TESTED uint16_t voltageAdcToVoltage(const uint16_t src, const voltag void voltageMeterADCRefresh(void) { for (uint8_t i = 0; i < MAX_VOLTAGE_SENSOR_ADC && i < ARRAYLEN(voltageMeterAdcChannelMap); i++) { + voltageMeterADCState_t *state = &voltageMeterADCStates[i]; +#ifdef USE_ADC // store the battery voltage with some other recent battery voltage readings - voltageMeterADCState_t *state = &voltageMeterADCStates[i]; const voltageSensorADCConfig_t *config = voltageSensorADCConfig(i); uint8_t channel = voltageMeterAdcChannelMap[i]; @@ -157,6 +158,12 @@ void voltageMeterADCRefresh(void) // always calculate the latest voltage, see getLatestVoltage() which does the calculation on demand. state->voltageFiltered = voltageAdcToVoltage(filteredSample, config); state->voltageUnfiltered = voltageAdcToVoltage(rawSample, config); +#else + UNUSED(voltageAdcToVoltage); + + state->voltageFiltered = 0; + state->voltageUnfiltered = 0; +#endif } } diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index f62df4362a..01041f5526 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -28,8 +28,7 @@ #include "drivers/light_led.h" #include "drivers/pwm_esc_detect.h" - -#include "fc/config.h" +#include "drivers/sound_beeper.h" #include "flight/mixer.h" #include "flight/pid.h" diff --git a/src/main/target/BLUEJAYF4/config.c b/src/main/target/BLUEJAYF4/config.c index ea689cb78d..40290aed02 100644 --- a/src/main/target/BLUEJAYF4/config.c +++ b/src/main/target/BLUEJAYF4/config.c @@ -26,10 +26,9 @@ #include "config/feature.h" +#include "drivers/adc.h" #include "drivers/io.h" -#include "fc/config.h" - #include "sensors/acceleration.h" #include "sensors/gyro.h" diff --git a/src/main/target/MOTOLABF4/config.c b/src/main/target/MOTOLABF4/config.c index 7d7a2b7f91..617738e125 100644 --- a/src/main/target/MOTOLABF4/config.c +++ b/src/main/target/MOTOLABF4/config.c @@ -22,9 +22,10 @@ #ifdef USE_TARGET_CONFIG -#include "telemetry/telemetry.h" #include "pg/sdcard.h" +#include "telemetry/telemetry.h" + void targetConfiguration(void) { sdcardConfigMutable()->useDma = true; diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 7c2c31debb..c5b16c3f33 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -15,9 +15,15 @@ * along with Cleanflight. If not, see . */ +// SITL (software in the loop) simulator + #pragma once -// SITL (software in the loop) simulator +#include +#include + +#include "common/utils.h" + #define TARGET_BOARD_IDENTIFIER "SITL" #define SIMULATOR_BUILD @@ -132,8 +138,6 @@ // belows are internal stuff -#include -#include uint32_t SystemCoreClock; @@ -146,8 +150,6 @@ extern uint8_t __config_start; // configured via linker script when building b extern uint8_t __config_end; #endif -#define UNUSED(x) (void)(x) - typedef enum { Mode_TEST = 0x0, diff --git a/src/main/target/YUPIF4/config.c b/src/main/target/YUPIF4/config.c index f6721e25fc..b24286adef 100644 --- a/src/main/target/YUPIF4/config.c +++ b/src/main/target/YUPIF4/config.c @@ -22,10 +22,12 @@ #ifdef USE_TARGET_CONFIG #include "blackbox/blackbox.h" -#include "fc/config.h" + #include "flight/pid.h" + #include "pg/adc.h" #include "pg/beeper_dev.h" + #include "telemetry/telemetry.h" #include "hardware_revision.h" diff --git a/src/test/unit/arming_prevention_unittest.cc b/src/test/unit/arming_prevention_unittest.cc index c411baa656..3ffd0aedb0 100644 --- a/src/test/unit/arming_prevention_unittest.cc +++ b/src/test/unit/arming_prevention_unittest.cc @@ -21,6 +21,7 @@ extern "C" { #include "blackbox/blackbox.h" #include "build/debug.h" #include "common/maths.h" + #include "config/feature.h" #include "pg/pg.h" #include "pg/pg_ids.h" #include "fc/config.h" diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc index b402b117e7..78603be43a 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -73,7 +73,6 @@ extern "C" { PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR_MIXER, 0); PG_REGISTER_ARRAY(servoParam_t, MAX_SUPPORTED_SERVOS, servoParams, PG_SERVO_PARAMS, 0); PG_REGISTER_ARRAY(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 0); - PG_REGISTER(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0); PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0); PG_REGISTER(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0); diff --git a/src/test/unit/flight_imu_unittest.cc b/src/test/unit/flight_imu_unittest.cc index 1945c70d9c..9468ec38ef 100644 --- a/src/test/unit/flight_imu_unittest.cc +++ b/src/test/unit/flight_imu_unittest.cc @@ -60,8 +60,6 @@ extern "C" { PG_REGISTER(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 0); PG_REGISTER(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0); - PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); - PG_RESET_TEMPLATE(featureConfig_t, featureConfig, .enabledFeatures = 0 ); diff --git a/src/test/unit/osd_unittest.cc b/src/test/unit/osd_unittest.cc index 040b2b44d7..4121f18906 100644 --- a/src/test/unit/osd_unittest.cc +++ b/src/test/unit/osd_unittest.cc @@ -32,6 +32,7 @@ extern "C" { #include "common/time.h" #include "drivers/max7456_symbols.h" + #include "drivers/serial.h" #include "fc/config.h" #include "fc/rc_controls.h" diff --git a/src/test/unit/rx_rx_unittest.cc b/src/test/unit/rx_rx_unittest.cc index 3505b6c791..54d09b3740 100644 --- a/src/test/unit/rx_rx_unittest.cc +++ b/src/test/unit/rx_rx_unittest.cc @@ -40,8 +40,6 @@ extern "C" { bool isPulseValid(uint16_t pulseDuration); void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration); - PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); - PG_RESET_TEMPLATE(featureConfig_t, featureConfig, .enabledFeatures = 0 );