mirror of https://github.com/ArduPilot/ardupilot
added loiter control to reset nav
This commit is contained in:
parent
8691b10ee9
commit
d2fd6c5ee5
|
@ -193,6 +193,9 @@ static void reset_nav(void)
|
||||||
g.pi_nav_lat.reset_I();
|
g.pi_nav_lat.reset_I();
|
||||||
g.pi_nav_lon.reset_I();
|
g.pi_nav_lon.reset_I();
|
||||||
|
|
||||||
|
g.pi_loiter_lat.reset_I();
|
||||||
|
g.pi_loiter_lon.reset_I();
|
||||||
|
|
||||||
circle_angle = 0;
|
circle_angle = 0;
|
||||||
crosstrack_error = 0;
|
crosstrack_error = 0;
|
||||||
nav_lat = 0;
|
nav_lat = 0;
|
||||||
|
|
Loading…
Reference in New Issue