mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Sub: fixed range check for RC channel
This commit is contained in:
parent
bf39e1dfdd
commit
6388372f04
@ -19,7 +19,7 @@ public:
|
||||
|
||||
RC_Channel_Sub obj_channels[NUM_RC_CHANNELS];
|
||||
RC_Channel_Sub *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
Block a user