From 82aba6fe56ba143f5600b6a470e5805c1a562a41 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 7 Jul 2018 16:38:16 +0900 Subject: [PATCH] Rover: guided heading-and-speed control slows using yaw error --- APMrover2/mode_guided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index f65e124e90..335e422d06 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -47,7 +47,7 @@ void ModeGuided::update() if (have_attitude_target) { // run steering and throttle controllers calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0); - calc_throttle(_desired_speed, true, true); + calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true, true); } else { stop_vehicle(); }