Browse Source

AP_WheelEncoder: Fix AP_WheelRateControl::get_pid() always returning the

first pid

CID: 318644
master
Michael du Breuil 6 years ago committed by Randy Mackay
parent
commit
b5caea19da
  1. 2
      libraries/AP_WheelEncoder/AP_WheelRateControl.cpp

2
libraries/AP_WheelEncoder/AP_WheelRateControl.cpp

@ -183,6 +183,6 @@ AC_PID& AP_WheelRateControl::get_pid(uint8_t instance) @@ -183,6 +183,6 @@ AC_PID& AP_WheelRateControl::get_pid(uint8_t instance)
if (instance == 0) {
return _rate_pid0;
} else {
return _rate_pid0;
return _rate_pid1;
}
}

Loading…
Cancel
Save