From 181f7368a327d0567257e3e5933529eb7f1538fe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 14 Apr 2013 18:20:58 +1000 Subject: [PATCH] AP_L1_Control: change turn_distance() to be min of wp_radius and L1 distance this gives less surprising behaviour for users --- libraries/AP_L1_Control/AP_L1_Control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 6b7429869a..9cacd18a12 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -59,7 +59,7 @@ int32_t AP_L1_Control::target_bearing_cd(void) float AP_L1_Control::turn_distance(float wp_radius) { - return max(wp_radius, _L1_dist); + return min(wp_radius, _L1_dist); } bool AP_L1_Control::reached_loiter_target(void)