RC_Channel: return uint32_t for number of ms overrides should live

This commit is contained in:
Peter Barker 2020-01-23 16:07:48 +11:00 committed by Andrew Tridgell
parent ef0b860a48
commit c590aa061f
2 changed files with 30 additions and 5 deletions

View File

@ -359,12 +359,22 @@ void RC_Channel::clear_override()
bool RC_Channel::has_override() const
{
if (override_value <= 0) {
if (override_value == 0) {
return false;
}
const float override_timeout_ms = rc().override_timeout_ms();
return (override_timeout_ms < 0) || (is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms));
uint32_t override_timeout_ms;
if (!rc().get_override_timeout_ms(override_timeout_ms)) {
// timeouts are disabled
return true;
}
if (override_timeout_ms == 0) {
// overrides are explicitly disabled by a zero value
return false;
}
return (AP_HAL::millis() - last_override_time < override_timeout_ms);
}
/*

View File

@ -4,6 +4,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#define NUM_RC_CHANNELS 16
@ -427,8 +428,22 @@ public:
return _options & uint32_t(Option::ARMING_SKIP_CHECK_RPY);
}
float override_timeout_ms() const {
return _override_timeout.get() * 1e3f;
// returns true if overrides should time out. If true is returned
// then returned_timeout_ms will contain the timeout in
// milliseconds, with 0 meaning overrides are disabled.
bool get_override_timeout_ms(uint32_t &returned_timeout_ms) const {
const float value = _override_timeout.get();
if (is_positive(value)) {
returned_timeout_ms = uint32_t(value * 1e3f);
return true;
}
if (is_zero(value)) {
returned_timeout_ms = 0;
return true;
}
// overrides will not time out
return false;
}
// get mask of enabled protocols