From fb9f695d2f04642c28c2cdb596ea33d54e34d607 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 25 Oct 2017 15:41:47 +0900 Subject: [PATCH] Rover: fix use-pivot-steering absolute yaw error should be used --- APMrover2/Steering.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/Steering.cpp b/APMrover2/Steering.cpp index e1694ee818..247fa30163 100644 --- a/APMrover2/Steering.cpp +++ b/APMrover2/Steering.cpp @@ -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) {