From 444e64a3d0f95008d5bc15c8d699bce700abc8af Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 21 May 2018 20:38:31 +0900 Subject: [PATCH] Rover: slow before pivot turns --- APMrover2/mode.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 3b9a205dec..2b12110e36 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -148,6 +148,9 @@ void Mode::set_desired_location(const struct Location& destination, float next_l if (is_zero(turn_angle_cd)) { // if not turning can continue at full speed _desired_speed_final = _desired_speed; + } else if (rover.use_pivot_steering(turn_angle_cd)) { + // pivoting so we will stop + _desired_speed_final = 0.0f; } else { // calculate maximum speed that keeps overshoot within bounds const float radius_m = fabsf(g.waypoint_overshoot / (cosf(radians(turn_angle_cd * 0.01f)) - 1.0f));