mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: fix use-pivot-steering
absolute yaw error should be used
This commit is contained in:
parent
fb944322c7
commit
fb9f695d2f
@ -12,7 +12,7 @@ bool Rover::use_pivot_steering(float yaw_error_cd)
|
||||
}
|
||||
|
||||
// calc bearing error
|
||||
const float yaw_error = yaw_error_cd / 100.0f;
|
||||
const float yaw_error = fabsf(yaw_error_cd) * 0.01f;
|
||||
|
||||
// if error is larger than pivot_turn_angle start pivot steering
|
||||
if (yaw_error > g.pivot_turn_angle) {
|
||||
|
Loading…
Reference in New Issue
Block a user