mirror of https://github.com/ArduPilot/ardupilot
Rover: increase RC timeout failsafe from 200ms to 500ms.
- this allows for a smoother MAVLink_RC_Override over nasty lossy links
This commit is contained in:
parent
9ebe5d7de9
commit
b3c5971538
|
@ -125,7 +125,7 @@ void Rover::radio_failsafe_check(uint16_t pwm)
|
|||
}
|
||||
|
||||
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
|
||||
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 200) {
|
||||
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 500) {
|
||||
failed = true;
|
||||
}
|
||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
||||
|
|
Loading…
Reference in New Issue