From 380884e175b40d8f8da18abf58e1863b738953d1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 2 Nov 2018 09:16:34 +0900 Subject: [PATCH] Rover: shorten radio/throttle failsafe to 0.2 sec min --- APMrover2/radio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 578d733ea0..6b12127bc6 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -131,7 +131,7 @@ void Rover::radio_failsafe_check(uint16_t pwm) } bool failed = pwm < static_cast(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; } failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);