mirror of https://github.com/ArduPilot/ardupilot
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:
parent
5130a37a9e
commit
4dc2956ca9
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue