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
This commit is contained in:
Randy Mackay 2018-10-31 14:29:10 +09:00
parent fa5de31cb9
commit ed8feda5b9
2 changed files with 5 additions and 3 deletions

View File

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

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