mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Merge pull request #1340 from martinbudden/bf_config_move
Moved config.c from config directory to fc directory
This commit is contained in:
commit
8cf52c80c2
46 changed files with 94 additions and 103 deletions
14
Makefile
14
Makefile
|
@ -396,19 +396,15 @@ COMMON_SRC = \
|
||||||
build/version.c \
|
build/version.c \
|
||||||
$(TARGET_DIR_SRC) \
|
$(TARGET_DIR_SRC) \
|
||||||
main.c \
|
main.c \
|
||||||
fc/mw.c \
|
|
||||||
fc/fc_tasks.c \
|
|
||||||
common/encoding.c \
|
common/encoding.c \
|
||||||
common/filter.c \
|
common/filter.c \
|
||||||
common/maths.c \
|
common/maths.c \
|
||||||
common/printf.c \
|
common/printf.c \
|
||||||
common/streambuf.c \
|
common/streambuf.c \
|
||||||
common/typeconversion.c \
|
common/typeconversion.c \
|
||||||
config/config.c \
|
|
||||||
config/config_eeprom.c \
|
config/config_eeprom.c \
|
||||||
config/feature.c \
|
config/feature.c \
|
||||||
config/parameter_group.c \
|
config/parameter_group.c \
|
||||||
fc/runtime_config.c \
|
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/buf_writer.c \
|
drivers/buf_writer.c \
|
||||||
drivers/bus_i2c_soft.c \
|
drivers/bus_i2c_soft.c \
|
||||||
|
@ -429,6 +425,13 @@ COMMON_SRC = \
|
||||||
drivers/sound_beeper.c \
|
drivers/sound_beeper.c \
|
||||||
drivers/system.c \
|
drivers/system.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
|
fc/config.c \
|
||||||
|
fc/fc_tasks.c \
|
||||||
|
fc/fc_msp.c \
|
||||||
|
fc/mw.c \
|
||||||
|
fc/rc_controls.c \
|
||||||
|
fc/rc_curves.c \
|
||||||
|
fc/runtime_config.c \
|
||||||
flight/altitudehold.c \
|
flight/altitudehold.c \
|
||||||
flight/failsafe.c \
|
flight/failsafe.c \
|
||||||
flight/imu.c \
|
flight/imu.c \
|
||||||
|
@ -436,9 +439,6 @@ COMMON_SRC = \
|
||||||
flight/pid.c \
|
flight/pid.c \
|
||||||
flight/pid_legacy.c \
|
flight/pid_legacy.c \
|
||||||
flight/pid_betaflight.c \
|
flight/pid_betaflight.c \
|
||||||
fc/fc_msp.c \
|
|
||||||
fc/rc_controls.c \
|
|
||||||
fc/rc_curves.c \
|
|
||||||
io/beeper.c \
|
io/beeper.c \
|
||||||
io/serial.c \
|
io/serial.c \
|
||||||
io/serial_4way.c \
|
io/serial_4way.c \
|
||||||
|
|
|
@ -37,6 +37,7 @@
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -48,7 +49,6 @@
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
#include "sensors/sonar.h"
|
#include "sensors/sonar.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
#include "common/encoding.h"
|
#include "common/encoding.h"
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
@ -25,7 +26,6 @@
|
||||||
|
|
||||||
#include "msp/msp_serial.h"
|
#include "msp/msp_serial.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,6 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -17,8 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,6 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
|
|
@ -43,6 +43,11 @@
|
||||||
#include "drivers/max7456.h"
|
#include "drivers/max7456.h"
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/rc_curves.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
@ -56,8 +61,6 @@
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "io/servos.h"
|
#include "io/servos.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "fc/rc_curves.h"
|
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
|
@ -75,9 +78,6 @@
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
|
@ -49,8 +49,9 @@
|
||||||
#include "drivers/max7456.h"
|
#include "drivers/max7456.h"
|
||||||
#include "drivers/vtx_soft_spi_rtc6705.h"
|
#include "drivers/vtx_soft_spi_rtc6705.h"
|
||||||
|
|
||||||
#include "fc/fc_msp.h"
|
#include "fc/config.h"
|
||||||
#include "fc/mw.h"
|
#include "fc/mw.h"
|
||||||
|
#include "fc/fc_msp.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -95,7 +96,6 @@
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
|
@ -30,6 +30,7 @@
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/fc_tasks.h"
|
#include "fc/fc_tasks.h"
|
||||||
#include "fc/mw.h"
|
#include "fc/mw.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
@ -51,8 +52,6 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
|
@ -63,7 +62,8 @@
|
||||||
|
|
||||||
#include "scheduler/scheduler.h"
|
#include "scheduler/scheduler.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
|
@ -44,8 +44,10 @@
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_curves.h"
|
#include "fc/rc_curves.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "msp/msp_serial.h"
|
#include "msp/msp_serial.h"
|
||||||
|
|
||||||
|
@ -68,8 +70,6 @@
|
||||||
#include "flight/gtune.h"
|
#include "flight/gtune.h"
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
|
@ -28,9 +28,11 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/rc_curves.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
@ -48,8 +50,6 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "fc/rc_curves.h"
|
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
#include "io/display.h"
|
#include "io/display.h"
|
||||||
|
|
|
@ -20,11 +20,11 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_curves.h"
|
#include "fc/rc_curves.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
|
|
@ -24,17 +24,19 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/motors.h"
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
|
#include "io/beeper.h"
|
||||||
|
#include "io/motors.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Usage:
|
* Usage:
|
||||||
*
|
*
|
||||||
|
|
|
@ -38,11 +38,10 @@
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "blackbox/blackbox.h"
|
#include "blackbox/blackbox.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -41,7 +41,6 @@
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "io/servos.h"
|
#include "io/servos.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
@ -52,9 +51,10 @@
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
uint8_t motorCount;
|
uint8_t motorCount;
|
||||||
|
|
|
@ -37,6 +37,10 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
@ -44,7 +48,6 @@
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
@ -54,10 +57,6 @@
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
|
|
||||||
extern int16_t magHold;
|
extern int16_t magHold;
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
|
|
@ -38,9 +38,9 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
|
|
@ -46,7 +46,9 @@
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
@ -57,10 +59,7 @@
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
|
|
||||||
#include "io/display.h"
|
#include "io/display.h"
|
||||||
|
|
|
@ -49,10 +49,10 @@
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "fc/config.h"
|
||||||
#include "config/feature.h"
|
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
#define LOG_ERROR '?'
|
#define LOG_ERROR '?'
|
||||||
#define LOG_IGNORED '!'
|
#define LOG_IGNORED '!'
|
||||||
|
|
|
@ -44,7 +44,9 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
@ -63,19 +65,16 @@
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
|
@ -38,12 +38,12 @@
|
||||||
#include "io/flashfs.h"
|
#include "io/flashfs.h"
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
|
@ -56,6 +56,7 @@ uint8_t cliMode = 0;
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
#include "drivers/buf_writer.h"
|
#include "drivers/buf_writer.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -94,7 +95,6 @@ uint8_t cliMode = 0;
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/frsky.h"
|
#include "telemetry/frsky.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
|
@ -27,11 +27,11 @@
|
||||||
|
|
||||||
#include "drivers/transponder_ir.h"
|
#include "drivers/transponder_ir.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/usb_io.h"
|
#include "drivers/usb_io.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "io/transponder_ir.h"
|
#include "io/transponder_ir.h"
|
||||||
#include "config/config.h"
|
|
||||||
|
|
||||||
static bool transponderInitialised = false;
|
static bool transponderInitialised = false;
|
||||||
static bool transponderRepeat = false;
|
static bool transponderRepeat = false;
|
||||||
|
|
|
@ -63,8 +63,9 @@
|
||||||
#include "bus_bst.h"
|
#include "bus_bst.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "fc/fc_msp.h"
|
#include "fc/config.h"
|
||||||
#include "fc/fc_tasks.h"
|
#include "fc/fc_tasks.h"
|
||||||
|
#include "fc/fc_msp.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -108,7 +109,6 @@
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
|
@ -30,7 +30,8 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -28,7 +28,6 @@
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
@ -39,6 +38,7 @@
|
||||||
#include "drivers/rx_spi.h"
|
#include "drivers/rx_spi.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
|
@ -26,9 +26,10 @@
|
||||||
|
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
#include "rx/nrf24_cx10.h"
|
#include "rx/nrf24_cx10.h"
|
||||||
|
|
|
@ -28,14 +28,13 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
|
@ -30,13 +30,16 @@
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "sensors/acceleration.h"
|
|
||||||
|
|
||||||
int32_t accSmooth[XYZ_AXIS_COUNT];
|
int32_t accSmooth[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
|
|
@ -28,9 +28,9 @@
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
|
@ -27,12 +27,11 @@
|
||||||
#include "drivers/compass_hmc5883l.h"
|
#include "drivers/compass_hmc5883l.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "sensors/boardalignment.h"
|
#include "fc/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||||
|
|
|
@ -30,9 +30,10 @@
|
||||||
|
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
|
@ -28,7 +28,6 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,6 @@
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,6 @@
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -32,7 +32,6 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,6 @@
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -33,7 +33,6 @@
|
||||||
|
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "io/servos.h"
|
#include "io/servos.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
@ -59,10 +58,11 @@
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
#include "fc/mw.h"
|
#include "fc/mw.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
|
@ -20,7 +20,6 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -28,7 +28,6 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -31,6 +31,8 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
|
@ -38,6 +40,9 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
@ -46,20 +51,14 @@
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/frsky.h"
|
#include "telemetry/frsky.h"
|
||||||
|
|
|
@ -49,6 +49,10 @@
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
|
@ -57,7 +61,6 @@
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
|
@ -77,9 +80,6 @@
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/ltm.h"
|
#include "telemetry/ltm.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
|
|
||||||
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
||||||
#define LTM_CYCLETIME 100
|
#define LTM_CYCLETIME 100
|
||||||
|
|
|
@ -27,12 +27,12 @@
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "fc/config.h"
|
||||||
#include "rx/msp.h"
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
@ -55,12 +55,12 @@
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
#include "flight/altitudehold.h"
|
#include "flight/altitudehold.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
#include "rx/msp.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/smartport.h"
|
#include "telemetry/smartport.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
|
|
@ -26,14 +26,14 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/frsky.h"
|
#include "telemetry/frsky.h"
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue