mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 14:25:16 +03:00
Renamed config/config.* to fc/config.*
This commit is contained in:
parent
12fe47a1d3
commit
0d2d74a259
65 changed files with 139 additions and 111 deletions
2
Makefile
2
Makefile
|
@ -471,10 +471,10 @@ COMMON_SRC = \
|
|||
common/printf.c \
|
||||
common/typeconversion.c \
|
||||
common/streambuf.c \
|
||||
config/config.c \
|
||||
config/feature.c \
|
||||
config/config_eeprom.c \
|
||||
config/parameter_group.c \
|
||||
fc/config.c \
|
||||
fc/runtime_config.c \
|
||||
drivers/logging.c \
|
||||
drivers/adc.c \
|
||||
|
|
|
@ -49,6 +49,7 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
@ -73,7 +74,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -76,8 +76,9 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
|
|
@ -43,10 +43,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -40,10 +40,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -31,10 +31,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -31,10 +31,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -32,10 +32,11 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -43,8 +43,11 @@
|
|||
#include "io/gimbal.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
|
@ -58,7 +61,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -27,11 +27,14 @@
|
|||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
@ -62,9 +65,6 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
||||
#define motorConfig(x) (&masterConfig.motorConfig)
|
||||
#define flight3DConfig(x) (&masterConfig.flight3DConfig)
|
||||
#define servoConfig(x) (&masterConfig.servoConfig)
|
||||
|
|
|
@ -32,16 +32,6 @@ const pgRegistry_t* pgFind(pgn_t pgn)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const pgRegistry_t* pgMatcher(pgMatcherFuncPtr matcher, const void *criteria)
|
||||
{
|
||||
PG_FOREACH(candidate) {
|
||||
if (matcher(candidate, criteria)) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static uint8_t *pgOffset(const pgRegistry_t* reg, uint8_t profileIndex)
|
||||
{
|
||||
const uint16_t regSize = pgSize(reg);
|
||||
|
@ -58,7 +48,7 @@ static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base)
|
|||
const uint16_t regSize = pgSize(reg);
|
||||
|
||||
memset(base, 0, regSize);
|
||||
if(reg->reset.ptr >= (void*)__pg_resetdata_start && reg->reset.ptr < (void*)__pg_resetdata_end) {
|
||||
if (reg->reset.ptr >= (void*)__pg_resetdata_start && reg->reset.ptr < (void*)__pg_resetdata_end) {
|
||||
// pointer points to resetdata section, to it is data template
|
||||
memcpy(base, reg->reset.ptr, regSize);
|
||||
} else if (reg->reset.fn) {
|
||||
|
@ -67,21 +57,38 @@ static void pgResetInstance(const pgRegistry_t *reg, uint8_t *base)
|
|||
}
|
||||
}
|
||||
|
||||
void pgReset(const pgRegistry_t* reg, int profileIndex)
|
||||
{
|
||||
pgResetInstance(reg, pgOffset(reg, profileIndex));
|
||||
}
|
||||
|
||||
void pgResetCurrent(const pgRegistry_t *reg)
|
||||
{
|
||||
if(pgIsSystem(reg)) {
|
||||
if (pgIsSystem(reg)) {
|
||||
pgResetInstance(reg, reg->address);
|
||||
} else {
|
||||
pgResetInstance(reg, *reg->ptr);
|
||||
}
|
||||
}
|
||||
|
||||
void pgLoad(const pgRegistry_t* reg, const void *from, int size, uint8_t profileIndex)
|
||||
bool pgResetCopy(void *copy, pgn_t pgn)
|
||||
{
|
||||
pgResetInstance(reg,pgOffset(reg, profileIndex));
|
||||
const pgRegistry_t *reg = pgFind(pgn);
|
||||
if (reg) {
|
||||
pgResetInstance(reg, copy);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
const int take = MIN(size, pgSize(reg));
|
||||
memcpy(pgOffset(reg, profileIndex), from, take);
|
||||
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version)
|
||||
{
|
||||
pgResetInstance(reg, pgOffset(reg, profileIndex));
|
||||
// restore only matching version, keep defaults otherwise
|
||||
if (version == pgVersion(reg)) {
|
||||
const int take = MIN(size, pgSize(reg));
|
||||
memcpy(pgOffset(reg, profileIndex), from, take);
|
||||
}
|
||||
}
|
||||
|
||||
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex)
|
||||
|
@ -92,25 +99,25 @@ int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex)
|
|||
}
|
||||
|
||||
|
||||
void pgResetAll(uint8_t profileCount)
|
||||
void pgResetAll(int profileCount)
|
||||
{
|
||||
PG_FOREACH(reg) {
|
||||
if (pgIsSystem(reg)) {
|
||||
pgResetInstance(reg, reg->address);
|
||||
pgReset(reg, 0);
|
||||
} else {
|
||||
// reset one instance for each profile
|
||||
for (uint8_t profileIndex = 0; profileIndex < profileCount; profileIndex++) {
|
||||
pgResetInstance(reg, pgOffset(reg, profileIndex));
|
||||
for (int profileIndex = 0; profileIndex < profileCount; profileIndex++) {
|
||||
pgReset(reg, profileIndex);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void pgActivateProfile(uint8_t profileIndexToActivate)
|
||||
void pgActivateProfile(int profileIndex)
|
||||
{
|
||||
PG_FOREACH(reg) {
|
||||
if (!pgIsSystem(reg)) {
|
||||
uint8_t *ptr = pgOffset(reg, profileIndexToActivate);
|
||||
uint8_t *ptr = pgOffset(reg, profileIndex);
|
||||
*(reg->ptr) = ptr;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -17,12 +17,15 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
typedef uint16_t pgn_t;
|
||||
|
||||
// parameter group registry flags
|
||||
typedef enum {
|
||||
PGRF_NONE = 0,
|
||||
PGRF_CLASSIFICATON_BIT = (1 << 0),
|
||||
PGRF_CLASSIFICATON_BIT = (1 << 0)
|
||||
} pgRegistryFlags_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -30,7 +33,7 @@ typedef enum {
|
|||
PGR_PGN_VERSION_MASK = 0xf000,
|
||||
PGR_SIZE_MASK = 0x0fff,
|
||||
PGR_SIZE_SYSTEM_FLAG = 0x0000, // documentary
|
||||
PGR_SIZE_PROFILE_FLAG = 0x8000, // start using flags from the top bit down
|
||||
PGR_SIZE_PROFILE_FLAG = 0x8000 // start using flags from the top bit down
|
||||
} pgRegistryInternal_e;
|
||||
|
||||
// function that resets a single parameter group instance
|
||||
|
@ -167,7 +170,7 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
/**/
|
||||
|
||||
#if 0
|
||||
// ARRAY reset mechanism is not implemented yet, only few places in code would benefit from it.
|
||||
// ARRAY reset mechanism is not implemented yet, only few places in code would benefit from it - See pgResetInstance
|
||||
#define PG_REGISTER_ARR_WITH_RESET_TEMPLATE(_type, _size, _name, _pgn, _version) \
|
||||
extern const _type pgResetTemplate_ ## _name; \
|
||||
PG_REGISTER_ARR_I(_type, _size, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \
|
||||
|
@ -219,12 +222,12 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
} \
|
||||
/**/
|
||||
|
||||
typedef uint8_t (*pgMatcherFuncPtr)(const pgRegistry_t *candidate, const void *criteria);
|
||||
|
||||
const pgRegistry_t* pgFind(pgn_t pgn);
|
||||
const pgRegistry_t* pgMatcher(pgMatcherFuncPtr matcher, const void *criteria);
|
||||
void pgLoad(const pgRegistry_t* reg, const void *from, int size, uint8_t profileIndex);
|
||||
|
||||
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version);
|
||||
int pgStore(const pgRegistry_t* reg, void *to, int size, uint8_t profileIndex);
|
||||
void pgResetAll(uint8_t profileCount);
|
||||
void pgActivateProfile(uint8_t profileIndexToActivate);
|
||||
void pgResetAll(int profileCount);
|
||||
void pgResetCurrent(const pgRegistry_t *reg);
|
||||
bool pgResetCopy(void *copy, pgn_t pgn);
|
||||
void pgReset(const pgRegistry_t* reg, int profileIndex);
|
||||
void pgActivateProfile(int profileIndex);
|
||||
|
|
|
@ -29,11 +29,10 @@
|
|||
|
||||
#include "io/pwmdriver_i2c.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#if defined(STM32F40_41xxx) // must be multiples of timer clock
|
||||
#define ONESHOT125_TIMER_MHZ 12
|
||||
|
|
|
@ -67,9 +67,9 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
|
@ -105,6 +105,8 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
|
@ -112,7 +114,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -78,6 +78,8 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
|
@ -86,7 +88,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/stack_check.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_msp.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/mw.h"
|
||||
|
@ -69,7 +70,6 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -76,7 +77,6 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -29,11 +29,11 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/mw.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
|
|
|
@ -26,20 +26,20 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/motors.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
/*
|
||||
* Usage:
|
||||
*
|
||||
|
|
|
@ -43,10 +43,9 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#ifdef HIL
|
||||
|
||||
bool hilActive = false;
|
||||
|
|
|
@ -35,6 +35,9 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
|
@ -47,9 +50,6 @@
|
|||
#include "flight/hil.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
/**
|
||||
* In Cleanflight accelerometer is aligned in the following way:
|
||||
|
|
|
@ -41,6 +41,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
@ -51,7 +52,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
|
|
|
@ -43,8 +43,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Compatibility for home position
|
||||
|
|
|
@ -41,8 +41,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/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
|
||||
#define NAV_FW_THROTTLE_SPEED_BOOST_GAIN 1.5f
|
||||
|
|
|
@ -49,8 +49,9 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
||||
|
|
|
@ -38,8 +38,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#if defined(NAV_AUTO_MAG_DECLINATION)
|
||||
/* Declination calculation code from PX4 project */
|
||||
|
|
|
@ -38,6 +38,7 @@
|
|||
|
||||
#include "io/motors.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -48,8 +49,6 @@
|
|||
#include "flight/navigation_rewrite_private.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Altitude controller for multicopter aircraft
|
||||
*-----------------------------------------------------------*/
|
||||
|
|
|
@ -47,8 +47,8 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
#include "flight/navigation_rewrite_private.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
/**
|
||||
* Model-identification based position estimator
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
@ -54,7 +55,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
|
|
|
@ -38,10 +38,10 @@
|
|||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
|
@ -61,7 +62,6 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
|
||||
|
|
|
@ -46,9 +46,9 @@
|
|||
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2000 ms)
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "flight/hil.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#define GPS_I2C_POLL_RATE_HZ 20 // Poll I2C GPS at this rate
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
/* This is a light implementation of a GPS frame decoding
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
//#define GPS_PROTO_UBLOX_NEO7PLUS
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
#include "common/printf.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
@ -71,7 +72,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -41,13 +41,15 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
#include "io/gimbal.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
|
|
@ -1,9 +1,11 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#define PWM_DRIVER_IMPLEMENTATION_COUNT 1
|
||||
|
|
|
@ -24,13 +24,17 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/serial_4way.h"
|
||||
#include "io/serial_4way_impl.h"
|
||||
|
|
|
@ -35,7 +35,6 @@
|
|||
#include "common/printf.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
@ -56,6 +55,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
|
|
@ -27,11 +27,12 @@
|
|||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/pwm.h"
|
||||
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
|
@ -38,6 +37,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
|
|
@ -26,9 +26,10 @@
|
|||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_cx10.h"
|
||||
|
|
|
@ -31,9 +31,9 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
#include "telemetry/telemetry.h"
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro_bma280.h"
|
||||
|
@ -51,6 +49,7 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
|
|
@ -26,9 +26,9 @@
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/compass_ak8963.h"
|
||||
#include "drivers/compass_ak8975.h"
|
||||
|
@ -39,6 +37,7 @@
|
|||
#include "drivers/logging.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
|
|
@ -8,9 +8,9 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/time.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro_bma280.h"
|
||||
|
@ -46,6 +44,7 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
|
|
@ -22,11 +22,11 @@
|
|||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_eeprom.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -25,12 +25,11 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/pitotmeter.h"
|
||||
#include "drivers/pitotmeter_ms4525.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
@ -38,6 +37,7 @@
|
|||
#include "drivers/sonar_srf10.h"
|
||||
#include "drivers/rangefinder.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -19,10 +19,11 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/config_profile.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
// alternative defaults settings for BlueJayF4 targets
|
||||
|
|
|
@ -58,6 +58,7 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -67,7 +68,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -58,6 +58,7 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -67,7 +68,6 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
// !!Temporarily remove blackbox until ROM recovered for NAZE target
|
||||
#undef BLACKBOX
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
|
||||
|
|
|
@ -48,12 +48,13 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
|
|
@ -65,7 +65,7 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
@ -73,11 +73,11 @@
|
|||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/ltm.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX
|
||||
#define LTM_CYCLETIME 100
|
||||
|
||||
|
|
|
@ -67,7 +67,7 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/mavlink.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
@ -39,7 +40,6 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/smartport.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
enum
|
||||
|
|
|
@ -29,11 +29,10 @@
|
|||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue