From ed8feda5b91108c299c19838f475261bf40e3ca6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 31 Oct 2018 14:29:10 +0900 Subject: [PATCH] Rover: shorten failsafe timeouts radio failsafes may trigger within 1sec (previously was 2 seconds) default failsafe set to 1.5sec (was 5sec) also minor improvement to FS_TIMEOUT parameter description --- APMrover2/Parameters.cpp | 6 ++++-- APMrover2/radio.cpp | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 9ba18d6c55..0bef8fd54d 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -134,10 +134,12 @@ const AP_Param::Info Rover::var_info[] = { // @Param: FS_TIMEOUT // @DisplayName: Failsafe timeout - // @Description: How long a failsafe event need to happen for before we trigger the failsafe action + // @Description: The time in seconds that a failsafe condition must persist before the failsafe action is triggered // @Units: s + // @Range: 1 100 + // @Increment: 0.5 // @User: Standard - GSCALAR(fs_timeout, "FS_TIMEOUT", 5), + GSCALAR(fs_timeout, "FS_TIMEOUT", 1.5), // @Param: FS_THR_ENABLE // @DisplayName: Throttle Failsafe Enable diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index dda0b0a8c2..578d733ea0 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 > 2000) { + if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 1000) { failed = true; } failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);