mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
failsafe: make sure we clear any RC override in manual failsafe
This commit is contained in:
parent
9892886994
commit
ef3c5c071a
@ -38,6 +38,7 @@ void failsafe_check(uint32_t tnow)
|
||||
if (in_failsafe && tnow - last_timestamp > 20000) {
|
||||
// pass RC inputs to outputs every 20ms
|
||||
last_timestamp = tnow;
|
||||
APM_RC.clearOverride();
|
||||
for (uint8_t ch=0; ch<8; ch++) {
|
||||
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user