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

first pid

CID: 318644
This commit is contained in:
Michael du Breuil 2018-11-05 15:14:27 -07:00 committed by Randy Mackay
parent b38200a960
commit b5caea19da

View File

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