From cbe297b634ca03e0c6ecbd3ba3e6c99b84acd3e9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:08:07 -0800 Subject: [PATCH] scaled X velocity --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index a2b178fca5..d7e9ce933c 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -55,7 +55,7 @@ static void calc_XY_velocity(){ // straightforward approach: ///* - x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * tmp; + x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * scaleLongDown * tmp; y_actual_speed = y_speed_old + (float)(g_gps->latitude - last_latitude) * tmp; x_actual_speed = x_actual_speed >> 1;