mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
RC_Channel: make has_new_overrides non-static
This commit is contained in:
parent
2331232bdd
commit
e869eaeda4
@ -338,7 +338,7 @@ void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_us)
|
||||
}
|
||||
last_override_time = timestamp_us != 0 ? timestamp_us : AP_HAL::millis();
|
||||
override_value = v;
|
||||
RC_Channels::has_new_overrides = true;
|
||||
rc().new_override_received();
|
||||
}
|
||||
|
||||
void RC_Channel::clear_override()
|
||||
|
@ -354,12 +354,17 @@ protected:
|
||||
IGNORE_FAILSAFE = (1 << 2), // ignore RC failsafe bits
|
||||
};
|
||||
|
||||
void new_override_received() {
|
||||
has_new_overrides = true;
|
||||
}
|
||||
|
||||
private:
|
||||
static RC_Channels *_singleton;
|
||||
// this static arrangement is to avoid static pointers in AP_Param tables
|
||||
static RC_Channel *channels;
|
||||
|
||||
static bool has_new_overrides;
|
||||
bool has_new_overrides;
|
||||
|
||||
AP_Float _override_timeout;
|
||||
AP_Int32 _options;
|
||||
|
||||
|
@ -28,8 +28,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#include "RC_Channel.h"
|
||||
|
||||
bool RC_Channels::has_new_overrides;
|
||||
|
||||
/*
|
||||
channels group object constructor
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user