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:
Tom Pittenger 2019-04-25 18:19:38 -07:00 committed by Randy Mackay
parent 9ebe5d7de9
commit b3c5971538
1 changed files with 1 additions and 1 deletions

View File

@ -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);