RC_Channel: prevent overwrite of memory on high RC_Channel constructor

This commit is contained in:
Andrew Tridgell 2013-08-18 11:37:42 +10:00
parent b16e3e4c85
commit a12991923e
2 changed files with 16 additions and 5 deletions

View File

@ -20,11 +20,10 @@ extern const AP_HAL::HAL& hal;
#include "RC_Channel.h" #include "RC_Channel.h"
#define NUM_CHANNELS 8
/// global array with pointers to all APM RC channels, will be used by AP_Mount /// 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 /// and AP_Camera classes / It points to RC input channels, both APM1 and APM2
/// only have 8 input channels. /// only have 8 input channels.
RC_Channel *RC_Channel::rc_ch[NUM_CHANNELS]; RC_Channel *RC_Channel::rc_ch[RC_MAX_CHANNELS];
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
// @Param: MIN // @Param: MIN
@ -370,3 +369,11 @@ RC_Channel::enable_out()
{ {
hal.rcout->enable_ch(_ch_out); hal.rcout->enable_ch(_ch_out);
} }
RC_Channel *RC_Channel::rc_channel(uint8_t i)
{
if (i >= RC_MAX_CHANNELS) {
return NULL;
}
return rc_ch[i];
}

View File

@ -17,6 +17,8 @@
#define RC_CHANNEL_TYPE_RANGE 1 #define RC_CHANNEL_TYPE_RANGE 1
#define RC_CHANNEL_TYPE_ANGLE_RAW 2 #define RC_CHANNEL_TYPE_ANGLE_RAW 2
#define RC_MAX_CHANNELS 14
/// @class RC_Channel /// @class RC_Channel
/// @brief Object managing one RC channel /// @brief Object managing one RC channel
class RC_Channel { class RC_Channel {
@ -30,7 +32,9 @@ public:
_high(1), _high(1),
_ch_out(ch_out) { _ch_out(ch_out) {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
rc_ch[ch_out] = this; if (ch_out < RC_MAX_CHANNELS) {
rc_ch[ch_out] = this;
}
} }
// setup min and max radio values in CLI // setup min and max radio values in CLI
@ -103,7 +107,7 @@ public:
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
static RC_Channel *rc_channel(uint8_t i) { return rc_ch[i]; } static RC_Channel *rc_channel(uint8_t i);
private: private:
AP_Int8 _reverse; AP_Int8 _reverse;
@ -115,7 +119,7 @@ private:
int16_t _low_out; int16_t _low_out;
uint8_t _ch_out; uint8_t _ch_out;
static RC_Channel *rc_ch[8]; static RC_Channel *rc_ch[RC_MAX_CHANNELS];
}; };
// This is ugly, but it fixes poorly architected library // This is ugly, but it fixes poorly architected library