mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
RC_Channel: removed global rc_ch[] array
hide it as a object static instead
This commit is contained in:
parent
213eaa8db6
commit
0438952a8b
@ -24,7 +24,7 @@ extern const AP_HAL::HAL& hal;
|
||||
/// global array with pointers to all APM RC channels, will be used by AP_Mount
|
||||
/// and AP_Camera classes / It points to RC input channels, both APM1 and APM2
|
||||
/// only have 8 input channels.
|
||||
RC_Channel* rc_ch[NUM_CHANNELS];
|
||||
RC_Channel *RC_Channel::rc_ch[NUM_CHANNELS];
|
||||
|
||||
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
||||
// @Param: MIN
|
||||
|
@ -30,6 +30,7 @@ public:
|
||||
_high(1),
|
||||
_ch_out(ch_out) {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
rc_ch[ch_out] = this;
|
||||
}
|
||||
|
||||
// setup min and max radio values in CLI
|
||||
@ -100,6 +101,8 @@ public:
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
static RC_Channel *rc_channel(uint8_t i) { return rc_ch[i]; }
|
||||
|
||||
private:
|
||||
AP_Int8 _reverse;
|
||||
AP_Int16 _dead_zone;
|
||||
@ -109,6 +112,8 @@ private:
|
||||
int16_t _high_out;
|
||||
int16_t _low_out;
|
||||
uint8_t _ch_out;
|
||||
|
||||
static RC_Channel *rc_ch[8];
|
||||
};
|
||||
|
||||
// This is ugly, but it fixes poorly architected library
|
||||
|
Loading…
Reference in New Issue
Block a user