diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index b0a1f2b8b1..5cba080b26 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -16,77 +16,43 @@ */ #include +#include #include #include "platform.h" #ifdef BLACKBOX -#include "build/version.h" #include "build/debug.h" +#include "build/version.h" -#include "common/maths.h" #include "common/axis.h" -#include "common/color.h" #include "common/encoding.h" #include "common/utils.h" -#include "drivers/gpio.h" -#include "drivers/sensor.h" -#include "drivers/system.h" -#include "drivers/serial.h" -#include "drivers/compass.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/accgyro.h" -#include "drivers/light_led.h" +#include "blackbox.h" +#include "blackbox_io.h" -#include "sensors/sensors.h" -#include "sensors/boardalignment.h" -#include "sensors/sonar.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/gyro.h" -#include "sensors/battery.h" +#include "drivers/sensor.h" +#include "drivers/compass.h" +#include "drivers/system.h" + +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" + +#include "flight/pid.h" #include "io/beeper.h" -#include "io/display.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "io/gimbal.h" -#include "io/gps.h" -#include "io/ledstrip.h" -#include "io/serial.h" -#include "io/serial_cli.h" -#include "io/serial_msp.h" -#include "io/statusindicator.h" -#include "io/osd.h" -#include "io/vtx.h" -#include "rx/rx.h" -#include "rx/msp.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/altitudehold.h" -#include "flight/failsafe.h" -#include "flight/imu.h" -#include "flight/pid.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" +#include "sensors/sensors.h" +#include "sensors/compass.h" +#include "sensors/sonar.h" #include "config/config.h" #include "config/config_profile.h" #include "config/config_master.h" #include "config/feature.h" -#include "blackbox.h" -#include "blackbox_io.h" - #define BLACKBOX_I_INTERVAL 32 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200 #define SLOW_FRAME_INTERVAL 4096 diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index be6bc3e61a..490c271b2f 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -17,8 +17,6 @@ #pragma once -#include - typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1, diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 7532d58b09..5f4088bbc8 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -1,73 +1,33 @@ +#include +#include #include #include #include +#include "platform.h" + +#ifdef BLACKBOX + #include "blackbox_io.h" #include "build/version.h" #include "build/build_config.h" -#include "common/maths.h" -#include "common/axis.h" -#include "common/color.h" #include "common/encoding.h" - -#include "drivers/gpio.h" -#include "drivers/sensor.h" -#include "drivers/system.h" -#include "drivers/serial.h" -#include "drivers/compass.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/accgyro.h" -#include "drivers/light_led.h" -#include "drivers/sound_beeper.h" - -#include "sensors/sensors.h" -#include "sensors/boardalignment.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/gyro.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/display.h" -#include "io/motors.h" -#include "io/servos.h" -#include "rx/rx.h" -#include "fc/rc_controls.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "io/gimbal.h" -#include "io/gps.h" -#include "io/ledstrip.h" -#include "io/serial.h" -#include "io/serial_cli.h" -#include "io/serial_msp.h" -#include "io/statusindicator.h" -#include "rx/msp.h" -#include "telemetry/telemetry.h" #include "common/printf.h" -#include "flight/mixer.h" -#include "flight/altitudehold.h" -#include "flight/failsafe.h" -#include "flight/imu.h" -#include "flight/pid.h" -#include "flight/navigation.h" +#include "fc/rc_controls.h" -#include "fc/runtime_config.h" +#include "flight/pid.h" + +#include "io/asyncfatfs/asyncfatfs.h" +#include "io/flashfs.h" +#include "io/serial_msp.h" #include "config/config.h" #include "config/config_profile.h" #include "config/config_master.h" -#include "io/flashfs.h" -#include "io/asyncfatfs/asyncfatfs.h" - -#ifdef BLACKBOX - #define BLACKBOX_SERIAL_PORT_MODE MODE_TX // How many bytes can we transmit per loop iteration when writing headers? diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 37abd2695a..5cb6548087 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -17,11 +17,6 @@ #pragma once -#include -#include - -#include "platform.h" - typedef enum BlackboxDevice { BLACKBOX_DEVICE_SERIAL = 0, diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 3b24dd734d..b47a19ae7d 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -51,7 +51,7 @@ typedef struct fp_vector { float Z; } t_fp_vector_def; -typedef union { +typedef union u_fp_vector { float A[3]; t_fp_vector_def V; } t_fp_vector; diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index ea163077cc..8763e06b9b 100644 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -21,53 +21,14 @@ #include "platform.h" -#include "build/build_config.h" - -#include "common/color.h" -#include "common/axis.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" #include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" +#include "config/config_master.h" -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" +#include "build/build_config.h" #include "config/config.h" #include "config/config_eeprom.h" -#include "config/config_profile.h" #include "config/config_master.h" #if !defined(FLASH_SIZE) diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 4883df44e5..0af674b4c7 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -17,6 +17,51 @@ #pragma once +#include +#include +#include + +#include "common/color.h" +#include "common/axis.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/motors.h" +#include "io/servos.h" +#include "fc/rc_controls.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" + + // System-wide typedef struct master_s { uint8_t version; diff --git a/src/main/config/feature.c b/src/main/config/feature.c index 4e4acf488f..9d4e2c2b70 100644 --- a/src/main/config/feature.c +++ b/src/main/config/feature.c @@ -21,55 +21,11 @@ #include "platform.h" -#include "build/build_config.h" - -#include "common/color.h" -#include "common/axis.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - #include "config/config.h" -#include "config/config_profile.h" #include "config/config_master.h" #include "config/feature.h" + static uint32_t activeFeaturesLatch = 0; void intFeatureSet(uint32_t mask, master_t *config) diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 44d7b95464..d0df78c4b1 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -22,6 +22,7 @@ #ifdef USE_FLASH_M25P16 +#include "flash.h" #include "flash_m25p16.h" #include "io.h" #include "bus_spi.h" diff --git a/src/main/drivers/flash_m25p16.h b/src/main/drivers/flash_m25p16.h index 6cad8a8ea6..ace78fc8bc 100644 --- a/src/main/drivers/flash_m25p16.h +++ b/src/main/drivers/flash_m25p16.h @@ -18,7 +18,6 @@ #pragma once #include -#include "flash.h" #include "io_types.h" #define M25P16_PAGESIZE 256 @@ -39,4 +38,5 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length); bool m25p16_isReady(); bool m25p16_waitForReady(uint32_t timeoutMillis); -const flashGeometry_t* m25p16_getGeometry(); +struct flashGeometry_s; +const struct flashGeometry_s* m25p16_getGeometry(); diff --git a/src/main/drivers/pwm_rx.h b/src/main/drivers/pwm_rx.h index 1eb792b7fe..5158a24653 100644 --- a/src/main/drivers/pwm_rx.h +++ b/src/main/drivers/pwm_rx.h @@ -24,11 +24,11 @@ typedef enum { #define PPM_RCVR_TIMEOUT 0 +struct timerHardware_s; +void ppmInConfig(const struct timerHardware_s *timerHardwarePtr); +void ppmAvoidPWMTimerClash(const struct timerHardware_s *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol); -void ppmInConfig(const timerHardware_t *timerHardwarePtr); -void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol); - -void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel); +void pwmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t channel); uint16_t pwmRead(uint8_t channel); uint16_t ppmRead(uint8_t channel); diff --git a/src/main/fc/mw.h b/src/main/fc/mw.h index d1d49bdf72..e111be78b8 100644 --- a/src/main/fc/mw.h +++ b/src/main/fc/mw.h @@ -19,7 +19,8 @@ extern int16_t magHold; -void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta); +union rollAndPitchTrims_u; +void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta); void handleInflightCalibrationStickPosition(); void mwDisarm(void); diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 1cad69a38a..43a629ce30 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -79,14 +79,16 @@ void imuConfigure( float getCosTiltAngle(void); void calculateEstimatedAltitude(uint32_t currentTime); -void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims); +union rollAndPitchTrims_u; +void imuUpdateAccelerometer(union rollAndPitchTrims_u *accelerometerTrims); void imuUpdateAttitude(uint32_t currentTime); float calculateThrottleAngleScale(uint16_t throttle_correction_angle); int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value); float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz); -int16_t imuCalculateHeading(t_fp_vector *vec); +union u_fp_vector; +int16_t imuCalculateHeading(union u_fp_vector *vec); void imuResetAccelerationSum(void); -void imuUpdateAcc(rollAndPitchTrims_t *accelerometerTrims); +void imuUpdateAcc(union rollAndPitchTrims_u *accelerometerTrims); void imuInit(void); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8bef32e789..c63921a038 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -114,7 +114,7 @@ void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, const struct rxConfig_s *rxConfig); -extern int16_t axisPID[XYZ_AXIS_COUNT]; +extern int16_t axisPID[3]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; bool airmodeWasActivated; extern uint32_t targetPidLooptime; diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 08372494f4..7adfe0f7f6 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -402,7 +402,7 @@ bool isBeeperOn(void) { void beeper(beeperMode_e mode) {UNUSED(mode);} void beeperSilence(void) {} void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);} -void beeperUpdate(uint32_t currentTime) {} +void beeperUpdate(uint32_t currentTime) {UNUSED(currentTime);} uint32_t getArmingBeepTimeMicros(void) {return 0;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index d1cc136f97..de897b7c63 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -33,8 +33,10 @@ #include #include +#include "drivers/flash.h" #include "drivers/flash_m25p16.h" -#include "flashfs.h" + +#include "io/flashfs.h" static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h index 3460c7d830..90f1ca9e57 100644 --- a/src/main/io/flashfs.h +++ b/src/main/io/flashfs.h @@ -17,10 +17,6 @@ #pragma once -#include - -#include "drivers/flash.h" - #define FLASHFS_WRITE_BUFFER_SIZE 128 #define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1) @@ -35,7 +31,8 @@ uint32_t flashfsGetOffset(); uint32_t flashfsGetWriteBufferFreeSpace(); uint32_t flashfsGetWriteBufferSize(); int flashfsIdentifyStartOfFreeSpace(); -const flashGeometry_t* flashfsGetGeometry(); +struct flashGeometry_s; +const struct flashGeometry_s* flashfsGetGeometry(); void flashfsSeekAbs(uint32_t offset); void flashfsSeekRel(int32_t offset); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 96eb0a0c09..0c212a59ac 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -22,91 +22,28 @@ #include #include -#include #include -#include #include #include "platform.h" #ifdef OSD -#include "build/atomic.h" -#include "build/build_config.h" -#include "build/debug.h" #include "build/version.h" -#include "scheduler/scheduler.h" +#include "common/utils.h" -#include "common/axis.h" -#include "common/color.h" -#include "common/maths.h" -#include "common/typeconversion.h" - -#include "drivers/nvic.h" - -#include "drivers/sensor.h" #include "drivers/system.h" -#include "drivers/gpio.h" -#include "drivers/light_led.h" -#include "drivers/sound_beeper.h" -#include "drivers/timer.h" -#include "drivers/serial.h" -#include "drivers/serial_softserial.h" -#include "drivers/serial_uart.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/pwm_mapping.h" -#include "drivers/pwm_rx.h" -#include "drivers/adc.h" -#include "drivers/bus_i2c.h" -#include "drivers/bus_spi.h" -#include "drivers/inverter.h" -#include "drivers/flash_m25p16.h" -#include "drivers/sonar_hcsr04.h" -#include "drivers/usb_io.h" -#include "drivers/transponder_ir.h" -#include "drivers/sdcard.h" -#include "rx/rx.h" - -#include "io/beeper.h" -#include "io/serial.h" #include "io/flashfs.h" -#include "io/gps.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "io/gimbal.h" -#include "io/ledstrip.h" -#include "io/display.h" -#include "io/asyncfatfs/asyncfatfs.h" -#include "io/transponder_ir.h" #include "io/osd.h" -#include "sensors/sensors.h" -#include "sensors/sonar.h" -#include "sensors/barometer.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/gyro.h" -#include "sensors/battery.h" -#include "sensors/boardalignment.h" -#include "sensors/initialisation.h" - -#include "telemetry/telemetry.h" -#include "blackbox/blackbox.h" - -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/mixer.h" -#include "flight/failsafe.h" -#include "flight/navigation.h" - +#include "fc/rc_controls.h" #include "fc/runtime_config.h" +#include "flight/pid.h" + #include "config/config.h" -#include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/config_master.h" #include "config/feature.h" diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 62a0b1233c..166a02827a 100755 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -25,38 +25,46 @@ #include "platform.h" -#include "build/version.h" -#include "build/debug.h" +// FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled +// signal that we're in cli mode +uint8_t cliMode = 0; + +#ifdef USE_CLI + #include "build/build_config.h" +#include "build/debug.h" +#include "build/version.h" #include "common/axis.h" -#include "common/maths.h" #include "common/color.h" +#include "common/maths.h" +#include "common/printf.h" #include "common/typeconversion.h" #include "drivers/system.h" - #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/compass.h" - #include "drivers/serial.h" #include "drivers/bus_i2c.h" +#include "drivers/flash.h" #include "drivers/gpio.h" #include "drivers/io.h" #include "drivers/io_impl.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/sdcard.h" - #include "drivers/buf_writer.h" +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" + #include "io/motors.h" #include "io/servos.h" #include "io/gps.h" #include "io/gimbal.h" -#include "fc/rc_controls.h" #include "io/serial.h" +#include "io/serial_cli.h" #include "io/ledstrip.h" #include "io/flashfs.h" #include "io/beeper.h" @@ -67,6 +75,8 @@ #include "rx/rx.h" #include "rx/spektrum.h" +#include "scheduler/scheduler.h" + #include "sensors/battery.h" #include "sensors/boardalignment.h" #include "sensors/sensors.h" @@ -84,25 +94,12 @@ #include "telemetry/telemetry.h" #include "telemetry/frsky.h" -#include "fc/runtime_config.h" - #include "config/config.h" #include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/config_master.h" #include "config/feature.h" -#include "common/printf.h" - -#include "io/serial_cli.h" -#include "scheduler/scheduler.h" - -// FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled -// signal that we're in cli mode -uint8_t cliMode = 0; - -#ifdef USE_CLI - extern uint16_t cycleTime; // FIXME dependency on mw.c void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort); @@ -1503,12 +1500,13 @@ static void cliAdjustmentRange(char *cmdline) } } +#ifndef USE_QUAD_MIXER_ONLY static void printMotorMix(uint8_t dumpMask, master_t *defaultConfig) { - char buf0[8]; - char buf1[8]; - char buf2[8]; - char buf3[8]; + char buf0[8]; + char buf1[8]; + char buf2[8]; + char buf3[8]; for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { if (masterConfig.customMotorMixer[i].throttle == 0.0f) break; @@ -1537,6 +1535,7 @@ static void printMotorMix(uint8_t dumpMask, master_t *defaultConfig) ftoa(yaw, buf3)); } } +#endif // USE_QUAD_MIXER_ONLY static void cliMotorMix(char *cmdline) { @@ -1548,7 +1547,7 @@ static void cliMotorMix(char *cmdline) char *ptr; if (isEmpty(cmdline)) { - printMotorMix(DUMP_MASTER, NULL); + printMotorMix(DUMP_MASTER, NULL); } else if (strncasecmp(cmdline, "reset", 5) == 0) { // erase custom mixer for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) @@ -1597,7 +1596,7 @@ static void cliMotorMix(char *cmdline) if (check != 4) { cliShowParseError(); } else { - printMotorMix(DUMP_MASTER, NULL); + printMotorMix(DUMP_MASTER, NULL); } } else { cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1); @@ -2720,7 +2719,7 @@ static void printConfig(char *cmdline, bool doDiff) #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# mixer\r\n"); #endif - bool equalsDefault = masterConfig.mixerMode == defaultConfig.mixerMode; + const bool equalsDefault = masterConfig.mixerMode == defaultConfig.mixerMode; const char *formatMixer = "mixer %s\r\n"; cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[defaultConfig.mixerMode - 1]); cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[masterConfig.mixerMode - 1]); @@ -2733,33 +2732,33 @@ static void printConfig(char *cmdline, bool doDiff) #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# servo\r\n"); #endif - printServo(dumpMask, &defaultConfig); + printServo(dumpMask, &defaultConfig); #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# servo mix\r\n"); #endif // print custom servo mixer if exists cliDumpPrintf(dumpMask, masterConfig.customServoMixer[0].rate == 0, "smix reset\r\n\r\n"); - printServoMix(dumpMask, &defaultConfig); + printServoMix(dumpMask, &defaultConfig); #endif #endif #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# feature\r\n"); #endif - printFeature(dumpMask, &defaultConfig); + printFeature(dumpMask, &defaultConfig); #ifdef BEEPER #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# beeper\r\n"); #endif - printBeeper(dumpMask, &defaultConfig); + printBeeper(dumpMask, &defaultConfig); #endif #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# map\r\n"); #endif - printMap(dumpMask, &defaultConfig); + printMap(dumpMask, &defaultConfig); #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# serial\r\n"); diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 00aff0b5f0..5ea8e0e9a7 100755 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -27,19 +27,20 @@ #include "build/debug.h" #include "build/version.h" +#include "blackbox/blackbox.h" + #include "common/axis.h" #include "common/color.h" #include "common/maths.h" #include "drivers/system.h" - #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/compass.h" - #include "drivers/serial.h" #include "drivers/bus_i2c.h" #include "drivers/io.h" +#include "drivers/flash.h" #include "drivers/gpio.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" @@ -47,13 +48,14 @@ #include "drivers/buf_writer.h" #include "drivers/max7456.h" #include "drivers/vtx_soft_spi_rtc6705.h" -#include "rx/rx.h" -#include "rx/msp.h" + +#include "fc/mw.h" +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" #include "io/beeper.h" #include "io/motors.h" #include "io/servos.h" -#include "fc/rc_controls.h" #include "io/gps.h" #include "io/gimbal.h" #include "io/serial.h" @@ -62,10 +64,13 @@ #include "io/transponder_ir.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/osd.h" +#include "io/serial_4way.h" +#include "io/serial_msp.h" #include "io/vtx.h" #include "io/msp_protocol.h" -#include "telemetry/telemetry.h" +#include "rx/rx.h" +#include "rx/msp.h" #include "scheduler/scheduler.h" @@ -78,6 +83,8 @@ #include "sensors/compass.h" #include "sensors/gyro.h" +#include "telemetry/telemetry.h" + #include "flight/mixer.h" #include "flight/pid.h" #include "flight/imu.h" @@ -85,12 +92,6 @@ #include "flight/navigation.h" #include "flight/altitudehold.h" -#include "blackbox/blackbox.h" - -#include "fc/mw.h" - -#include "fc/runtime_config.h" - #include "config/config.h" #include "config/config_eeprom.h" #include "config/config_profile.h" @@ -101,10 +102,6 @@ #include "hardware_revision.h" #endif -#include "serial_msp.h" - -#include "io/serial_4way.h" - static serialPort_t *mspSerialPort; extern uint16_t cycleTime; // FIXME dependency on mw.c diff --git a/src/main/io/serial_msp.h b/src/main/io/serial_msp.h index a1c7cdbdf9..8046aa8565 100644 --- a/src/main/io/serial_msp.h +++ b/src/main/io/serial_msp.h @@ -32,8 +32,9 @@ typedef enum { #define MSP_PORT_INBUF_SIZE 64 +struct serialPort_s; typedef struct mspPort_s { - serialPort_t *port; // null when port unused. + struct serialPort_s *port; // null when port unused. uint8_t offset; uint8_t dataSize; uint8_t checksum; diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 745da3ec6e..c4c859a170 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -17,62 +17,25 @@ #include #include -#include #include "platform.h" #ifdef VTX -#include "common/color.h" -#include "common/axis.h" -#include "common/maths.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/gpio.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" #include "drivers/vtx_rtc6705.h" +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" +#include "flight/pid.h" #include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" #include "io/vtx.h" -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - #include "config/config.h" +#include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/config_master.h" -#include "config/config_eeprom.h" -#include "fc/runtime_config.h" static uint8_t locked = 0; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 0def4b52c1..cb8253faac 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -43,6 +43,7 @@ #include "drivers/accgyro_lsm303dlhc.h" #include "drivers/bus_spi.h" +#include "drivers/accgyro_spi_icm20689.h" #include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6500.h" #include "drivers/accgyro_spi_mpu9250.h" diff --git a/src/main/target/ALIENFLIGHTF1/config.c b/src/main/target/ALIENFLIGHTF1/config.c index df417c0766..e78cb2149b 100644 --- a/src/main/target/ALIENFLIGHTF1/config.c +++ b/src/main/target/ALIENFLIGHTF1/config.c @@ -15,62 +15,24 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" #include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" #include "rx/rx.h" -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" - #include "config/config.h" - #include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for AlienFlight targets void targetConfiguration(master_t *config) { diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index 6268d31fc1..676e471154 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -15,70 +15,35 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" #include "common/axis.h" -#include "common/filter.h" #include "drivers/sensor.h" -#include "drivers/accgyro.h" #include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" #include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" #include "rx/rx.h" -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" +#include "sensors/sensors.h" +#include "sensors/compass.h" #include "config/config.h" - #include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for AlienFlight targets -void targetConfiguration(master_t *config) { +void targetConfiguration(master_t *config) +{ config->mag_hardware = MAG_NONE; // disabled by default config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind_autoreset = 1; diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h index 48d56a86a3..745a9f9f52 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.h +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h @@ -16,8 +16,6 @@ */ #pragma once -#include "drivers/exti.h" - typedef enum awf3HardwareRevision_t { UNKNOWN = 0, AFF3_REV_1, // MPU6050 / MPU9150 (I2C) @@ -29,4 +27,5 @@ extern uint8_t hardwareRevision; void updateHardwareRevision(void); void detectHardwareRevision(void); -const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); +struct extiConfig_s; +const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void); diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index 914dbc8826..6a9cfaba60 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -15,70 +15,35 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" #include "common/axis.h" -#include "common/filter.h" #include "drivers/sensor.h" -#include "drivers/accgyro.h" #include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" #include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" #include "rx/rx.h" -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" +#include "sensors/sensors.h" +#include "sensors/compass.h" #include "config/config.h" - #include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for AlienFlight targets -void targetConfiguration(master_t *config) { +void targetConfiguration(master_t *config) +{ config->mag_hardware = MAG_NONE; // disabled by default config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind_autoreset = 1; diff --git a/src/main/target/BLUEJAYF4/config.c b/src/main/target/BLUEJAYF4/config.c index eaf989d546..3d285c6787 100644 --- a/src/main/target/BLUEJAYF4/config.c +++ b/src/main/target/BLUEJAYF4/config.c @@ -19,66 +19,11 @@ #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" - -#include "config/config.h" - -#include "config/config_profile.h" #include "config/config_master.h" #include "hardware_revision.h" + // alternative defaults settings for BlueJayF4 targets void targetConfiguration(master_t *config) { diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h index 89e3478c13..ed6413d8cf 100755 --- a/src/main/target/CJMCU/hardware_revision.h +++ b/src/main/target/CJMCU/hardware_revision.h @@ -16,9 +16,7 @@ */ #pragma once - #include "drivers/exti.h" - -typedef enum cjmcuHardwareRevision_t { + typedef enum cjmcuHardwareRevision_t { UNKNOWN = 0, REV_1, // Blue LED3 REV_2 // Green LED3 @@ -31,4 +29,5 @@ void detectHardwareRevision(void); void spiBusInit(void); -const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); \ No newline at end of file +struct extiConfig_s; +const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void); diff --git a/src/main/target/COLIBRI/config.c b/src/main/target/COLIBRI/config.c index fd80365488..3e5a5d99f4 100644 --- a/src/main/target/COLIBRI/config.c +++ b/src/main/target/COLIBRI/config.c @@ -17,68 +17,26 @@ #include #include -#include #include "platform.h" -#include "build/build_config.h" -#include "build/debug.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/maths.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/gpio.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" #include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" #include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" #include "flight/mixer.h" #include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" -#include "fc/runtime_config.h" +#include "io/motors.h" +#include "io/serial.h" + +#include "rx/rx.h" + #include "config/config.h" - #include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for Colibri/Gemini targets void targetConfiguration(master_t *config) { diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c index ab50da768e..7a008e4fef 100644 --- a/src/main/target/COLIBRI_RACE/config.c +++ b/src/main/target/COLIBRI_RACE/config.c @@ -15,70 +15,22 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" +#include "io/motors.h" -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" #include "sensors/battery.h" -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" - #include "config/config.h" - -#include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for COLIBRI RACE targets -void targetConfiguration(master_t *config) { +void targetConfiguration(master_t *config) +{ config->motorConfig.minthrottle = 1025; config->motorConfig.maxthrottle = 1980; config->batteryConfig.vbatmaxcellvoltage = 45; diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index afdff94005..1428777124 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -63,8 +63,10 @@ #include "fc/runtime_config.h" #include "config/config.h" +#include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/config_master.h" +#include "config/feature.h" #ifdef NAZE #include "hardware_revision.h" diff --git a/src/main/target/MOTOLAB/config.c b/src/main/target/MOTOLAB/config.c index e0314ad935..0754d268c7 100755 --- a/src/main/target/MOTOLAB/config.c +++ b/src/main/target/MOTOLAB/config.c @@ -15,70 +15,18 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "fc/runtime_config.h" - #include "config/config.h" - -#include "config/config_profile.h" #include "config/config_master.h" + // Motolab target supports 2 different type of boards Tornado / Cyclone. -void targetConfiguration(master_t *config) { +void targetConfiguration(master_t *config) +{ config->gyro_sync_denom = 4; config->pid_process_denom = 1; } diff --git a/src/main/target/NAZE/hardware_revision.h b/src/main/target/NAZE/hardware_revision.h index 08895620f0..a8f3f985d0 100755 --- a/src/main/target/NAZE/hardware_revision.h +++ b/src/main/target/NAZE/hardware_revision.h @@ -16,8 +16,6 @@ */ #pragma once -#include "drivers/exti.h" - typedef enum nazeHardwareRevision_t { UNKNOWN = 0, NAZE32, // Naze32 and compatible with 8MHz HSE @@ -32,4 +30,5 @@ void detectHardwareRevision(void); void spiBusInit(void); -const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); +struct extiConfig_s; +const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void); diff --git a/src/main/target/RACEBASE/config.c b/src/main/target/RACEBASE/config.c index b1fb9c6107..7b1a8fa9f7 100755 --- a/src/main/target/RACEBASE/config.c +++ b/src/main/target/RACEBASE/config.c @@ -15,70 +15,20 @@ * along with Cleanflight. If not, see . */ +#include #include #include -#include "build/build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "fc/rc_controls.h" -#include "fc/rc_curves.h" -#include "fc/runtime_config.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/motors.h" -#include "io/servos.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - #include "rx/rx.h" -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - #include "config/config.h" - -#include "config/config_profile.h" #include "config/config_master.h" + // alternative defaults settings for COLIBRI RACE targets -void targetConfiguration(master_t *config) { +void targetConfiguration(master_t *config) +{ config->rxConfig.sbus_inversion = 0; config->rxConfig.rssi_scale = 19; config->rxConfig.serialrx_provider = SERIALRX_SBUS; diff --git a/src/main/target/RACEBASE/hardware_revision.h b/src/main/target/RACEBASE/hardware_revision.h index a331babad8..d7f94540b4 100755 --- a/src/main/target/RACEBASE/hardware_revision.h +++ b/src/main/target/RACEBASE/hardware_revision.h @@ -16,8 +16,6 @@ */ #pragma once -#include "drivers/exti.h" - extern uint8_t hardwareRevision; void updateHardwareRevision(void);