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

This commit is contained in:
Randy Mackay 2011-12-09 22:13:37 +09:00
parent f531764f88
commit f4fd6e0910
1 changed files with 1 additions and 1 deletions

View File

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