Merge branch 'master' of https://github.com/borisbstyle/betaflight into PikoBLX_target_bf

This commit is contained in:
NightHawk32 2016-08-12 06:32:01 -04:00
commit 3a97061a94
28 changed files with 948 additions and 587 deletions

View File

@ -4,7 +4,7 @@ REVISION=$(git rev-parse --short HEAD)
BRANCH=$(git rev-parse --abbrev-ref HEAD) BRANCH=$(git rev-parse --abbrev-ref HEAD)
REVISION=$(git rev-parse --short HEAD) REVISION=$(git rev-parse --short HEAD)
LAST_COMMIT_DATE=$(git log -1 --date=short --format="%cd") LAST_COMMIT_DATE=$(git log -1 --date=short --format="%cd")
TARGET_FILE=obj/cleanflight_${TARGET} TARGET_FILE=obj/betaflight_${TARGET}
TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/undefined} TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/undefined}
BUILDNAME=${BUILDNAME:=travis} BUILDNAME=${BUILDNAME:=travis}
TRAVIS_BUILD_NUMBER=${TRAVIS_BUILD_NUMBER:=undefined} TRAVIS_BUILD_NUMBER=${TRAVIS_BUILD_NUMBER:=undefined}

View File

@ -1,27 +1,52 @@
env: env:
- RUNTESTS=True # - RUNTESTS=True
- PUBLISHMETA=True # - PUBLISHMETA=True
- PUBLISHDOCS=True # - PUBLISHDOCS=True
# - TARGET=AFROMINI
# - TARGET=AIORACERF3
# - TARGET=AIR32
# - TARGET=ALIENFLIGHTF1
- TARGET=ALIENFLIGHTF3
- TARGET=ALIENFLIGHTF4
- TARGET=BLUEJAYF4
- TARGET=CC3D - TARGET=CC3D
- TARGET=CC3D_OPBL - TARGET=CC3D_OPBL
- TARGET=CC3D_BP6 # - TARGET=CHEBUZZF3
- TARGET=CC3D_OPBL_BP6 # - TARGET=CJMCU
- TARGET=COLIBRI_RACE # - TARGET=COLIBRI
- TARGET=LUX_RACE # - TARGET=COLIBRI_RACE
- TARGET=CHEBUZZF3 # - TARGET=DOGE
- TARGET=CJMCU # - TARGET=EUSTM32F103RC
- TARGET=EUSTM32F103RC # - TARGET=F4BY
- TARGET=SPRACINGF3 # - TARGET=FURYF3
- TARGET=FURYF4
# - TARGET=IRCFUSIONF3
# - TARGET=KISSFC
# - TARGET=LUX_RACE
# - TARGET=MICROSCISKY
# - TARGET=MOTOLAB
- TARGET=NAZE - TARGET=NAZE
- TARGET=NAZE32PRO # - TARGET=OLIMEXINO
- TARGET=OLIMEXINO # - TARGET=OMNIBUS
- TARGET=RMDO # - TARGET=OMNIBUSF4
- TARGET=PORT103R # - TARGET=PIKOBLX
# - TARGET=PORT103R
- TARGET=REVO
# - TARGET=REVONANO
# - TARGET=REVO_OPBL
# - TARGET=RMDO
# - TARGET=SINGULARITY
# - TARGET=SIRINFPV
- TARGET=SPARKY - TARGET=SPARKY
# - TARGET=SPARKY2
# - TARGET=SPARKY_OPBL
- TARGET=SPRACINGF3
- TARGET=SPRACINGF3EVO
# - TARGET=SPRACINGF3MINI
- TARGET=STM32F3DISCOVERY - TARGET=STM32F3DISCOVERY
- TARGET=ALIENFLIGHTF1 # - TARGET=VRRACE
- TARGET=ALIENFLIGHTF3 # - TARGET=X_RACERSPI
# - TARGET=ZCOREF3
# use new docker environment # use new docker environment
sudo: false sudo: false
@ -52,7 +77,7 @@ script: ./.travis.sh
cache: apt cache: apt
notifications: #notifications:
irc: "chat.freenode.net#cleanflight" # irc: "chat.freenode.net#cleanflight"
use_notice: true # use_notice: true
skip_join: true # skip_join: true

View File

@ -179,7 +179,6 @@ LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
TARGET_FLAGS = -D$(TARGET)
# End F3 targets # End F3 targets
# #
# Start F4 targets # Start F4 targets
@ -273,7 +272,6 @@ $(error Unknown MCU for F4 target)
endif endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
TARGET_FLAGS = -D$(TARGET)
# End F4 targets # End F4 targets
# #
# Start F1 targets # Start F1 targets
@ -313,7 +311,6 @@ endif
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS)
ifeq ($(DEVICE_FLAGS),) ifeq ($(DEVICE_FLAGS),)
DEVICE_FLAGS = -DSTM32F10X_MD DEVICE_FLAGS = -DSTM32F10X_MD
@ -581,8 +578,10 @@ CFLAGS += $(ARCH_FLAGS) \
-Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
-ffunction-sections \ -ffunction-sections \
-fdata-sections \ -fdata-sections \
-pedantic \
$(DEVICE_FLAGS) \ $(DEVICE_FLAGS) \
-DUSE_STDPERIPH_DRIVER \ -DUSE_STDPERIPH_DRIVER \
-D$(TARGET) \
$(TARGET_FLAGS) \ $(TARGET_FLAGS) \
-D'__FORKNAME__="$(FORKNAME)"' \ -D'__FORKNAME__="$(FORKNAME)"' \
-D'__TARGET__="$(TARGET)"' \ -D'__TARGET__="$(TARGET)"' \

View File

