mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-15 04:15:38 +03:00
Minor changes to directory structure to reflect changes in Cleanflight and betaflight
This commit is contained in:
parent
9e214889c9
commit
944adb06f8
106 changed files with 357 additions and 216 deletions
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,12 +357,12 @@ 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 \
|
||||
|
@ -370,7 +370,7 @@ COMMON_SRC = \
|
|||
common/typeconversion.c \
|
||||
common/streambuf.c \
|
||||
config/config.c \
|
||||
config/runtime_config.c \
|
||||
fc/runtime_config.c \
|
||||
drivers/adc.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
|
@ -398,8 +398,8 @@ COMMON_SRC = \
|
|||
flight/mixer.c \
|
||||
flight/pid.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 \
|
||||
|
|
|
@ -20,10 +20,11 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.h"
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
|
@ -49,10 +50,12 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -71,7 +74,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -21,8 +21,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"
|
||||
|
@ -52,7 +52,8 @@
|
|||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
|
@ -70,7 +71,7 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.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,14 @@
|
|||
|
||||
#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 "build/build_config.h"
|
||||
|
||||
#include "printf.h"
|
||||
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
|
|
|
@ -17,7 +17,8 @@
|
|||
#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
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -50,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"
|
||||
|
||||
|
@ -68,7 +69,8 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -19,8 +19,10 @@
|
|||
#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,8 @@
|
|||
|
||||
#ifdef USE_ACC_LSM303DLHC
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
|
|
@ -21,8 +21,10 @@
|
|||
#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,10 @@
|
|||
#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"
|
||||
|
||||
|
|
|
@ -38,7 +38,8 @@
|
|||
#include "exti.h"
|
||||
#include "bus_spi.h"
|
||||
#include "gyro_sync.h"
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "sensor.h"
|
||||
#include "accgyro.h"
|
||||
|
|
|
@ -19,8 +19,10 @@
|
|||
#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,8 @@
|
|||
|
||||
#ifdef USE_ADC
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "system.h"
|
||||
#include "sensor.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
|
|
|
@ -25,7 +25,8 @@
|
|||
#include "system.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/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"
|
||||
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
|
||||
#ifdef USE_SOFTSPI
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
|
|
|
@ -20,11 +20,13 @@
|
|||
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -24,7 +24,8 @@
|
|||
|
||||
#ifdef USE_MAG_AK8975
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -24,7 +24,8 @@
|
|||
|
||||
#ifdef USE_MAG_HMC5883
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -24,7 +24,8 @@
|
|||
|
||||
#ifdef USE_MAG_MAG3110
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "gps_i2cnav.h"
|
||||
|
||||
|
|
|
@ -19,7 +19,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -28,7 +29,8 @@
|
|||
#include "drivers/accgyro.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
extern gyro_t gyro;
|
||||
|
|
|
@ -32,7 +32,8 @@
|
|||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/colorconversion.h"
|
||||
|
|
|
@ -22,8 +22,10 @@
|
|||
|
||||
#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"
|
||||
|
||||
|
|
|
@ -26,7 +26,8 @@
|
|||
|
||||
#ifdef USE_RX_NRF24
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
|
|
|
@ -22,10 +22,11 @@
|
|||
|
||||
#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,8 @@
|
|||
|
||||
#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"
|
||||
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
|
||||
#if defined(SONAR)
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "system.h"
|
||||
#include "exti.h"
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
|
||||
#if defined(SONAR) && defined(USE_SONAR_SRF10)
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
|
|
|
@ -20,11 +20,12 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/atomic.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "common/atomic.h"
|
||||
|
||||
#include "nvic.h"
|
||||
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
#include "system.h"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
#include "scheduler/scheduler_tasks.h"
|
||||
|
@ -53,11 +54,13 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -80,7 +83,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -43,8 +43,10 @@
|
|||
#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 "fc/runtime_config.h"
|
||||
|
||||
#include "io/display.h"
|
||||
|
||||
|
@ -53,7 +55,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
|
@ -19,10 +19,10 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "io/escservo.h"
|
||||
|
||||
#include "io/rc_curves.h"
|
||||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define YAW_LOOKUP_LENGTH 7
|
|
@ -17,7 +17,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig);
|
||||
struct controlRateConfig_s;
|
||||
struct escAndServoConfig_s;
|
||||
void generateThrottleCurve(struct controlRateConfig_s *controlRateConfig, struct escAndServoConfig_s *escAndServoConfig);
|
||||
|
||||
int16_t rcLookup(int32_t stickDeflection, uint8_t expo);
|
||||
int16_t rcLookupThrottle(int32_t tmp);
|
|
@ -18,7 +18,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
uint8_t armingFlags = 0;
|
|
@ -20,9 +20,11 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -30,8 +32,10 @@
|
|||
#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"
|
||||
|
|
|
@ -21,9 +21,11 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -43,7 +45,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#ifdef HIL
|
||||
|
|
|
@ -23,10 +23,13 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
#include "build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
|
@ -48,7 +51,8 @@
|
|||
#include "flight/hil.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
/**
|
||||
|
|
|
@ -21,9 +21,11 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -40,7 +42,8 @@
|
|||
|
||||
#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"
|
||||
|
@ -51,7 +54,8 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
||||
|
|
|
@ -19,9 +19,11 @@
|
|||
#include <stdint.h>
|
||||
#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"
|
||||
|
@ -43,7 +45,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
|
|
|
@ -19,12 +19,12 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(NAV)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -43,7 +43,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
// If we are going slower than NAV_FW_MIN_VEL_SPEED_BOOST - boost throttle to fight against the wind
|
||||
|
|
|
@ -19,12 +19,12 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(NAV)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -42,7 +42,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#if defined(NAV_AUTO_MAG_DECLINATION)
|
||||
|
|
|
@ -19,12 +19,12 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(NAV)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -39,8 +39,10 @@
|
|||
#include "sensors/boardalignment.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 "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -48,7 +50,6 @@
|
|||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
|
|
|
@ -20,12 +20,12 @@
|
|||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(NAV)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -47,7 +47,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
/**
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#if defined(NAV)
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#define MIN_POSITION_UPDATE_RATE_HZ 5 // Minimum position update rate at which XYZ controllers would be applied
|
||||
#define NAV_THROTTLE_CUTOFF_FREQENCY_HZ 4 // low-pass filter on throttle output
|
||||
|
|
|
@ -21,10 +21,13 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -40,7 +43,8 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
|
|
@ -17,12 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#define GYRO_SATURATION_LIMIT 1800 // 1800dps
|
||||
#define PID_MAX_OUTPUT 1000
|
||||
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
|
||||
|
@ -78,8 +72,10 @@ extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[];
|
|||
|
||||
void pidInit(void);
|
||||
void pidResetErrorAccumulators(void);
|
||||
void updatePIDCoefficients(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, const rxConfig_t *rxConfig);
|
||||
void pidController(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, const rxConfig_t *rxConfig);
|
||||
struct controlRateConfig_s;
|
||||
struct rxConfig_s;
|
||||
void updatePIDCoefficients(const pidProfile_t *pidProfile, const struct controlRateConfig_s *controlRateConfig, const struct rxConfig_s *rxConfig);
|
||||
void pidController(const pidProfile_t *pidProfile, const struct controlRateConfig_s *controlRateConfig, const struct rxConfig_s *rxConfig);
|
||||
|
||||
float pidRateToRcCommand(float rateDPS, uint8_t rate);
|
||||
int16_t pidAngleToRcCommand(float angleDeciDegrees, int16_t maxInclination);
|
||||
|
|
|
@ -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"
|
||||
|
@ -29,14 +30,16 @@
|
|||
#include "sensors/sensors.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#ifdef GPS
|
||||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
|
|
@ -21,9 +21,11 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#ifdef DISPLAY
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
@ -37,8 +39,6 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
||||
#ifdef DISPLAY
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/compass.h"
|
||||
|
@ -48,7 +48,8 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -59,7 +60,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#endif
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
|
|
|
@ -21,11 +21,13 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#ifdef GPS
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -50,7 +52,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2000 ms)
|
||||
#define GPS_TIMEOUT (2000)
|
||||
|
|
|
@ -20,11 +20,11 @@
|
|||
#include <ctype.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
|
||||
#if defined(GPS) && defined(GPS_PROTO_I2C_NAV)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -44,7 +44,7 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#define GPS_I2C_POLL_RATE_HZ 20 // Poll I2C GPS at this rate
|
||||
|
||||
|
|
|
@ -22,11 +22,13 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#if defined(GPS) && defined(GPS_PROTO_NAZA)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -43,7 +45,8 @@
|
|||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
#define NAZA_MAX_PAYLOAD_SIZE 256
|
||||
|
||||
|
|
|
@ -22,11 +22,13 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#if defined(GPS) && defined(GPS_PROTO_NMEA)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -43,7 +45,7 @@
|
|||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
/* This is a light implementation of a GPS frame decoding
|
||||
This should work with most of modern GPS devices configured to output 5 frames.
|
||||
|
|
|
@ -23,11 +23,13 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#if defined(GPS) && defined(GPS_PROTO_UBLOX)
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -44,7 +46,7 @@
|
|||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
//#define GPS_PROTO_UBLOX_NEO7PLUS
|
||||
#define GPS_VERSION_DETECTION_TIMEOUT_MS 300
|
||||
|
|
|
@ -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,8 @@
|
|||
#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"
|
||||
|
@ -70,7 +71,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"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
|
|
|
@ -24,12 +24,12 @@
|
|||
#include <ctype.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "version.h"
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/color.h"
|
||||
|
@ -55,7 +55,8 @@
|
|||
#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"
|
||||
|
@ -82,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 "scheduler/scheduler.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
@ -52,7 +54,8 @@
|
|||
#include "blackbox/blackbox.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"
|
||||
|
@ -79,16 +82,15 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.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 "blackbox/blackbox.h"
|
||||
|
||||
#include "version.h"
|
||||
#ifdef NAZE
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
|
|
@ -21,9 +21,12 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/atomic.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/atomic.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
|
||||
|
@ -65,7 +68,8 @@
|
|||
#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"
|
||||
|
@ -94,7 +98,8 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.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"
|
||||
|
@ -103,8 +108,6 @@
|
|||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
extern uint8_t motorControlEnable;
|
||||
|
||||
|
|
|
@ -27,7 +27,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -40,7 +40,8 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
|
@ -61,7 +62,8 @@
|
|||
#endif //TELEMETRY
|
||||
|
||||
|
||||
#include "debug.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
//
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#ifndef SKIP_RX_MSP
|
||||
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
|
||||
#ifdef USE_RX_NRF24
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "rx/rx.h"
|
||||
#include "rx/nrf24.h"
|
||||
|
|
|
@ -23,7 +23,8 @@
|
|||
#include <string.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#ifdef USE_RX_CX10
|
||||
|
||||
|
|
|
@ -26,7 +26,8 @@
|
|||
|
||||
#ifdef USE_RX_H8_3D
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_xn297.h"
|
||||
|
|
|
@ -23,7 +23,8 @@
|
|||
#include <string.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#ifdef USE_RX_SYMA
|
||||
|
||||
|
|
|
@ -23,7 +23,8 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#ifdef USE_RX_V202
|
||||
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include <string.h>
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
|
|
@ -22,8 +22,10 @@
|
|||
#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"
|
||||
|
@ -34,7 +36,8 @@
|
|||
#include "drivers/adc.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#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,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -27,7 +27,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
|
|
@ -25,8 +25,10 @@ typedef enum {TEST_IRQ = 0 } IRQn_Type;
|
|||
#include "platform.h"
|
||||
|
||||
#include "scheduler.h"
|
||||
#include "debug.h"
|
||||
#include "build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
|
|
|
@ -33,7 +33,8 @@
|
|||
#include "sensors/sensors.h"
|
||||
#include "io/beeper.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
|
|
|
@ -26,14 +26,16 @@
|
|||
#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 "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
||||
#define VBATT_PRESENT_THRESHOLD_MV 10
|
||||
|
|
|
@ -31,7 +31,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 "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -61,7 +62,8 @@
|
|||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/sonar_srf10.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -24,12 +24,14 @@
|
|||
|
||||
#ifdef SONAR
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/sonar_hcsr04.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"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
|
|
@ -21,7 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
|
|
@ -45,7 +45,9 @@
|
|||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue