RC_Channel: fix handling of rc_override_time of -1

This commit is contained in:
Rob Ratcliff 2020-01-22 10:00:02 -06:00 committed by Randy Mackay
parent 2f6d655ff0
commit 5c388507d4

View File

@ -359,7 +359,7 @@ bool RC_Channel::has_override() const
}
const float override_timeout_ms = rc().override_timeout_ms();
return is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms);
return (override_timeout_ms < 0) || (is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms));
}
/*