Merge branch 'development' of https://github.com/betaflight/betaflight into rc_rate_yaw_adjustment
This commit is contained in:
commit
3fe79bf050
20
Makefile
20
Makefile
|
@ -122,9 +122,9 @@ endif
|
|||
|
||||
REVISION = $(shell git log -1 --format="%h")
|
||||
|
||||
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/version.h | awk '{print $$3}' )
|
||||
FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/version.h | awk '{print $$3}' )
|
||||
FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/version.h | awk '{print $$3}' )
|
||||
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
|
||||
FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
|
||||
FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
|
||||
|
||||
FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
|
||||
|
||||
|
@ -357,19 +357,19 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
VPATH := $(VPATH):$(TARGET_DIR)
|
||||
|
||||
COMMON_SRC = \
|
||||
build_config.c \
|
||||
debug.c \
|
||||
version.c \
|
||||
build/build_config.c \
|
||||
build/debug.c \
|
||||
build/version.c \
|
||||
$(TARGET_DIR_SRC) \
|
||||
main.c \
|
||||
mw.c \
|
||||
fc/mw.c \
|
||||
common/encoding.c \
|
||||
common/filter.c \
|
||||
common/maths.c \
|
||||
common/printf.c \
|
||||
common/typeconversion.c \
|
||||
config/config.c \
|
||||
config/runtime_config.c \
|
||||
fc/runtime_config.c \
|
||||
drivers/adc.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
|
@ -395,8 +395,8 @@ COMMON_SRC = \
|
|||
flight/pid_legacy.c \
|
||||
flight/pid_betaflight.c \
|
||||
io/beeper.c \
|
||||
io/rc_controls.c \
|
||||
io/rc_curves.c \
|
||||
fc/rc_controls.c \
|
||||
fc/rc_curves.c \
|
||||
io/serial.c \
|
||||
io/serial_4way.c \
|
||||
io/serial_4way_avrootloader.c \
|
||||
|
|
|
@ -19,11 +19,12 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.h"
|
||||
#include "debug.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
|
@ -52,7 +53,7 @@
|
|||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -75,7 +76,8 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -4,8 +4,8 @@
|
|||
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "version.h"
|
||||
#include "build_config.h"
|
||||
#include "build/version.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -34,7 +34,7 @@
|
|||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
|
@ -56,7 +56,8 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -36,12 +36,11 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "printf.h"
|
||||
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
#include "maths.h"
|
||||
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
|
|
|
@ -20,10 +20,9 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -56,8 +55,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -74,7 +73,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -19,8 +19,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#ifdef USE_ACC_LSM303DLHC
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
|
|
@ -21,8 +21,9 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
|
|
@ -20,8 +20,9 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
|
|
@ -27,7 +27,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "light_led.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -38,7 +39,7 @@
|
|||
#include "exti.h"
|
||||
#include "bus_spi.h"
|
||||
#include "gyro_sync.h"
|
||||
#include "debug.h"
|
||||
#include "light_led.h"
|
||||
|
||||
#include "sensor.h"
|
||||
#include "accgyro.h"
|
||||
|
|
|
@ -19,8 +19,9 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "system.h"
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#ifdef USE_ADC
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "sensor.h"
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
|
|
|
@ -20,14 +20,14 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "system.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
// MS5611, Standard address 0x77
|
||||
#define MS5611_ADDR 0x77
|
||||
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "bus_i2c.h"
|
||||
#include "io.h"
|
||||
|
||||
|
|
|
@ -20,11 +20,10 @@
|
|||
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
#ifdef USE_MAG_AK8975
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
#ifdef USE_MAG_HMC5883
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/colorconversion.h"
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
#ifdef USE_MAX7456
|
||||
|
||||
#include "version.h"
|
||||
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "bus_spi.h"
|
||||
|
|
|
@ -22,8 +22,8 @@
|
|||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
|
|
|
@ -22,10 +22,10 @@
|
|||
|
||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/atomic.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "common/atomic.h"
|
||||
|
||||
#include "nvic.h"
|
||||
#include "system.h"
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "gpio.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "io.h"
|
||||
|
||||
|
|
|
@ -19,7 +19,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "nvic.h"
|
||||
|
|
|
@ -20,8 +20,10 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/atomic.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "common/atomic.h"
|
||||
|
||||
#include "nvic.h"
|
||||
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -53,8 +54,8 @@
|
|||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -82,7 +83,7 @@
|
|||
#include "flight/gtune.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
|
@ -23,13 +23,14 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
@ -46,8 +47,8 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
#include "io/display.h"
|
||||
|
@ -58,7 +59,7 @@
|
|||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "mw.h"
|
||||
#include "fc/mw.h"
|
||||
|
||||
static escAndServoConfig_t *escAndServoConfig;
|
||||
static pidProfile_t *pidProfile;
|
|
@ -18,11 +18,14 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
@ -18,7 +18,9 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "platform.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
uint8_t armingFlags = 0;
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -39,14 +39,15 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/escservo.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
int32_t setVelocity = 0;
|
||||
uint8_t velocityControl = 0;
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -28,8 +28,9 @@
|
|||
#include "drivers/system.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
|
|
@ -41,9 +41,10 @@
|
|||
#include "config/config.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern uint16_t cycleTime;
|
||||
extern uint8_t motorCount;
|
||||
|
|
|
@ -23,9 +23,10 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -47,7 +48,8 @@
|
|||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
// the limit (in degrees/second) beyond which we stop integrating
|
||||
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
|
||||
|
|
|
@ -22,9 +22,9 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -41,7 +41,7 @@
|
|||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
@ -52,7 +52,8 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
uint8_t motorCount;
|
||||
|
|
|
@ -23,7 +23,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -43,7 +44,7 @@
|
|||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
@ -54,7 +55,8 @@
|
|||
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
extern int16_t magHold;
|
||||
|
||||
|
|
|
@ -21,8 +21,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -37,7 +37,7 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
@ -45,7 +45,8 @@
|
|||
#include "flight/navigation.h"
|
||||
#include "flight/gtune.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
uint32_t targetPidLooptime;
|
||||
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
|
||||
#ifndef SKIP_PID_FLOAT
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -39,16 +39,16 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/gtune.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern float rcInput[3];
|
||||
extern float setpointRate[3];
|
||||
|
||||
|
|
|
@ -21,8 +21,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -38,15 +38,16 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/gtune.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern uint8_t motorCount;
|
||||
extern uint8_t PIDweight[3];
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include "stdlib.h"
|
||||
|
||||
#include <platform.h>
|
||||
#include "build_config.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
@ -28,7 +29,7 @@
|
|||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/vtx.h"
|
||||
|
@ -37,7 +38,8 @@
|
|||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
|
|
@ -23,10 +23,10 @@
|
|||
|
||||
#ifdef DISPLAY
|
||||
|
||||
#include "version.h"
|
||||
#include "debug.h"
|
||||
#include "build/version.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
@ -46,7 +46,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -58,7 +58,8 @@
|
|||
#endif
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
||||
#include "io/display.h"
|
||||
|
|
|
@ -26,8 +26,8 @@
|
|||
|
||||
#ifdef GPS
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -50,7 +50,7 @@
|
|||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
#define LOG_ERROR '?'
|
||||
|
|
|
@ -23,13 +23,13 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include <build_config.h>
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include <common/color.h>
|
||||
#include <common/maths.h>
|
||||
#include <common/typeconversion.h>
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "drivers/system.h"
|
||||
|
@ -44,7 +44,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -72,7 +72,8 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -23,12 +23,18 @@
|
|||
#include <ctype.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.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/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/atomic.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
||||
|
@ -64,7 +70,7 @@
|
|||
#include "io/flashfs.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/display.h"
|
||||
|
@ -91,7 +97,8 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
@ -100,11 +107,6 @@
|
|||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#ifdef OSD
|
||||
|
||||
#include "drivers/max7456.h"
|
||||
#include "drivers/max7456_symbols.h"
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
|
|
|
@ -24,10 +24,10 @@
|
|||
#include <ctype.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/version.h"
|
||||
#include "build/debug.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -54,7 +54,7 @@
|
|||
#include "io/escservo.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/flashfs.h"
|
||||
|
@ -83,7 +83,8 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/frsky.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -21,10 +21,12 @@
|
|||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -50,7 +52,7 @@
|
|||
|
||||
#include "io/beeper.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -84,14 +86,14 @@
|
|||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "mw.h"
|
||||
#include "fc/mw.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "version.h"
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include <build_config.h>
|
||||
#include <build/build_config.h>
|
||||
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/system.h"
|
||||
|
|
|
@ -50,8 +50,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/vtx.h"
|
||||
|
@ -70,7 +70,8 @@
|
|||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
static uint8_t locked = 0;
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@
|
|||
#include "io/flashfs.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/display.h"
|
||||
|
@ -102,7 +102,8 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
@ -111,8 +112,8 @@
|
|||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
extern uint8_t motorControlEnable;
|
||||
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
*
|
||||
*
|
||||
* Driver for IBUS (Flysky) receiver
|
||||
* - initial implementation for MultiWii by Cesco/Plüschi
|
||||
* - initial implementation for MultiWii by Cesco/Pl¸schi
|
||||
* - implementation for BaseFlight by Andreas (fiendie) Tacke
|
||||
* - ported to CleanFlight by Konstantin (digitalentity) Sharlaimov
|
||||
*/
|
||||
|
@ -27,7 +27,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -39,8 +39,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#ifndef SKIP_RX_MSP
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
|
|
|
@ -22,9 +22,9 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -32,14 +32,16 @@
|
|||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/pwm.h"
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "debug.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
#include "scheduler/scheduler_tasks.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
|
|
|
@ -19,7 +19,8 @@
|
|||
#include "stdint.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
@ -27,12 +28,13 @@
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -28,7 +28,8 @@
|
|||
#include "drivers/light_led.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -60,7 +60,7 @@
|
|||
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
|
|
@ -20,16 +20,18 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
|
||||
#ifdef SONAR
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/io.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -48,8 +48,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
@ -63,7 +63,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -51,8 +51,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -69,7 +69,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/io.h"
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -51,8 +51,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -69,7 +69,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -51,8 +51,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -69,7 +69,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
|
|
@ -20,9 +20,9 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -54,8 +54,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -72,7 +72,7 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include <build_config.h>
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "bus_bst.h"
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -51,8 +51,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -69,7 +69,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -6,8 +6,9 @@
|
|||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -31,7 +32,7 @@
|
|||
#include "rx/msp.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -57,14 +58,13 @@
|
|||
#include "flight/navigation.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "mw.h"
|
||||
#include "fc/mw.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "version.h"
|
||||
#ifdef NAZE
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -51,8 +51,8 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
|
@ -69,7 +69,8 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
@ -56,7 +56,8 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
|
|
@ -60,8 +60,8 @@
|
|||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -70,7 +70,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -57,7 +57,7 @@
|
|||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -78,7 +78,8 @@
|
|||
#include "telemetry/ltm.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
||||
#define LTM_CYCLETIME 100
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
|
||||
#include "io/beeper.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -58,7 +58,8 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/smartport.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
enum
|
||||
|
|
|
@ -29,9 +29,10 @@
|
|||
#include "io/serial.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
|
|
Loading…
Reference in New Issue