mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_WheelEncoder: correct check for wheelencoder-max-instances
This commit is contained in:
parent
21201b8816
commit
a09154c45b
@ -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
|
||||
// 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…
Reference in New Issue
Block a user