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