RC_Channel: remove old members objects
This commit is contained in:
parent
dab93750a0
commit
ff36eb3aca
@ -327,7 +327,6 @@ private:
|
|||||||
static bool has_new_overrides;
|
static bool has_new_overrides;
|
||||||
static AP_Float *override_timeout;
|
static AP_Float *override_timeout;
|
||||||
static AP_Int32 *options;
|
static AP_Int32 *options;
|
||||||
RC_Channel obj_channels[NUM_RC_CHANNELS];
|
|
||||||
AP_Float _override_timeout;
|
AP_Float _override_timeout;
|
||||||
AP_Int32 _options;
|
AP_Int32 _options;
|
||||||
|
|
||||||
|
@ -28,7 +28,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#include "RC_Channel.h"
|
#include "RC_Channel.h"
|
||||||
|
|
||||||
RC_Channel *RC_Channels::channels;
|
|
||||||
bool RC_Channels::has_new_overrides;
|
bool RC_Channels::has_new_overrides;
|
||||||
AP_Float *RC_Channels::override_timeout;
|
AP_Float *RC_Channels::override_timeout;
|
||||||
AP_Int32 *RC_Channels::options;
|
AP_Int32 *RC_Channels::options;
|
||||||
@ -38,8 +37,6 @@ AP_Int32 *RC_Channels::options;
|
|||||||
*/
|
*/
|
||||||
RC_Channels::RC_Channels(void)
|
RC_Channels::RC_Channels(void)
|
||||||
{
|
{
|
||||||
channels = obj_channels;
|
|
||||||
|
|
||||||
override_timeout = &_override_timeout;
|
override_timeout = &_override_timeout;
|
||||||
options = &_options;
|
options = &_options;
|
||||||
|
|
||||||
@ -106,8 +103,9 @@ int16_t RC_Channels::get_receiver_rssi(void)
|
|||||||
|
|
||||||
void RC_Channels::clear_overrides(void)
|
void RC_Channels::clear_overrides(void)
|
||||||
{
|
{
|
||||||
|
RC_Channels &_rc = rc();
|
||||||
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
||||||
channels[i].clear_override();
|
_rc.channel(i)->clear_override();
|
||||||
}
|
}
|
||||||
// we really should set has_new_overrides to true, and rerun read_input from
|
// we really should set has_new_overrides to true, and rerun read_input from
|
||||||
// the vehicle code however doing so currently breaks the failsafe system on
|
// the vehicle code however doing so currently breaks the failsafe system on
|
||||||
@ -116,16 +114,18 @@ void RC_Channels::clear_overrides(void)
|
|||||||
|
|
||||||
void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms)
|
void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms)
|
||||||
{
|
{
|
||||||
|
RC_Channels &_rc = rc();
|
||||||
if (chan < NUM_RC_CHANNELS) {
|
if (chan < NUM_RC_CHANNELS) {
|
||||||
channels[chan].set_override(value, timestamp_ms);
|
_rc.channel(chan)->set_override(value, timestamp_ms);
|
||||||
has_new_overrides = true;
|
has_new_overrides = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool RC_Channels::has_active_overrides()
|
bool RC_Channels::has_active_overrides()
|
||||||
{
|
{
|
||||||
|
RC_Channels &_rc = rc();
|
||||||
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
||||||
if (channels[i].has_override()) {
|
if (_rc.channel(i)->has_override()) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user