mirror of https://github.com/ArduPilot/ardupilot
Tracker: fixed range check for RC channel
This commit is contained in:
parent
d1bbe4f03b
commit
69ea4882d2
|
@ -19,7 +19,7 @@ public:
|
||||||
|
|
||||||
RC_Channel_Tracker obj_channels[NUM_RC_CHANNELS];
|
RC_Channel_Tracker obj_channels[NUM_RC_CHANNELS];
|
||||||
RC_Channel_Tracker *channel(const uint8_t chan) override {
|
RC_Channel_Tracker *channel(const uint8_t chan) override {
|
||||||
if (chan > NUM_RC_CHANNELS) {
|
if (chan >= NUM_RC_CHANNELS) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return &obj_channels[chan];
|
return &obj_channels[chan];
|
||||||
|
|
Loading…
Reference in New Issue