5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-02 22:18:28 -04:00

Sub: fixed range check for RC channel

This commit is contained in:
Andrew Tridgell 2019-12-19 17:37:07 +11:00 committed by Peter Barker
parent 0e79044285
commit f42c4e9ce1

View File

@ -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];