@ -61,11 +61,9 @@ If what you need is not covered then refer to the baseflight documentation. If y
## IRC Support and Developers Channel ## IRC Support and Developers Channel
There's a dedicated IRC channel here: There's a dedicated IRCgitter chat channel here:
irc://irc.freenode.net/#cleanflight https://gitter.im/betaflight/betaflight
If you are using windows and don't have an IRC client installed then take a look at HydraIRC - here: http://hydrairc.com/
Etiquette: Don't ask to ask and please wait around long enough for a reply - sometimes people are out flying, asleep or at work and can't answer immediately. Etiquette: Don't ask to ask and please wait around long enough for a reply - sometimes people are out flying, asleep or at work and can't answer immediately.
@ -79,13 +77,13 @@ Please subscribe and '+1' the videos if you find them useful.
## Configuration Tool ## Configuration Tool
To configure Cleanflight you should use the Cleanflight-configurator GUI tool (Windows/OSX/Linux) that can be found here: To configure Betaflight you should use the Betaflight-configurator GUI tool (Windows/OSX/Linux) that can be found here:
https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb https://chrome.google.com/webstore/detail/betaflight-configurator/kdaghagfopacdngbohiknlhcocjccjao
The source for it is here: The source for it is here:
https://github.com/cleanflight/cleanflight-configurator https://github.com/betaflight/betaflight-configurator
## Contributing ## Contributing
@ -97,10 +95,10 @@ Contributions are welcome and encouraged. You can contribute in many ways:
* New features. * New features.
* Telling us your ideas and suggestions. * Telling us your ideas and suggestions.
The best place to start is the IRC channel on freenode (see above), drop in, say hi. Next place is the github issue tracker: The best place to start is the IRC channel on gitter (see above), drop in, say hi. Next place is the github issue tracker:
https://github.com/cleanflight/cleanflight/issues https://github.com/betaflight/betaflight/issues
https://github.com/cleanflight/cleanflight-configurator/issues https://github.com/betaflight/betaflight-configurator/issues
Before creating new issues please check to see if there is an existing one, search first otherwise you waste peoples time when they could be coding instead! Before creating new issues please check to see if there is an existing one, search first otherwise you waste peoples time when they could be coding instead!
@ -110,11 +108,11 @@ Please refer to the development section in the `docs/development` folder.
TravisCI is used to run automatic builds TravisCI is used to run automatic builds
https://travis-ci.org/cleanflight/cleanflight https://travis-ci.org/betaflight/betaflight
[![Build Status](https://travis-ci.org/cleanflight/cleanflight.svg?branch=master)](https://travis-ci.org/cleanflight/cleanflight) [![Build Status](https://travis-ci.org/betaflight/betaflight.svg?branch=master)](https://travis-ci.org/betaflight/betaflight)
## Cleanflight Releases ## Betaflight Releases
https://github.com/cleanflight/cleanflight/releases https://github.com/betaflight/betaflight/releases

View File

@ -1210,18 +1210,34 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], BLACKBOX_PRINT_HEADER_LINE("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL],
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL],
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]);
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_filter_type);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count);
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.vbatPidCompensation);
BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate);
BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_cutoff * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_cutoff * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("deltaMethod:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.deltaMethod);
BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate);
BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate);
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit);
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count);
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.vbatPidCompensation);
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidAtMinThrottle);
// Betaflight PID controller parameters
BLACKBOX_PRINT_HEADER_LINE("toleranceBand:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.toleranceBand);
BLACKBOX_PRINT_HEADER_LINE("toleranceBandReduction:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.toleranceBandReduction);
BLACKBOX_PRINT_HEADER_LINE("zeroCrossAllowanceCount:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.zeroCrossAllowanceCount);
BLACKBOX_PRINT_HEADER_LINE("itermThrottleGain:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.itermThrottleGain);
BLACKBOX_PRINT_HEADER_LINE("ptermSetpointWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.ptermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawRateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rateAccelLimit);
// End of Betaflight controller parameters
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband); BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband);
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_soft_type:%d", masterConfig.gyro_soft_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d", (int)(masterConfig.gyro_soft_notch_cutoff * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d", (int)(masterConfig.gyro_soft_notch_cutoff * 100.0f));
@ -1237,6 +1253,7 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.use_unsyncedPwm); BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.use_unsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", masterConfig.motor_pwm_protocol); BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", masterConfig.motor_pwm_protocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", masterConfig.motor_pwm_rate); BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", masterConfig.motor_pwm_rate);
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", masterConfig.debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures); BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
default: default:

View File

@ -206,7 +206,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->D8[ROLL] = 20; pidProfile->D8[ROLL] = 20;
pidProfile->P8[PITCH] = 60; pidProfile->P8[PITCH] = 60;
pidProfile->I8[PITCH] = 60; pidProfile->I8[PITCH] = 60;
pidProfile->D8[PITCH] = 25; pidProfile->D8[PITCH] = 22;
pidProfile->P8[YAW] = 80; pidProfile->P8[YAW] = 80;
pidProfile->I8[YAW] = 45; pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20; pidProfile->D8[YAW] = 20;
@ -232,22 +232,22 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 80; pidProfile->yaw_lpf_hz = 80;
pidProfile->rollPitchItermIgnoreRate = 200; pidProfile->rollPitchItermIgnoreRate = 130;
pidProfile->yawItermIgnoreRate = 50; pidProfile->yawItermIgnoreRate = 32;
pidProfile->dterm_filter_type = FILTER_BIQUAD; pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->dterm_notch_hz = 0; pidProfile->dterm_notch_hz = 0;
pidProfile->dterm_notch_cutoff = 150; pidProfile->dterm_notch_cutoff = 150;
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT; pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
pidProfile->vbatPidCompensation = 0; pidProfile->vbatPidCompensation = 0;
pidProfile->zeroThrottleStabilisation = PID_STABILISATION_OFF; pidProfile->pidAtMinThrottle = PID_STABILISATION_OFF;
// Betaflight PID controller parameters // Betaflight PID controller parameters
pidProfile->ptermSetpointWeight = 75; pidProfile->ptermSetpointWeight = 75;
pidProfile->dtermSetpointWeight = 120; pidProfile->dtermSetpointWeight = 120;
pidProfile->yawRateAccelLimit = 220; pidProfile->yawRateAccelLimit = 220;
pidProfile->rateAccelLimit = 0; pidProfile->rateAccelLimit = 0;
pidProfile->toleranceBand = 15; pidProfile->toleranceBand = 0;
pidProfile->toleranceBandReduction = 40; pidProfile->toleranceBandReduction = 40;
pidProfile->zeroCrossAllowanceCount = 2; pidProfile->zeroCrossAllowanceCount = 2;
pidProfile->itermThrottleGain = 0; pidProfile->itermThrottleGain = 0;
@ -273,7 +273,7 @@ void resetProfile(profile_t *profile)
resetControlRateConfig(&profile->controlRateProfile[rI]); resetControlRateConfig(&profile->controlRateProfile[rI]);
} }
profile->activeRateProfile = 0; profile->activeRateProfile = 0;
} }
#ifdef GPS #ifdef GPS
@ -310,11 +310,10 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
{ {
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
escAndServoConfig->minthrottle = 1000; escAndServoConfig->minthrottle = 1000;
escAndServoConfig->maxthrottle = 2000;
#else #else
escAndServoConfig->minthrottle = 1150; escAndServoConfig->minthrottle = 1070;
escAndServoConfig->maxthrottle = 1850;
#endif #endif
escAndServoConfig->maxthrottle = 2000;
escAndServoConfig->mincommand = 1000; escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500; escAndServoConfig->servoCenterPulse = 1500;
} }
@ -440,263 +439,280 @@ uint16_t getCurrentMinthrottle(void)
return masterConfig.escAndServoConfig.minthrottle; return masterConfig.escAndServoConfig.minthrottle;
} }
static void intFeatureClearAll(master_t *config);
static void intFeatureSet(uint32_t mask, master_t *config);
static void intFeatureClear(uint32_t mask, master_t *config);
// Default settings // Default settings
static void resetConf(void) void createDefaultConfig(master_t *config)
{ {
// Clear all configuration // Clear all configuration
memset(&masterConfig, 0, sizeof(master_t)); memset(config, 0, sizeof(master_t));
setProfile(0);
featureClearAll(); intFeatureClearAll(config);
featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES); intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES, config);
#ifdef DEFAULT_FEATURES #ifdef DEFAULT_FEATURES
featureSet(DEFAULT_FEATURES); intFeatureSet(DEFAULT_FEATURES, config);
#endif #endif
#ifdef OSD #ifdef OSD
resetOsdConfig(); intFeatureSet(FEATURE_OSD, config);
resetOsdConfig(&config->osdProfile);
#endif #endif
#ifdef BOARD_HAS_VOLTAGE_DIVIDER #ifdef BOARD_HAS_VOLTAGE_DIVIDER
// only enable the VBAT feature by default if the board has a voltage divider otherwise // only enable the VBAT feature by default if the board has a voltage divider otherwise
// the user may see incorrect readings and unexpected issues with pin mappings may occur. // the user may see incorrect readings and unexpected issues with pin mappings may occur.
featureSet(FEATURE_VBAT); intFeatureSet(FEATURE_VBAT, config);
#endif #endif
config->version = EEPROM_CONF_VERSION;
masterConfig.version = EEPROM_CONF_VERSION; config->mixerMode = MIXER_QUADX;
masterConfig.mixerMode = MIXER_QUADX;
// global settings // global settings
masterConfig.current_profile_index = 0; // default profile config->current_profile_index = 0; // default profile
masterConfig.dcm_kp = 2500; // 1.0 * 10000 config->dcm_kp = 2500; // 1.0 * 10000
masterConfig.dcm_ki = 0; // 0.003 * 10000 config->dcm_ki = 0; // 0.003 * 10000
masterConfig.gyro_lpf = 0; // 256HZ default config->gyro_lpf = 0; // 256HZ default
#ifdef STM32F10X #ifdef STM32F10X
masterConfig.gyro_sync_denom = 8; config->gyro_sync_denom = 8;
masterConfig.pid_process_denom = 1; config->pid_process_denom = 1;
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
masterConfig.gyro_sync_denom = 1; config->gyro_sync_denom = 1;
masterConfig.pid_process_denom = 4; config->pid_process_denom = 4;
#else #else
masterConfig.gyro_sync_denom = 4; config->gyro_sync_denom = 4;
masterConfig.pid_process_denom = 2; config->pid_process_denom = 2;
#endif #endif
masterConfig.gyro_soft_type = FILTER_PT1; config->gyro_soft_type = FILTER_PT1;
masterConfig.gyro_soft_lpf_hz = 90; config->gyro_soft_lpf_hz = 90;
masterConfig.gyro_soft_notch_hz = 0; config->gyro_soft_notch_hz = 0;
masterConfig.gyro_soft_notch_cutoff = 150; config->gyro_soft_notch_cutoff = 150;
masterConfig.debug_mode = DEBUG_NONE; config->debug_mode = DEBUG_NONE;
resetAccelerometerTrims(&masterConfig.accZero); resetAccelerometerTrims(&config->accZero);
resetSensorAlignment(&masterConfig.sensorAlignmentConfig); resetSensorAlignment(&config->sensorAlignmentConfig);
masterConfig.boardAlignment.rollDegrees = 0; config->boardAlignment.rollDegrees = 0;
masterConfig.boardAlignment.pitchDegrees = 0; config->boardAlignment.pitchDegrees = 0;
masterConfig.boardAlignment.yawDegrees = 0; config->boardAlignment.yawDegrees = 0;
masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect config->acc_hardware = ACC_DEFAULT; // default/autodetect
masterConfig.max_angle_inclination = 700; // 70 degrees config->max_angle_inclination = 700; // 70 degrees
masterConfig.yaw_control_direction = 1; config->yaw_control_direction = 1;
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; config->gyroConfig.gyroMovementCalibrationThreshold = 32;
// xxx_hardware: 0:default/autodetect, 1: disable // xxx_hardware: 0:default/autodetect, 1: disable
masterConfig.mag_hardware = 0; config->mag_hardware = 0;
masterConfig.baro_hardware = 0; config->baro_hardware = 0;
resetBatteryConfig(&masterConfig.batteryConfig); resetBatteryConfig(&config->batteryConfig);
#ifdef TELEMETRY #ifdef TELEMETRY
resetTelemetryConfig(&masterConfig.telemetryConfig); resetTelemetryConfig(&config->telemetryConfig);
#endif #endif
#ifdef SERIALRX_PROVIDER #ifdef SERIALRX_PROVIDER
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER; config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else #else
masterConfig.rxConfig.serialrx_provider = 0; config->rxConfig.serialrx_provider = 0;
#endif #endif
masterConfig.rxConfig.sbus_inversion = 1; config->rxConfig.sbus_inversion = 1;
masterConfig.rxConfig.spektrum_sat_bind = 0; config->rxConfig.spektrum_sat_bind = 0;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.rxConfig.midrc = 1500; config->rxConfig.midrc = 1500;
masterConfig.rxConfig.mincheck = 1100; config->rxConfig.mincheck = 1100;
masterConfig.rxConfig.maxcheck = 1900; config->rxConfig.maxcheck = 1900;
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i]; rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc); channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
} }
masterConfig.rxConfig.rssi_channel = 0; config->rxConfig.rssi_channel = 0;
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT; config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
masterConfig.rxConfig.rssi_ppm_invert = 0; config->rxConfig.rssi_ppm_invert = 0;
masterConfig.rxConfig.rcInterpolation = RC_SMOOTHING_AUTO; config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
masterConfig.rxConfig.rcInterpolationInterval = 19; config->rxConfig.rcInterpolationInterval = 19;
masterConfig.rxConfig.fpvCamAngleDegrees = 0; config->rxConfig.fpvCamAngleDegrees = 0;
masterConfig.rxConfig.max_aux_channel = MAX_AUX_CHANNELS; config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
masterConfig.rxConfig.airModeActivateThreshold = 1350; config->rxConfig.airModeActivateThreshold = 1350;
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges); resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; config->inputFilteringMode = INPUT_FILTERING_DISABLED;
masterConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
masterConfig.disarm_kill_switch = 1; config->disarm_kill_switch = 1;
masterConfig.auto_disarm_delay = 5; config->auto_disarm_delay = 5;
masterConfig.small_angle = 25; config->small_angle = 25;
resetMixerConfig(&masterConfig.mixerConfig); resetMixerConfig(&config->mixerConfig);
masterConfig.airplaneConfig.fixedwing_althold_dir = 1; config->airplaneConfig.fixedwing_althold_dir = 1;
// Motor/ESC/Servo // Motor/ESC/Servo
resetEscAndServoConfig(&masterConfig.escAndServoConfig); resetEscAndServoConfig(&config->escAndServoConfig);
resetFlight3DConfig(&masterConfig.flight3DConfig); resetFlight3DConfig(&config->flight3DConfig);
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE; config->motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED; config->motor_pwm_protocol = PWM_TYPE_BRUSHED;
masterConfig.use_unsyncedPwm = true; config->use_unsyncedPwm = true;
#else #else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; config->motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125; config->motor_pwm_protocol = PWM_TYPE_ONESHOT125;
#endif #endif
masterConfig.servo_pwm_rate = 50;
config->servo_pwm_rate = 50;
#ifdef CC3D #ifdef CC3D
masterConfig.use_buzzer_p6 = 0; config->use_buzzer_p6 = 0;
#endif #endif
#ifdef GPS #ifdef GPS
// gps/nav stuff // gps/nav stuff
masterConfig.gpsConfig.provider = GPS_NMEA; config->gpsConfig.provider = GPS_NMEA;
masterConfig.gpsConfig.sbasMode = SBAS_AUTO; config->gpsConfig.sbasMode = SBAS_AUTO;
masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON; config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF; config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
#endif #endif
resetSerialConfig(&masterConfig.serialConfig); resetSerialConfig(&config->serialConfig);
masterConfig.emf_avoidance = 0; // TODO - needs removal config->emf_avoidance = 0; // TODO - needs removal
resetProfile(currentProfile); resetProfile(&config->profile[0]);
resetRollAndPitchTrims(&masterConfig.accelerometerTrims); resetRollAndPitchTrims(&config->accelerometerTrims);
masterConfig.mag_declination = 0; config->mag_declination = 0;
masterConfig.acc_lpf_hz = 10.0f; config->acc_lpf_hz = 10.0f;
masterConfig.accDeadband.xy = 40; config->accDeadband.xy = 40;
masterConfig.accDeadband.z = 40; config->accDeadband.z = 40;
masterConfig.acc_unarmedcal = 1; config->acc_unarmedcal = 1;
#ifdef BARO #ifdef BARO
resetBarometerConfig(&masterConfig.barometerConfig); resetBarometerConfig(&config->barometerConfig);
#endif #endif
// Radio // Radio
#ifdef RX_CHANNELS_TAER #ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", &masterConfig.rxConfig); parseRcChannels("TAER1234", &config->rxConfig);
#else #else
parseRcChannels("AETR1234", &masterConfig.rxConfig); parseRcChannels("AETR1234", &config->rxConfig);
#endif #endif
resetRcControlsConfig(&masterConfig.rcControlsConfig); resetRcControlsConfig(&config->rcControlsConfig);
masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv config->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
masterConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv config->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
// Failsafe Variables // Failsafe Variables
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec config->failsafeConfig.failsafe_delay = 10; // 1sec
masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec config->failsafeConfig.failsafe_off_delay = 10; // 1sec
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off. config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing config->failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
#ifdef USE_SERVOS #ifdef USE_SERVOS
// servos // servos
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN; config->servoConf[i].min = DEFAULT_SERVO_MIN;
masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX; config->servoConf[i].max = DEFAULT_SERVO_MAX;
masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE; config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
masterConfig.servoConf[i].rate = 100; config->servoConf[i].rate = 100;
masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE; config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE; config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED; config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
} }
// gimbal // gimbal
masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL; config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
#endif #endif
#ifdef GPS #ifdef GPS
resetGpsProfile(&masterConfig.gpsProfile); resetGpsProfile(&config->gpsProfile);
#endif #endif
// custom mixer. clear by defaults. // custom mixer. clear by defaults.
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
masterConfig.customMotorMixer[i].throttle = 0.0f; config->customMotorMixer[i].throttle = 0.0f;
} }
#ifdef LED_STRIP #ifdef LED_STRIP
applyDefaultColors(masterConfig.colors); applyDefaultColors(config->colors);
applyDefaultLedStripConfig(masterConfig.ledConfigs); applyDefaultLedStripConfig(config->ledConfigs);
applyDefaultModeColors(masterConfig.modeColors); applyDefaultModeColors(config->modeColors);
applyDefaultSpecialColors(&(masterConfig.specialColors)); applyDefaultSpecialColors(&(config->specialColors));
masterConfig.ledstrip_visual_beeper = 0; config->ledstrip_visual_beeper = 0;
#endif #endif
#ifdef VTX #ifdef VTX
masterConfig.vtx_band = 4; //Fatshark/Airwaves config->vtx_band = 4; //Fatshark/Airwaves
masterConfig.vtx_channel = 1; //CH1 config->vtx_channel = 1; //CH1
masterConfig.vtx_mode = 0; //CH+BAND mode config->vtx_mode = 0; //CH+BAND mode
masterConfig.vtx_mhz = 5740; //F0 config->vtx_mhz = 5740; //F0
#endif #endif
#ifdef TRANSPONDER #ifdef TRANSPONDER
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData)); memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
#endif #endif
#ifdef BLACKBOX #ifdef BLACKBOX
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT) #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
featureSet(FEATURE_BLACKBOX); intFeatureSet(FEATURE_BLACKBOX, config);
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH; config->blackbox_device = BLACKBOX_DEVICE_FLASH;
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT) #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
featureSet(FEATURE_BLACKBOX); intFeatureSet(FEATURE_BLACKBOX, config);
masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD; config->blackbox_device = BLACKBOX_DEVICE_SDCARD;
#else #else
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL; config->blackbox_device = BLACKBOX_DEVICE_SERIAL;
#endif #endif
masterConfig.blackbox_rate_num = 1; config->blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1; config->blackbox_rate_denom = 1;
#endif // BLACKBOX #endif // BLACKBOX
#ifdef SERIALRX_UART #ifdef SERIALRX_UART
if (featureConfigured(FEATURE_RX_SERIAL)) { if (featureConfigured(FEATURE_RX_SERIAL)) {
masterConfig.serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL; config->serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
} }
#endif #endif
#if defined(TARGET_CONFIG) #if defined(TARGET_CONFIG)
targetConfiguration(); // Don't look at target specific config settings when getting default
// values for a CLI diff. This is suboptimal, but it doesn't break the
// public API
if (config == &masterConfig) {
targetConfiguration();
}
#endif #endif
// copy first profile into remaining profile // copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) { for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
} }
}
static void resetConf(void)
{
createDefaultConfig(&masterConfig);
setProfile(0);
#ifdef LED_STRIP
reevaluateLedConfig();
#endif
} }
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length) static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
@ -1067,17 +1083,32 @@ bool feature(uint32_t mask)
void featureSet(uint32_t mask) void featureSet(uint32_t mask)
{ {
masterConfig.enabledFeatures |= mask; intFeatureSet(mask, &masterConfig);
}
static void intFeatureSet(uint32_t mask, master_t *config)
{
config->enabledFeatures |= mask;
} }
void featureClear(uint32_t mask) void featureClear(uint32_t mask)
{ {
masterConfig.enabledFeatures &= ~(mask); intFeatureClear(mask, &masterConfig);
}
static void intFeatureClear(uint32_t mask, master_t *config)
{
config->enabledFeatures &= ~(mask);
} }
void featureClearAll() void featureClearAll()
{ {
masterConfig.enabledFeatures = 0; intFeatureClearAll(&masterConfig);
}
static void intFeatureClearAll(master_t *config)
{
config->enabledFeatures = 0;
} }
uint32_t featureMask(void) uint32_t featureMask(void)

View File

@ -26,7 +26,6 @@
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
#define MAX_NAME_LENGTH 16 #define MAX_NAME_LENGTH 16
typedef enum { typedef enum {
FEATURE_RX_PPM = 1 << 0, FEATURE_RX_PPM = 1 << 0,
FEATURE_VBAT = 1 << 1, FEATURE_VBAT = 1 << 1,

View File

@ -174,3 +174,5 @@ typedef struct master_t {
extern master_t masterConfig; extern master_t masterConfig;
extern profile_t *currentProfile; extern profile_t *currentProfile;
extern controlRateConfig_t *currentControlRateProfile; extern controlRateConfig_t *currentControlRateProfile;
void createDefaultConfig(master_t *config);

View File

@ -115,12 +115,14 @@ void initFilters(const pidProfile_t *pidProfile) {
if (pidProfile->dterm_notch_hz && !dtermNotchInitialised) { if (pidProfile->dterm_notch_hz && !dtermNotchInitialised) {
float notchQ = filterGetNotchQ(pidProfile->dterm_notch_hz, pidProfile->dterm_notch_cutoff); float notchQ = filterGetNotchQ(pidProfile->dterm_notch_hz, pidProfile->dterm_notch_cutoff);
for (axis = 0; axis < 3; axis++) biquadFilterInit(&dtermFilterNotch[axis], pidProfile->dterm_notch_hz, gyro.targetLooptime, notchQ, FILTER_NOTCH); for (axis = 0; axis < 3; axis++) biquadFilterInit(&dtermFilterNotch[axis], pidProfile->dterm_notch_hz, targetPidLooptime, notchQ, FILTER_NOTCH);
dtermNotchInitialised = true;
} }
if (pidProfile->dterm_filter_type == FILTER_BIQUAD) { if (pidProfile->dterm_filter_type == FILTER_BIQUAD) {
if (pidProfile->dterm_lpf_hz && !dtermBiquadLpfInitialised) { if (pidProfile->dterm_lpf_hz && !dtermBiquadLpfInitialised) {
for (axis = 0; axis < 3; axis++) biquadFilterInitLPF(&dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, gyro.targetLooptime); for (axis = 0; axis < 3; axis++) biquadFilterInitLPF(&dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, targetPidLooptime);
dtermBiquadLpfInitialised = true;
} }
} }
} }
@ -272,7 +274,7 @@ static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inc
// -----calculate I component. // -----calculate I component.
// Reduce strong Iterm accumulation during higher stick inputs // Reduce strong Iterm accumulation during higher stick inputs
float accumulationThreshold = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate; float accumulationThreshold = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
float setpointRateScaler = constrainf(1.0f - (1.5f * (ABS(setpointRate[axis]) / accumulationThreshold)), 0.0f, 1.0f); float setpointRateScaler = constrainf(1.0f - (ABS(setpointRate[axis]) / accumulationThreshold), 0.0f, 1.0f);
// Handle All windup Scenarios // Handle All windup Scenarios
// limit maximum integrator value to prevent WindUp // limit maximum integrator value to prevent WindUp

View File

@ -91,7 +91,7 @@ typedef struct pidProfile_s {
uint16_t yaw_p_limit; uint16_t yaw_p_limit;
uint8_t dterm_average_count; // Configurable delta count for dterm uint8_t dterm_average_count; // Configurable delta count for dterm
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
uint8_t zeroThrottleStabilisation; // Disable/Enable zero throttle stabilisation. Normally even without airmode P and D would be active. uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
// Betaflight PID controller parameters // Betaflight PID controller parameters
uint8_t toleranceBand; // Error tolerance area where toleranceBandReduction is applied under certain circumstances uint8_t toleranceBand; // Error tolerance area where toleranceBandReduction is applied under certain circumstances

View File

@ -238,85 +238,6 @@ static const specialColorIndexes_t defaultSpecialColors[] = {
static int scaledThrottle; static int scaledThrottle;
/*
#ifdef USE_LED_RING_DEFAULT_CONFIG
const ledConfig_t defaultLedStripConfig[] = {
{ CALCULATE_LED_XY( 2, 2), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 2, 1), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 2, 0), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 0), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 0, 0), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 0, 1), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 0, 2), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 2), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
};
#elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG)
const ledConfig_t defaultLedStripConfig[] = {
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
};
#else
const ledConfig_t defaultLedStripConfig[] = {
{ CALCULATE_LED_XY(15, 15), 0, LED_DIRECTION_SOUTH | LED_DIRECTION_EAST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
{ CALCULATE_LED_XY(15, 8), 0, LED_DIRECTION_EAST | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY(15, 7), 0, LED_DIRECTION_EAST | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY(15, 0), 0, LED_DIRECTION_NORTH | LED_DIRECTION_EAST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
{ CALCULATE_LED_XY( 8, 0), 0, LED_DIRECTION_NORTH | LED_FUNCTION_FLIGHT_MODE },
{ CALCULATE_LED_XY( 7, 0), 0, LED_DIRECTION_NORTH | LED_FUNCTION_FLIGHT_MODE },
{ CALCULATE_LED_XY( 0, 0), 0, LED_DIRECTION_NORTH | LED_DIRECTION_WEST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
{ CALCULATE_LED_XY( 0, 7), 0, LED_DIRECTION_WEST | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 0, 8), 0, LED_DIRECTION_WEST | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 0, 15), 0, LED_DIRECTION_SOUTH | LED_DIRECTION_WEST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
{ CALCULATE_LED_XY( 7, 15), 0, LED_DIRECTION_SOUTH | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 8, 15), 0, LED_DIRECTION_SOUTH | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 7, 7), 0, LED_DIRECTION_UP | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 8, 7), 0, LED_DIRECTION_UP | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 7, 8), 0, LED_DIRECTION_DOWN | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 8, 8), 0, LED_DIRECTION_DOWN | LED_FUNCTION_FLIGHT_MODE | LED_FUNCTION_WARNING },
{ CALCULATE_LED_XY( 8, 9), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 9, 10), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY(10, 11), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY(10, 12), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 9, 13), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 8, 14), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 7, 14), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 6, 13), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 5, 12), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 5, 11), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 6, 10), 3, LED_FUNCTION_THRUST_RING},
{ CALCULATE_LED_XY( 7, 9), 3, LED_FUNCTION_THRUST_RING},
};
#endif
*/
static void updateLedRingCounts(void); static void updateLedRingCounts(void);
STATIC_UNIT_TESTED void determineLedStripDimensions(void) STATIC_UNIT_TESTED void determineLedStripDimensions(void)
@ -1223,9 +1144,6 @@ void pgResetFn_specialColors(specialColorIndexes_t *instance)
void applyDefaultLedStripConfig(ledConfig_t *ledConfigs) void applyDefaultLedStripConfig(ledConfig_t *ledConfigs)
{ {
memset(ledConfigs, 0, LED_MAX_STRIP_LENGTH * sizeof(ledConfig_t)); memset(ledConfigs, 0, LED_MAX_STRIP_LENGTH * sizeof(ledConfig_t));
memcpy(ledConfigs, &defaultLedStripConfig, sizeof(defaultLedStripConfig));
reevaluateLedConfig();
} }
void applyDefaultColors(hsvColor_t *colors) void applyDefaultColors(hsvColor_t *colors)

View File

@ -831,24 +831,22 @@ void osdInit(void)
max7456_draw_screen(); max7456_draw_screen();
} }
void resetOsdConfig(void) void resetOsdConfig(osd_profile *osdProfile)
{ {
featureSet(FEATURE_OSD); osdProfile->video_system = AUTO;
masterConfig.osdProfile.video_system = AUTO; osdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29; osdProfile->item_pos[OSD_RSSI_VALUE] = -59;
masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59; osdProfile->item_pos[OSD_TIMER] = -39;
masterConfig.osdProfile.item_pos[OSD_TIMER] = -39; osdProfile->item_pos[OSD_THROTTLE_POS] = -9;
masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] = -9; osdProfile->item_pos[OSD_CPU_LOAD] = 26;
masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] = 26; osdProfile->item_pos[OSD_VTX_CHANNEL] = 1;
masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL] = 1; osdProfile->item_pos[OSD_VOLTAGE_WARNING] = -80;
masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] = -80; osdProfile->item_pos[OSD_ARMED] = -107;
masterConfig.osdProfile.item_pos[OSD_ARMED] = -107; osdProfile->item_pos[OSD_DISARMED] = -109;
masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109; osdProfile->item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] = -1; osdProfile->item_pos[OSD_HORIZON_SIDEBARS] = -1;
masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] = -1; osdProfile->item_pos[OSD_CURRENT_DRAW] = -23;
masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW] = -23; osdProfile->item_pos[OSD_MAH_DRAWN] = -18;
masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN] = -18; osdProfile->item_pos[OSD_CRAFT_NAME] = 1;
masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME] = 1;
} }
#endif #endif

