mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_WheelEncoder: Fix AP_WheelRateControl::get_pid() always returning the
first pid CID: 318644
This commit is contained in:
parent
b38200a960
commit
b5caea19da
@ -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…
Reference in New Issue
Block a user