mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-20 14:55:18 +03:00
Moved navigation modules to navigation directory
This commit is contained in:
parent
6afd52c984
commit
58e3f5aebe
33 changed files with 196 additions and 168 deletions
12
Makefile
12
Makefile
|
@ -575,12 +575,6 @@ HIGHEND_SRC = \
|
|||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sonar_srf10.c \
|
||||
flight/navigation_rewrite.c \
|
||||
flight/navigation_rewrite_multicopter.c \
|
||||
flight/navigation_rewrite_fixedwing.c \
|
||||
flight/navigation_rewrite_fw_launch.c \
|
||||
flight/navigation_rewrite_pos_estimator.c \
|
||||
flight/navigation_rewrite_geo.c \
|
||||
io/dashboard.c \
|
||||
io/displayport_max7456.c \
|
||||
io/displayport_msp.c \
|
||||
|
@ -592,6 +586,12 @@ HIGHEND_SRC = \
|
|||
io/gps_i2cnav.c \
|
||||
io/ledstrip.c \
|
||||
io/osd.c \
|
||||
navigation/navigation.c \
|
||||
navigation/navigation_fixedwing.c \
|
||||
navigation/navigation_fw_launch.c \
|
||||
navigation/navigation_geo.c \
|
||||
navigation/navigation_multicopter.c \
|
||||
navigation/navigation_pos_estimator.c \
|
||||
sensors/barometer.c \
|
||||
sensors/pitotmeter.c \
|
||||
sensors/rangefinder.c \
|
||||
|
|
|
@ -23,6 +23,10 @@
|
|||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
@ -31,32 +35,29 @@
|
|||
#include "common/encoding.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
|
@ -64,24 +65,23 @@
|
|||
#include "io/serial.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#ifdef ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
|
||||
|
|
|
@ -19,16 +19,21 @@
|
|||
#include <stdarg.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "blackbox.h"
|
||||
#include "blackbox_io.h"
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/encoding.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/streambuf.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
|
@ -42,17 +47,18 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -61,25 +67,20 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/msp.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/flashfs.h"
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
|
||||
|
||||
|
|
|
@ -35,12 +35,13 @@
|
|||
#include "common/axis.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
|
||||
|
|
|
@ -75,7 +75,6 @@ extern uint8_t __config_end;
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -88,6 +87,8 @@ extern uint8_t __config_end;
|
|||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -62,7 +63,6 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -71,7 +71,7 @@
|
|||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#ifndef DEFAULT_RX_FEATURE
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
|
||||
|
|
|
@ -63,6 +63,8 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
|
@ -74,8 +76,8 @@
|
|||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
|
|
@ -87,6 +87,8 @@
|
|||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
|
@ -110,7 +112,6 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -53,7 +53,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/hil.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -73,6 +72,8 @@
|
|||
#include "msp/msp_protocol.h"
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
|
|
|
@ -43,12 +43,13 @@
|
|||
#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 "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
|
|
|
@ -38,7 +38,8 @@
|
|||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
|
|
@ -21,11 +21,12 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#ifdef HIL
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -40,13 +41,13 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/hil.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#ifdef HIL
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
bool hilActive = false;
|
||||
hilIncomingStateData_t hilToFC;
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
|
@ -35,6 +36,8 @@
|
|||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -50,9 +53,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
//#define MIXER_DEBUG
|
||||
|
||||
|
|
|
@ -39,10 +39,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -31,9 +31,10 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/config_reset.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
@ -41,6 +42,8 @@
|
|||
|
||||
#include "io/gimbal.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -56,9 +59,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
||||
extern const mixer_t mixers[];
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/dashboard.h"
|
||||
#include "io/displayport_oled.h"
|
||||
|
@ -54,6 +53,8 @@
|
|||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
|
|
@ -39,13 +39,15 @@
|
|||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/hil.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
|
||||
#define GPS_I2C_POLL_RATE_HZ 20 // Poll I2C GPS at this rate
|
||||
|
||||
bool gpsDetectI2CNAV(void)
|
||||
|
|
|
@ -27,11 +27,14 @@
|
|||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/typeconversion.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
|
@ -39,14 +42,25 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/barometer.h"
|
||||
|
@ -56,24 +70,8 @@
|
|||
#include "sensors/sensors.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
extern uint16_t rssi; // FIXME dependency on mw.c
|
||||
|
||||
|
|
|
@ -68,10 +68,11 @@
|
|||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -34,21 +34,23 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Compatibility for home position
|
|
@ -39,14 +39,15 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
// If we are going slower than NAV_FW_MIN_VEL_SPEED_BOOST - boost throttle to fight against the wind
|
||||
#define NAV_FW_THROTTLE_SPEED_BOOST_GAIN 1.5f
|
||||
#define NAV_FW_MIN_VEL_SPEED_BOOST 700.0f // 7 m/s
|
|
@ -30,6 +30,8 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
@ -47,14 +49,13 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
typedef struct FixedWingLaunchState_s {
|
|
@ -36,12 +36,14 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
#if defined(NAV_AUTO_MAG_DECLINATION)
|
||||
/* Declination calculation code from PX4 project */
|
||||
/* set this always to the sampling in degrees for the table below */
|
|
@ -43,11 +43,13 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Altitude controller for multicopter aircraft
|
||||
*-----------------------------------------------------------*/
|
|
@ -40,12 +40,13 @@
|
|||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
|
@ -31,29 +31,30 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/frsky.h"
|
||||
|
|
|
@ -73,15 +73,16 @@
|
|||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/hott.h"
|
||||
|
||||
|
|
|
@ -47,36 +47,37 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/ltm.h"
|
||||
|
||||
|
||||
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
||||
#define LTM_CYCLETIME 100
|
||||
|
||||
|
|
|
@ -48,7 +48,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -57,6 +56,10 @@
|
|||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
|
@ -65,8 +68,6 @@
|
|||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/mavlink.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
|
|
|
@ -15,32 +15,34 @@
|
|||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/smartport.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
enum
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue