1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 17:25:20 +03:00

Add failsafe_procedure

This commit is contained in:
borisbstyle 2016-02-09 12:06:00 +01:00
parent b745d9e480
commit 99d9d7483f
5 changed files with 27 additions and 9 deletions

View file

@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
static const uint8_t EEPROM_CONF_VERSION = 121;
static const uint8_t EEPROM_CONF_VERSION = 122;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{
@ -514,6 +514,7 @@ static void resetConf(void)
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
masterConfig.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
masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
#ifdef USE_SERVOS
// servos