View File

@ -65,4 +65,4 @@ typedef struct {
void updateOsd(void); void updateOsd(void);
void osdInit(void); void osdInit(void);
void resetOsdConfig(void); void resetOsdConfig(osd_profile *osdProfile);

File diff suppressed because it is too large Load Diff

View File

@ -536,7 +536,7 @@ void processRx(void)
This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */ This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */
if (throttleStatus == THROTTLE_LOW && !airmodeIsActivated) { if (throttleStatus == THROTTLE_LOW && !airmodeIsActivated) {
pidResetErrorGyroState(); pidResetErrorGyroState();
if (currentProfile->pidProfile.zeroThrottleStabilisation) if (currentProfile->pidProfile.pidAtMinThrottle)
pidStabilisationState(PID_STABILISATION_ON); pidStabilisationState(PID_STABILISATION_ON);
else else
pidStabilisationState(PID_STABILISATION_OFF); pidStabilisationState(PID_STABILISATION_OFF);

View File

@ -20,15 +20,16 @@
// Type of accelerometer used/detected // Type of accelerometer used/detected
typedef enum { typedef enum {
ACC_DEFAULT = 0, ACC_DEFAULT = 0,
ACC_NONE = 1, ACC_NONE,
ACC_ADXL345 = 2, ACC_ADXL345,
ACC_MPU6050 = 3, ACC_MPU6050,
ACC_MMA8452 = 4, ACC_MMA8452,
ACC_BMA280 = 5, ACC_BMA280,
ACC_LSM303DLHC = 6, ACC_LSM303DLHC,
ACC_MPU6000 = 7, ACC_MPU6000,
ACC_MPU6500 = 8, ACC_MPU6500,
ACC_FAKE = 9, ACC_MPU9250,
ACC_FAKE,
ACC_MAX = ACC_FAKE ACC_MAX = ACC_FAKE
} accelerationSensor_e; } accelerationSensor_e;

View File

@ -384,6 +384,20 @@ retry:
} }
#endif #endif
; // fallthrough ; // fallthrough
case ACC_MPU9250:
#ifdef USE_ACC_SPI_MPU9250
if (mpu9250SpiAccDetect(&acc))
{
accHardware = ACC_MPU9250;
#ifdef ACC_MPU9250_ALIGN
accAlign = ACC_MPU9250_ALIGN;
#endif
break;
}
#endif
; // fallthrough
case ACC_FAKE: case ACC_FAKE:
#ifdef USE_FAKE_ACC #ifdef USE_FAKE_ACC
if (fakeAccDetect(&acc)) { if (fakeAccDetect(&acc)) {

View File

@ -77,12 +77,12 @@ void targetConfiguration(void)
masterConfig.motor_pwm_rate = 32000; masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -85,12 +85,12 @@ void targetConfiguration(void) {
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 2; masterConfig.gyro_sync_denom = 2;
masterConfig.pid_process_denom = 1; masterConfig.pid_process_denom = 1;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -85,12 +85,12 @@ void targetConfiguration(void) {
masterConfig.failsafeConfig.failsafe_off_delay = 0; masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 1; masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1; masterConfig.pid_process_denom = 1;
currentProfile->pidProfile.P8[ROLL] = 90; masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
currentProfile->pidProfile.I8[ROLL] = 44; masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
currentProfile->pidProfile.D8[ROLL] = 60; masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
currentProfile->pidProfile.P8[PITCH] = 90; masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
currentProfile->pidProfile.I8[PITCH] = 44; masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
currentProfile->pidProfile.D8[PITCH] = 60; masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -91,7 +91,7 @@
#define VBAT_ADC_PIN PA0 #define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PB0 #define RSSI_ADC_PIN PB0
#define LED_STRIP //#define LED_STRIP
#define WS2811_PIN PB4 #define WS2811_PIN PB4
#define WS2811_TIMER TIM3 #define WS2811_TIMER TIM3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
@ -103,20 +103,20 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SONAR //#define SONAR
#define SONAR_ECHO_PIN PB0 //#define SONAR_ECHO_PIN PB0
#define SONAR_TRIGGER_PIN PB5 //#define SONAR_TRIGGER_PIN PB5
#undef GPS #undef GPS
#ifdef CC3D_OPBL #ifdef CC3D_OPBL
//#undef LED_STRIP #undef LED_STRIP
#define SKIP_CLI_COMMAND_HELP #define SKIP_CLI_COMMAND_HELP
#define SKIP_PID_FLOAT #define SKIP_PID_FLOAT
#undef BARO #undef BARO
#undef MAG #undef MAG
#undef SONAR #undef SONAR
#undef LED_STRIP #undef USE_SOFTSERIAL1
#endif #endif
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View File

@ -113,7 +113,6 @@
#define EXTERNAL1_ADC_PIN PC3 #define EXTERNAL1_ADC_PIN PC3
#define LED_STRIP #define LED_STRIP
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
#define WS2811_PIN PA6 // TIM16_CH1 #define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_TIMER TIM16 #define WS2811_TIMER TIM16

View File

@ -0,0 +1,86 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for FURYF4 targets
void targetConfiguration(void) {
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1;
}

View File

@ -18,6 +18,8 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "FYF4" #define TARGET_BOARD_IDENTIFIER "FYF4"
#define TARGET_CONFIG
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "FuryF4" #define USBD_PRODUCT_STRING "FuryF4"
@ -36,6 +38,7 @@
#define MPU_INT_EXTI PC4 #define MPU_INT_EXTI PC4
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled)
#define USE_MPU_DATA_READY_SIGNAL #define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define MPU6000_CS_PIN PA4 #define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1 #define MPU6000_SPI_INSTANCE SPI1
@ -43,15 +46,18 @@
#define MPU6500_CS_PIN PA4 #define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1 #define MPU6500_SPI_INSTANCE SPI1
#define GYRO
#define USE_GYRO_SPI_MPU6000 #define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG #define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define USE_GYRO_MPU6500 #define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500 #define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG #define GYRO_MPU6500_ALIGN CW180_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define USE_ACC_MPU6500 #define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500 #define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG #define ACC_MPU6500_ALIGN CW180_DEG
@ -68,17 +74,6 @@
#define SDCARD_SPI_INSTANCE SPI2 #define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12 #define SDCARD_SPI_CS_PIN PB12
/*
#define SDCARD_DETECT_PIN PD2
#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD
#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PB3
*/
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: // SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz #define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation: // Divide to under 25MHz for normal operation:
@ -95,7 +90,6 @@
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0 #define SDCARD_DMA_CHANNEL DMA_Channel_0
#define USE_FLASHFS #define USE_FLASHFS
#define USE_FLASH_M25P16 #define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3 #define M25P16_CS_PIN PB3
@ -110,7 +104,6 @@
#define USE_UART1 #define USE_UART1
#define UART1_RX_PIN PA10 #define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9 #define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3 #define USE_UART3
#define UART3_RX_PIN PB11 #define UART3_RX_PIN PB11

View File

@ -21,6 +21,7 @@
#define USE_CLI #define USE_CLI
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define TARGET_CONFIG
#define LED0 PB5 // Blue LEDs - PB5 #define LED0 PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9 //#define LED1 PB9 // Green LEDs - PB9

View File

@ -110,7 +110,7 @@
#define SONAR_TRIGGER_PIN_PWM PB8 #define SONAR_TRIGGER_PIN_PWM PB8
#define SONAR_ECHO_PIN_PWM PB9 #define SONAR_ECHO_PIN_PWM PB9
#define DISPLAY //#define DISPLAY
#define USE_UART1 #define USE_UART1
#define USE_UART2 #define USE_UART2

View File

@ -81,13 +81,13 @@
#define USE_FLASHTOOLS #define USE_FLASHTOOLS
#define USE_FLASH_M25P16 #define USE_FLASH_M25P16
#define SONAR //#define SONAR
#define SONAR_TRIGGER_PIN PB0 #define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1 #define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN_PWM PB8 #define SONAR_TRIGGER_PIN_PWM PB8
#define SONAR_ECHO_PIN_PWM PB9 #define SONAR_ECHO_PIN_PWM PB9
#define DISPLAY //#define DISPLAY
#define USE_UART1 #define USE_UART1
#define USE_UART2 #define USE_UART2
@ -115,6 +115,12 @@
#define RSSI_ADC_PIN PA1 #define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5 #define EXTERNAL1_ADC_PIN PA5
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM3
#define SKIP_CLI_COMMAND_HELP
#define SKIP_PID_LUXFLOAT
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f103RCT6 in 64pin package // IO - stm32f103RCT6 in 64pin package

View File

@ -77,18 +77,18 @@
#define USE_VCP #define USE_VCP
#define VBUS_SENSING_PIN PA8 #define VBUS_SENSING_PIN PA8
#define USE_USART1 #define USE_UART1
#define USART1_RX_PIN PA10 #define UART1_RX_PIN PA10
#define USART1_TX_PIN PA9 #define UART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART3 #define USE_UART3
#define USART3_RX_PIN PB11 #define UART3_RX_PIN PB11
#define USART3_TX_PIN PB10 #define UART3_TX_PIN PB10
#define USE_USART6 #define USE_UART6
#define USART6_RX_PIN PC7 #define UART6_RX_PIN PC7
#define USART6_TX_PIN PC6 //inverter #define UART6_TX_PIN PC6 //inverter
#define SERIAL_PORT_COUNT 4 #define SERIAL_PORT_COUNT 4