RC_Channel: remove static override_timeout

This commit is contained in:
Peter Barker 2019-03-29 21:45:49 +11:00 committed by Andrew Tridgell
parent 807c673b4f
commit 2331232bdd
3 changed files with 5 additions and 5 deletions

View File

@ -353,7 +353,7 @@ bool RC_Channel::has_override() const
return false;
}
const float override_timeout_ms = RC_Channels::override_timeout->get() * 1e3f;
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);
}

View File

@ -342,6 +342,10 @@ public:
return _options & uint32_t(Option::IGNORE_RECEIVER);
}
float override_timeout_ms() const {
return _override_timeout.get() * 1e3f;
}
protected:
enum class Option {
@ -356,7 +360,6 @@ private:
static RC_Channel *channels;
static bool has_new_overrides;
static AP_Float *override_timeout;
AP_Float _override_timeout;
AP_Int32 _options;

View File

@ -29,15 +29,12 @@ extern const AP_HAL::HAL& hal;
#include "RC_Channel.h"
bool RC_Channels::has_new_overrides;
AP_Float *RC_Channels::override_timeout;
/*
channels group object constructor
*/
RC_Channels::RC_Channels(void)
{
override_timeout = &_override_timeout;
// set defaults from the parameter table
AP_Param::setup_object_defaults(this, var_info);