diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 51d728c319..974b9df882 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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 diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index e86b46680e..dc616b33f2 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -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