RC_Channel: Fix accidental quantization of override_timeout to 1 second

This commit is contained in:
Michael du Breuil 2018-08-27 13:03:09 -07:00 committed by Peter Barker
parent 9d4ce91406
commit 80597d5cba
1 changed files with 6 additions and 3 deletions

View File

@ -336,9 +336,12 @@ void RC_Channel::clear_override()
bool RC_Channel::has_override() const
{
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)));
if (override_value <= 0) {
return false;
}
const float override_timeout_ms = RC_Channels::override_timeout->get() * 1e3f;
return is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms);
}
//