mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: don't do failsafe if throttle is below failsafe level
This commit is contained in:
parent
09ca9d4283
commit
ef4198bcb4
@ -35,7 +35,8 @@ void failsafe_check(uint32_t tnow)
|
||||
in_failsafe = true;
|
||||
}
|
||||
|
||||
if (in_failsafe && tnow - last_timestamp > 20000) {
|
||||
if (in_failsafe && tnow - last_timestamp > 20000 &&
|
||||
hal.rcin->read(CH_3) >= (uint16_t)g.fs_throttle_value) {
|
||||
// pass RC inputs to outputs every 20ms
|
||||
last_timestamp = tnow;
|
||||
hal.rcin->clear_overrides();
|
||||
|
Loading…
Reference in New Issue
Block a user