mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 09:16:07 +03:00
BUGFIX - Cleanup failsafe system so it works correctly with Serial RX
systems and Parallel PWM/PPM systems. Added setting for failsafe_max_usec. Renamed failsafe_detect_threshold to failsafe_min_usec. Failsafe now detects when a PPM/PWM RX isn't sending ANY data out on CH1-4. See documentation notes regarding Graupner receivers in Failsafe.md. Documented failsafe system.
This commit is contained in:
parent
d97722be8e
commit
032202ef8f
9 changed files with 174 additions and 46 deletions
|
@ -257,7 +257,8 @@ static void resetConf(void)
|
|||
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_detect_threshold = 985; // any of first 4 channels below this value will trigger failsafe
|
||||
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
|
||||
|
||||
// servos
|
||||
for (i = 0; i < 8; i++) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue