From 01a8cec3482eac96bcda06db4d3f4f89f2f2db93 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sat, 16 Jul 2011 22:02:47 +0000 Subject: [PATCH] tweaked WP speed so long distances wont blow up equation. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2871 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/navigation.pde | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopterMega/navigation.pde b/ArduCopterMega/navigation.pde index 5e84db1087..6d2d39f410 100644 --- a/ArduCopterMega/navigation.pde +++ b/ArduCopterMega/navigation.pde @@ -149,8 +149,9 @@ void calc_rate_nav() // Reduce speed on RTL //if(control_mode == RTL){ - waypoint_speed = min((wp_distance * 100), g.waypoint_speed_max.get()); - waypoint_speed = max(waypoint_speed, 80); + int tmp = min(wp_distance, 50) * 100; + waypoint_speed = min(tmp, g.waypoint_speed_max.get()); + waypoint_speed = max(waypoint_speed, 80); //}else{ // waypoint_speed = g.waypoint_speed_max.get(); //}