mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: Allow a RC_OVERRIDE_TIMEOUT of -1 to use the overrides
forever
This commit is contained in:
parent
83ed210869
commit
e1b69a7534
|
@ -327,7 +327,9 @@ void RC_Channel::clear_override()
|
|||
|
||||
bool RC_Channel::has_override() const
|
||||
{
|
||||
return (override_value > 0) && ((AP_HAL::millis() - last_override_time) < *RC_Channels::override_timeout * 1000);
|
||||
int32_t override_timeout = (int32_t)(*RC_Channels::override_timeout);
|
||||
return (override_value > 0) && ((override_timeout < 0) ||
|
||||
((AP_HAL::millis() - last_override_time) < (uint32_t)(override_timeout * 1000)));
|
||||
}
|
||||
|
||||
bool RC_Channel::min_max_configured() const
|
||||
|
|
|
@ -99,7 +99,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
|||
|
||||
// @Param: _OVERRIDE_TIME
|
||||
// @DisplayName: RC override timeout
|
||||
// @Description: Timeout after which RC overrides will no longer be used, and RC input will resume, 0 will disable RC overrides
|
||||
// @Description: Timeout after which RC overrides will no longer be used, and RC input will resume, 0 will disable RC overrides, -1 will never timeout, and continue using overrides until they are disabled
|
||||
// @User: Advanced
|
||||
// @Range: 0.0 120.0
|
||||
// @Units: s
|
||||
|
|
Loading…
Reference in New Issue