Rover: shorten radio/throttle failsafe to 0.2 sec min

This commit is contained in:
Randy Mackay 2018-11-02 09:16:34 +09:00
parent 2408538bdf
commit 380884e175

View File

@ -131,7 +131,7 @@ void Rover::radio_failsafe_check(uint16_t pwm)
} }
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value); bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 1000) { if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 200) {
failed = true; failed = true;
} }
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed); failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);