Moved 'config.[ch]' into the 'config/' directory.
This commit is contained in:
parent
9b2fd4c465
commit
4a7904695e
|
@ -9,6 +9,7 @@ COMMON_SRC = \
|
||||||
$(addprefix config/,$(notdir $(wildcard $(SRC_DIR)/config/*.c))) \
|
$(addprefix config/,$(notdir $(wildcard $(SRC_DIR)/config/*.c))) \
|
||||||
cli/cli.c \
|
cli/cli.c \
|
||||||
cli/settings.c \
|
cli/settings.c \
|
||||||
|
config/config.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/dshot.c \
|
drivers/dshot.c \
|
||||||
drivers/dshot_dpwm.c \
|
drivers/dshot_dpwm.c \
|
||||||
|
@ -47,7 +48,6 @@ COMMON_SRC = \
|
||||||
drivers/transponder_ir_ilap.c \
|
drivers/transponder_ir_ilap.c \
|
||||||
drivers/transponder_ir_erlt.c \
|
drivers/transponder_ir_erlt.c \
|
||||||
fc/board_info.c \
|
fc/board_info.c \
|
||||||
fc/config.c \
|
|
||||||
fc/dispatch.c \
|
fc/dispatch.c \
|
||||||
fc/hardfaults.c \
|
fc/hardfaults.c \
|
||||||
fc/tasks.c \
|
fc/tasks.c \
|
||||||
|
|
|
@ -52,7 +52,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -94,7 +94,7 @@ bool cliMode = false;
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/board_info.h"
|
#include "fc/board_info.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_adjustments.h"
|
#include "fc/rc_adjustments.h"
|
||||||
|
|
|
@ -59,7 +59,7 @@
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
||||||
// For 'ARM' related
|
// For 'ARM' related
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -49,7 +49,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/asyncfatfs/asyncfatfs.h"
|
#include "io/asyncfatfs/asyncfatfs.h"
|
||||||
#include "io/flashfs.h"
|
#include "io/flashfs.h"
|
||||||
|
|
|
@ -53,7 +53,7 @@
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
|
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/gps_rescue.h"
|
#include "flight/gps_rescue.h"
|
||||||
|
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
|
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include "sensors/current.h"
|
#include "sensors/current.h"
|
||||||
#include "sensors/voltage.h"
|
#include "sensors/voltage.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
voltageMeterSource_e batteryConfig_voltageMeterSource;
|
voltageMeterSource_e batteryConfig_voltageMeterSource;
|
||||||
currentMeterSource_e batteryConfig_currentMeterSource;
|
currentMeterSource_e batteryConfig_currentMeterSource;
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuSaveExitEntries[] =
|
static const OSD_Entry cmsx_menuSaveExitEntries[] =
|
||||||
{
|
{
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/vtx_rtc6705.h"
|
#include "io/vtx_rtc6705.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/vtx_smartaudio.h"
|
#include "io/vtx_smartaudio.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/vtx_tramp.h"
|
#include "io/vtx_tramp.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <common/printf.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -32,6 +31,8 @@
|
||||||
|
|
||||||
#include "cli/cli.h"
|
#include "cli/cli.h"
|
||||||
|
|
||||||
|
#include "common/sensor_alignment.h"
|
||||||
|
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
@ -39,7 +40,6 @@
|
||||||
#include "drivers/motor.h"
|
#include "drivers/motor.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
|
@ -65,9 +65,9 @@
|
||||||
#include "pg/beeper.h"
|
#include "pg/beeper.h"
|
||||||
#include "pg/beeper_dev.h"
|
#include "pg/beeper_dev.h"
|
||||||
#include "pg/gyrodev.h"
|
#include "pg/gyrodev.h"
|
||||||
|
#include "pg/motor.h"
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
#include "pg/motor.h"
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/vtx_table.h"
|
#include "pg/vtx_table.h"
|
||||||
|
|
||||||
|
@ -80,7 +80,7 @@
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
|
|
||||||
#include "common/sensor_alignment.h"
|
#include "config.h"
|
||||||
|
|
||||||
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
|
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_streamer.h"
|
#include "config/config_streamer.h"
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#ifdef CONFIG_IN_SDCARD
|
#ifdef CONFIG_IN_SDCARD
|
||||||
#include "io/asyncfatfs/asyncfatfs.h"
|
#include "io/asyncfatfs/asyncfatfs.h"
|
||||||
|
|
|
@ -39,13 +39,11 @@
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "timer.h"
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
#include "serial.h"
|
|
||||||
#include "serial_softserial.h"
|
#include "serial_softserial.h"
|
||||||
|
|
||||||
#include "fc/config.h" //!!TODO remove this dependency
|
|
||||||
|
|
||||||
#define RX_TOTAL_BITS 10
|
#define RX_TOTAL_BITS 10
|
||||||
#define TX_TOTAL_BITS 10
|
#define TX_TOTAL_BITS 10
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -49,7 +49,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/transponder_ir.h"
|
#include "drivers/transponder_ir.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
|
|
|
@ -83,7 +83,7 @@
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/board_info.h"
|
#include "fc/board_info.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/dispatch.h"
|
#include "fc/dispatch.h"
|
||||||
#include "fc/init.h"
|
#include "fc/init.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
|
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
|
|
||||||
#include "drivers/camera_control.h"
|
#include "drivers/camera_control.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/dispatch.h"
|
#include "fc/dispatch.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
#include "fc/stats.h"
|
#include "fc/stats.h"
|
||||||
|
|
|
@ -46,7 +46,7 @@
|
||||||
#include "drivers/usb_io.h"
|
#include "drivers/usb_io.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
#include "fc/dispatch.h"
|
#include "fc/dispatch.h"
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
|
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
|
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -50,7 +50,7 @@
|
||||||
#include "pg/dashboard.h"
|
#include "pg/dashboard.h"
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include "drivers/display.h"
|
#include "drivers/display.h"
|
||||||
#include "drivers/max7456.h"
|
#include "drivers/max7456.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/displayport_max7456.h"
|
#include "io/displayport_max7456.h"
|
||||||
|
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
|
|
@ -48,7 +48,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
|
@ -48,7 +48,7 @@
|
||||||
#include "drivers/serial_usb_vcp.h"
|
#include "drivers/serial_usb_vcp.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/usb_io.h"
|
#include "drivers/usb_io.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/transponder_ir.h"
|
#include "io/transponder_ir.h"
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#endif
|
#endif
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/spektrum_vtx_control.h"
|
#include "io/spektrum_vtx_control.h"
|
||||||
|
|
|
@ -67,7 +67,7 @@
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "fc/board_info.h"
|
#include "fc/board_info.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
|
@ -72,7 +72,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_adjustments.h"
|
#include "fc/rc_adjustments.h"
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include "drivers/rx/rx_cc2500.h"
|
#include "drivers/rx/rx_cc2500.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#include "drivers/rx/rx_pwm.h"
|
#include "drivers/rx/rx_pwm.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/pwm.h"
|
#include "rx/pwm.h"
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include "drivers/rx/rx_spi.h"
|
#include "drivers/rx/rx_spi.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
#include "drivers/rx/rx_spi.h"
|
#include "drivers/rx/rx_spi.h"
|
||||||
#include "drivers/rx/rx_nrf24l01.h"
|
#include "drivers/rx/rx_nrf24l01.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/spektrum_rssi.h"
|
#include "io/spektrum_rssi.h"
|
||||||
#include "io/spektrum_vtx_control.h"
|
#include "io/spektrum_vtx_control.h"
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#define TASK_PERIOD_HZ(hz) (1000000 / (hz))
|
#define TASK_PERIOD_HZ(hz) (1000000 / (hz))
|
||||||
#define TASK_PERIOD_MS(ms) ((ms) * 1000)
|
#define TASK_PERIOD_MS(ms) ((ms) * 1000)
|
||||||
|
|
|
@ -67,7 +67,7 @@
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
|
|
||||||
#include "esc_sensor.h"
|
#include "esc_sensor.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
|
|
|
@ -63,7 +63,7 @@
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#ifdef USE_GYRO_DATA_ANALYSE
|
#ifdef USE_GYRO_DATA_ANALYSE
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
||||||
#include "drivers/rangefinder/rangefinder_lidartf.h"
|
#include "drivers/rangefinder/rangefinder_lidartf.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
#include "fc/tasks.h"
|
#include "fc/tasks.h"
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
|
|
@ -26,12 +26,12 @@
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/core.h"
|
#include "fc/core.h"
|
||||||
#include "fc/rc_adjustments.h"
|
#include "fc/rc_adjustments.h"
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "drivers/pwm_esc_detect.h"
|
#include "drivers/pwm_esc_detect.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
|
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
|
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#ifdef SYNERGYF4
|
#ifdef SYNERGYF4
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
|
|
@ -46,7 +46,7 @@ const timerHardware_t timerHardware[1]; // unused
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "scheduler/scheduler.h"
|
#include "scheduler/scheduler.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "config_helper.h"
|
#include "config_helper.h"
|
||||||
|
|
||||||
|
|
|
@ -49,7 +49,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#ifdef USE_TARGET_CONFIG
|
#ifdef USE_TARGET_CONFIG
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -45,7 +45,7 @@
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -45,7 +45,7 @@ static uint16_t calculateChecksum(const uint8_t *ibusPacket);
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "drivers/accgyro/accgyro.h"
|
#include "drivers/accgyro/accgyro.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
|
@ -49,7 +49,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro/accgyro.h"
|
#include "drivers/accgyro/accgyro.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
|
@ -44,7 +44,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue