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