From 4dc2956ca9f8df80779db4d4a65d4bacd6ebc28c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 9 Dec 2011 22:13:37 +0900 Subject: [PATCH] Navigatino - small bug fix in loiter controller in which the y_iterm was coming from the Lon controller instead of the lat controller. Found by Sylvain. http://www.diydrones.com/forum/topic/listForContributor?user=18fsncw0k1x6i --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 243f25c8eb..044cc072bc 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -64,7 +64,7 @@ static void calc_loiter(int x_error, int y_error) int x_target_speed = g.pi_loiter_lon.get_p(x_error); int y_target_speed = g.pi_loiter_lat.get_p(y_error); int x_iterm = g.pi_loiter_lon.get_i(x_error, dTnav); - int y_iterm = g.pi_loiter_lon.get_i(y_error, dTnav); + int y_iterm = g.pi_loiter_lat.get_i(y_error, dTnav); // find the rates: float temp = g_gps->ground_course * RADX100;