mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
fa5de31cb9
commit
ed8feda5b9
@ -134,10 +134,12 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
|
|
||||||
// @Param: FS_TIMEOUT
|
// @Param: FS_TIMEOUT
|
||||||
// @DisplayName: Failsafe 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
|
// @Units: s
|
||||||
|
// @Range: 1 100
|
||||||
|
// @Increment: 0.5
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(fs_timeout, "FS_TIMEOUT", 5),
|
GSCALAR(fs_timeout, "FS_TIMEOUT", 1.5),
|
||||||
|
|
||||||
// @Param: FS_THR_ENABLE
|
// @Param: FS_THR_ENABLE
|
||||||
// @DisplayName: Throttle Failsafe Enable
|
// @DisplayName: Throttle Failsafe Enable
|
||||||
|
@ -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 > 2000) {
|
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 1000) {
|
||||||
failed = true;
|
failed = true;
|
||||||
}
|
}
|
||||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
||||||
|
Loading…
Reference in New Issue
Block a user