AP_WheelEncoder: correct check for wheelencoder-max-instances

This commit is contained in:
Peter Barker 2018-08-06 13:13:32 +10:00 committed by Randy Mackay
parent 21201b8816
commit a09154c45b

View File

@ -28,7 +28,7 @@ AP_WheelEncoder_Backend::AP_WheelEncoder_Backend(AP_WheelEncoder &frontend, uint
// return pin. returns -1 if pin is not defined for this instance // return pin. returns -1 if pin is not defined for this instance
int8_t AP_WheelEncoder_Backend::get_pin_a() const int8_t AP_WheelEncoder_Backend::get_pin_a() const
{ {
if (_state.instance > 1) { if (_state.instance >= WHEELENCODER_MAX_INSTANCES) {
return -1; return -1;
} }
return _frontend._pina[_state.instance].get(); return _frontend._pina[_state.instance].get();
@ -37,7 +37,7 @@ int8_t AP_WheelEncoder_Backend::get_pin_a() const
// return pin. returns -1 if pin is not defined for this instance // return pin. returns -1 if pin is not defined for this instance
int8_t AP_WheelEncoder_Backend::get_pin_b() const int8_t AP_WheelEncoder_Backend::get_pin_b() const
{ {
if (_state.instance > 1) { if (_state.instance >= WHEELENCODER_MAX_INSTANCES) {
return -1; return -1;
} }
return _frontend._pinb[_state.instance].get(); return _frontend._pinb[_state.instance].get();