Browse Source

AP_WheelEncoder: correct check for wheelencoder-max-instances

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
a09154c45b
  1. 4
      libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp

4
libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp

@ -28,7 +28,7 @@ AP_WheelEncoder_Backend::AP_WheelEncoder_Backend(AP_WheelEncoder &frontend, uint @@ -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
int8_t AP_WheelEncoder_Backend::get_pin_a() const
{
if (_state.instance > 1) {
if (_state.instance >= WHEELENCODER_MAX_INSTANCES) {
return -1;
}
return _frontend._pina[_state.instance].get();
@ -37,7 +37,7 @@ int8_t AP_WheelEncoder_Backend::get_pin_a() const @@ -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
int8_t AP_WheelEncoder_Backend::get_pin_b() const
{
if (_state.instance > 1) {
if (_state.instance >= WHEELENCODER_MAX_INSTANCES) {
return -1;
}
return _frontend._pinb[_state.instance].get();

Loading…
Cancel
Save