mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-21 15:25:29 +03:00
Reduced and rationalised #includes
This commit is contained in:
parent
ef43ccadc9
commit
d9f35dfc79
57 changed files with 114 additions and 297 deletions
|
@ -31,12 +31,10 @@
|
||||||
#include "common/encoding.h"
|
#include "common/encoding.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
|
|
|
@ -38,11 +38,9 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "io/serial.h"
|
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "printf.h"
|
#include "printf.h"
|
||||||
|
|
||||||
|
|
|
@ -107,8 +107,6 @@ regs Kusti, 23.10.2004
|
||||||
|
|
||||||
#include <stdarg.h>
|
#include <stdarg.h>
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
|
|
||||||
void init_printf(void *putp, void (*putf) (void *, char));
|
void init_printf(void *putp, void (*putf) (void *, char));
|
||||||
|
|
||||||
int tfp_printf(const char *fmt, ...);
|
int tfp_printf(const char *fmt, ...);
|
||||||
|
@ -120,6 +118,7 @@ int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list
|
||||||
#define sprintf tfp_sprintf
|
#define sprintf tfp_sprintf
|
||||||
|
|
||||||
void printfSupportInit(void);
|
void printfSupportInit(void);
|
||||||
void setPrintfSerialPort(serialPort_t *serialPort);
|
struct serialPort_s;
|
||||||
|
void setPrintfSerialPort(struct serialPort_s *serialPort);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -30,15 +30,9 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/rx_spi.h"
|
#include "drivers/rx_spi.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
|
@ -26,12 +26,7 @@
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
|
@ -52,6 +52,7 @@
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/servos.h"
|
#include "flight/servos.h"
|
||||||
|
#include "flight/navigation_rewrite.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
|
@ -17,62 +17,11 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <string.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "common/axis.h"
|
|
||||||
#include "common/color.h"
|
|
||||||
#include "common/maths.h"
|
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/rx_spi.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
|
||||||
#include "sensors/gyro.h"
|
|
||||||
#include "sensors/compass.h"
|
|
||||||
#include "sensors/acceleration.h"
|
|
||||||
#include "sensors/barometer.h"
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "sensors/battery.h"
|
|
||||||
|
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/serial.h"
|
|
||||||
#include "io/gimbal.h"
|
|
||||||
#include "io/motors.h"
|
|
||||||
#include "io/servos.h"
|
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "fc/rc_curves.h"
|
|
||||||
#include "io/ledstrip.h"
|
|
||||||
#include "io/gps.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "rx/rx_spi.h"
|
|
||||||
|
|
||||||
#include "blackbox/blackbox_io.h"
|
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
|
||||||
#include "flight/servos.h"
|
|
||||||
#include "flight/pid.h"
|
|
||||||
#include "flight/imu.h"
|
|
||||||
#include "flight/failsafe.h"
|
|
||||||
#include "flight/navigation_rewrite.h"
|
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
|
|
||||||
#include "config/config_profile.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
static uint32_t activeFeaturesLatch = 0;
|
static uint32_t activeFeaturesLatch = 0;
|
||||||
|
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
||||||
#define I2C_DEFAULT_TIMEOUT I2C_LONG_TIMEOUT
|
#define I2C_DEFAULT_TIMEOUT I2C_LONG_TIMEOUT
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io_types.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc_types.h"
|
||||||
|
|
||||||
#ifndef I2C_DEVICE
|
#ifndef I2C_DEVICE
|
||||||
#define I2C_DEVICE I2CINVALID
|
#define I2C_DEVICE I2CINVALID
|
||||||
|
|
|
@ -21,7 +21,10 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "fc/fc_init.h"
|
#include "fc/fc_init.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
#ifdef DEBUG_HARDFAULTS
|
#ifdef DEBUG_HARDFAULTS
|
||||||
|
|
|
@ -35,15 +35,11 @@
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
|
|
||||||
#include "fc/fc_msp.h"
|
#include "fc/fc_msp.h"
|
||||||
|
|
|
@ -31,14 +31,10 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/gyro_sync.h"
|
#include "drivers/gyro_sync.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
|
@ -25,12 +25,30 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "blackbox/blackbox.h"
|
||||||
|
|
||||||
#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 "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
#include "fc/mw.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/rc_curves.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/pid.h"
|
||||||
|
#include "flight/navigation_rewrite.h"
|
||||||
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
|
#include "io/gps.h"
|
||||||
|
#include "io/beeper.h"
|
||||||
|
#include "io/motors.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
@ -38,29 +56,6 @@
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "io/gps.h"
|
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/motors.h"
|
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "fc/rc_curves.h"
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "io/display.h"
|
|
||||||
|
|
||||||
#include "flight/pid.h"
|
|
||||||
#include "flight/navigation_rewrite.h"
|
|
||||||
#include "flight/failsafe.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
|
||||||
#include "config/feature.h"
|
|
||||||
|
|
||||||
#include "blackbox/blackbox.h"
|
|
||||||
|
|
||||||
#include "mw.h"
|
|
||||||
|
|
||||||
#define AIRMODE_DEADBAND 25
|
#define AIRMODE_DEADBAND 25
|
||||||
|
|
||||||
static motorConfig_t *motorConfig;
|
static motorConfig_t *motorConfig;
|
||||||
|
|
|
@ -32,8 +32,6 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
|
@ -35,9 +35,6 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
|
|
|
@ -34,21 +34,19 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/system.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "fc/rc_controls.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"
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/servos.h"
|
#include "flight/servos.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
@ -56,8 +54,6 @@
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/navigation_rewrite.h"
|
#include "flight/navigation_rewrite.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
|
@ -30,8 +30,6 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
|
@ -31,8 +31,6 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
|
@ -29,10 +29,6 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
|
@ -26,14 +26,12 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
|
@ -31,8 +31,6 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/rangefinder.h"
|
#include "sensors/rangefinder.h"
|
||||||
|
|
|
@ -22,34 +22,27 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
#include "common/filter.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/pid.h"
|
||||||
|
#include "flight/imu.h"
|
||||||
|
#include "flight/navigation_rewrite.h"
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "io/gps.h"
|
||||||
#include "common/maths.h"
|
|
||||||
#include "common/filter.h"
|
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
#include "rx/rx.h"
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gyro_sync.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
|
||||||
#include "io/gps.h"
|
|
||||||
|
|
||||||
#include "flight/pid.h"
|
|
||||||
#include "flight/imu.h"
|
|
||||||
#include "flight/navigation_rewrite.h"
|
|
||||||
|
|
||||||
#define MAG_HOLD_ERROR_LPF_FREQ 2
|
#define MAG_HOLD_ERROR_LPF_FREQ 2
|
||||||
|
|
||||||
|
|
|
@ -31,22 +31,22 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/servos.h"
|
#include "io/servos.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
#include "rx/rx.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"
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/servos.h"
|
#include "flight/servos.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
@ -54,12 +54,11 @@
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/navigation_rewrite.h"
|
#include "flight/navigation_rewrite.h"
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
|
||||||
extern mixerMode_e currentMixerMode;
|
extern mixerMode_e currentMixerMode;
|
||||||
extern const mixer_t mixers[];
|
extern const mixer_t mixers[];
|
||||||
extern mixerConfig_t *mixerConfig;
|
extern mixerConfig_t *mixerConfig;
|
||||||
|
|
|
@ -23,14 +23,13 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
|
|
||||||
|
@ -38,6 +37,7 @@
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
|
@ -27,12 +27,8 @@
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/display_ug2864hsweg01.h"
|
#include "drivers/display_ug2864hsweg01.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
|
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
|
@ -28,18 +28,14 @@
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/light_led.h"
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
|
@ -26,13 +26,13 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "common/maths.h"
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/gps_i2cnav.h"
|
#include "drivers/gps_i2cnav.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
|
@ -29,14 +29,12 @@
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
|
@ -29,14 +29,12 @@
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
|
@ -19,6 +19,8 @@
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
#define GPS_HDOP_TO_EPH_MULTIPLIER 2 // empirical value
|
#define GPS_HDOP_TO_EPH_MULTIPLIER 2 // empirical value
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
|
@ -35,9 +35,8 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
|
@ -32,26 +32,22 @@
|
||||||
#include "common/typeconversion.h"
|
#include "common/typeconversion.h"
|
||||||
|
|
||||||
#include "drivers/light_ws2811strip.h"
|
#include "drivers/light_ws2811strip.h"
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
|
|
||||||
#include <common/printf.h>
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
#include "common/printf.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
|
||||||
#include "sensors/sensors.h"
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "sensors/gyro.h"
|
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
|
#include "sensors/gyro.h"
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
@ -63,6 +59,8 @@
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/servos.h"
|
#include "flight/servos.h"
|
||||||
|
@ -70,15 +68,12 @@
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/navigation_rewrite.h"
|
#include "flight/navigation_rewrite.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/config_profile.h"
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
PG_REGISTER_ARR_WITH_RESET_FN(ledConfig_t, LED_MAX_STRIP_LENGTH, ledConfigs, PG_LED_STRIP_CONFIG, 0);
|
PG_REGISTER_ARR_WITH_RESET_FN(ledConfig_t, LED_MAX_STRIP_LENGTH, ledConfigs, PG_LED_STRIP_CONFIG, 0);
|
||||||
PG_REGISTER_ARR_WITH_RESET_FN(hsvColor_t, LED_CONFIGURABLE_COLOR_COUNT, colors, PG_COLOR_CONFIG, 0);
|
PG_REGISTER_ARR_WITH_RESET_FN(hsvColor_t, LED_CONFIGURABLE_COLOR_COUNT, colors, PG_COLOR_CONFIG, 0);
|
||||||
|
|
|
@ -43,10 +43,8 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/compass.h"
|
#include "drivers/compass.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
|
@ -21,9 +21,7 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
#include "drivers/sound_beeper.h"
|
|
||||||
|
|
||||||
#include "statusindicator.h"
|
#include "statusindicator.h"
|
||||||
|
|
||||||
|
|
|
@ -29,11 +29,9 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -42,10 +42,12 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/jetiexbus.h"
|
#include "rx/jetiexbus.h"
|
||||||
|
|
||||||
|
@ -57,6 +59,7 @@
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/jetiexbus.h"
|
#include "telemetry/jetiexbus.h"
|
||||||
|
|
||||||
|
@ -611,6 +614,6 @@ void sendJetiExBusTelemetry(uint8_t packetID)
|
||||||
requestLoop++;
|
requestLoop++;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //TELEMETRY
|
#endif // TELEMETRY
|
||||||
|
|
||||||
#endif //SKIP_SERIALRX_JETIEXBUS
|
#endif // USE_SERIALRX_JETIEXBUS
|
||||||
|
|
|
@ -25,10 +25,6 @@
|
||||||
|
|
||||||
#ifndef SKIP_RX_MSP
|
#ifndef SKIP_RX_MSP
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
|
||||||
|
|
|
@ -28,8 +28,6 @@
|
||||||
|
|
||||||
#ifndef SKIP_RX_PWM_PPM
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
|
@ -31,12 +31,10 @@
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
#include "drivers/rx_spi.h"
|
#include "drivers/rx_spi.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -23,14 +23,9 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/inverter.h"
|
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -20,17 +20,15 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
#include "build/debug.h"
|
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/light_led.h"
|
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
|
@ -23,11 +23,9 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -29,11 +29,9 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -21,10 +21,9 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
|
@ -26,8 +26,6 @@
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gyro_sync.h"
|
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
|
@ -17,6 +17,10 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/accgyro.h"
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
// Type of accelerometer used/detected
|
// Type of accelerometer used/detected
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ACC_DEFAULT = 0,
|
ACC_DEFAULT = 0,
|
||||||
|
|
|
@ -25,17 +25,14 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/compass_hmc5883l.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/light_led.h"
|
|
||||||
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "fc/runtime_config.h"
|
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
|
#include "drivers/compass.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
|
|
|
@ -17,6 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
// Type of magnetometer used/detected
|
// Type of magnetometer used/detected
|
||||||
typedef enum {
|
typedef enum {
|
||||||
MAG_DEFAULT = 0,
|
MAG_DEFAULT = 0,
|
||||||
|
@ -33,7 +35,8 @@ typedef enum {
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
bool compassInit(int16_t magDeclinationFromConfig);
|
bool compassInit(int16_t magDeclinationFromConfig);
|
||||||
void updateCompass(flightDynamicsTrims_t *magZero);
|
union flightDynamicsTrims_u;
|
||||||
|
void updateCompass(union flightDynamicsTrims_u *magZero);
|
||||||
bool isCompassReady(void);
|
bool isCompassReady(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -25,10 +25,6 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gyro_sync.h"
|
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
|
|
||||||
|
|
|
@ -17,6 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/accgyro.h"
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GYRO_NONE = 0,
|
GYRO_NONE = 0,
|
||||||
GYRO_DEFAULT,
|
GYRO_DEFAULT,
|
||||||
|
|
|
@ -32,13 +32,8 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.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"
|
||||||
|
|
|
@ -33,8 +33,6 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
|
@ -46,12 +46,7 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
|
@ -35,12 +35,7 @@
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -16,16 +16,7 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/bus_i2c.h"
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/adc.h"
|
|
||||||
#include "drivers/light_led.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
@ -33,24 +24,15 @@
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/motors.h"
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/gimbal.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "sensors/sensors.h"
|
|
||||||
#include "sensors/battery.h"
|
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
#include "sensors/battery.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "sensors/compass.h"
|
|
||||||
#include "sensors/gyro.h"
|
|
||||||
|
|
||||||
#include "flight/pid.h"
|
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/mixer.h"
|
|
||||||
#include "flight/failsafe.h"
|
|
||||||
#include "flight/navigation_rewrite.h"
|
#include "flight/navigation_rewrite.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
|
@ -25,20 +25,17 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_softserial.h"
|
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "rx/rx.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 "config/config.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/frsky.h"
|
#include "telemetry/frsky.h"
|
||||||
#include "telemetry/hott.h"
|
#include "telemetry/hott.h"
|
||||||
|
|
|
@ -51,7 +51,8 @@ typedef struct telemetryConfig_s {
|
||||||
|
|
||||||
void telemetryInit(void);
|
void telemetryInit(void);
|
||||||
bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig);
|
bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig);
|
||||||
extern serialPort_t *telemetrySharedPort;
|
struct serialPort_s;
|
||||||
|
extern struct serialPort_s *telemetrySharedPort;
|
||||||
|
|
||||||
void telemetryCheckState(void);
|
void telemetryCheckState(void);
|
||||||
struct rxConfig_s;
|
struct rxConfig_s;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue