AP_L1_Control: change turn_distance() to be min of wp_radius and L1 distance

this gives less surprising behaviour for users
This commit is contained in:
Andrew Tridgell 2013-04-14 18:20:58 +10:00
parent 13e6aaf682
commit 181f7368a3
1 changed files with 1 additions and 1 deletions

View File

@ -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)