From fc0d703b9b551ceab2d86e0fb1b6d3767170079e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <tridge@samba.org> Date: Sun, 18 May 2014 21:15:07 +1000 Subject: [PATCH] Rover: much simpler SPEED_TURN_GAIN implementation as soon as we hit the SPEED_TURN_DIST we lower target speed to the specified gain --- APMrover2/Steering.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/Steering.pde b/APMrover2/Steering.pde index 0883dc27b..ccbb69bbb 100644 --- a/APMrover2/Steering.pde +++ b/APMrover2/Steering.pde @@ -109,7 +109,7 @@ static void calc_throttle(float target_speed) if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) { // in auto-modes we reduce speed when approaching waypoints - float reduction2 = 1.0 - speed_turn_reduction*((g.speed_turn_dist - wp_distance)/g.speed_turn_dist); + float reduction2 = 1.0 - speed_turn_reduction; if (reduction2 < reduction) { reduction = reduction2; } -- GitLab