From 1a222fa2f448d6d5f7b54def2594ad2ead58f0c3 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 13 Oct 2011 10:54:51 -0700 Subject: [PATCH] slowed acceleration from WP --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index a102bbcd38..144b498243 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -115,7 +115,7 @@ static void calc_nav_rate(int max_speed) // limit the ramp up of the speed if(waypoint_speed_gov < max_speed){ - waypoint_speed_gov += 40; + waypoint_speed_gov += 10; max_speed = min(max_speed, waypoint_speed_gov); }