mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Default failsafe enabled and throttle off when no valid PPM signal is seen for 1 second #488
This commit is contained in:
parent
2a73ad6925
commit
d24d4699db
1 changed files with 2 additions and 1 deletions
|
@ -344,6 +344,7 @@ static void resetConf(void)
|
|||
featureSet(FEATURE_RX_PPM);
|
||||
#endif
|
||||
featureSet(FEATURE_VBAT);
|
||||
featureSet(FEATURE_FAILSAFE);
|
||||
|
||||
// global settings
|
||||
masterConfig.current_profile_index = 0; // default profile
|
||||
|
@ -441,7 +442,7 @@ static void resetConf(void)
|
|||
// Failsafe Variables
|
||||
currentProfile->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
currentProfile->failsafeConfig.failsafe_off_delay = 200; // 20sec
|
||||
currentProfile->failsafeConfig.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people.
|
||||
currentProfile->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||
currentProfile->failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe
|
||||
currentProfile->failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue