mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_SteerController: fix get_steering_out_rate bug when reversing
This commit is contained in:
parent
30852d4713
commit
164096225b
@ -145,7 +145,7 @@ int32_t AP_SteerController::get_steering_out_rate(float desired_rate)
|
||||
// We do this in earth frame to allow for rover leaning over in hard corners
|
||||
float yaw_rate_earth = ToDeg(_ahrs.get_yaw_rate_earth());
|
||||
if (_reverse) {
|
||||
yaw_rate_earth = wrap_180(180 + yaw_rate_earth);
|
||||
yaw_rate_earth *= -1.0f;
|
||||
}
|
||||
float rate_error = (desired_rate - yaw_rate_earth) * scaler;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user