Browse Source

removed loiter I from Reset Nav

mission-4.1.18
Jason Short 13 years ago
parent
commit
10abb7871e
  1. 5
      ArduCopter/Attitude.pde

5
ArduCopter/Attitude.pde

@ -242,8 +242,9 @@ static void reset_nav(void) @@ -242,8 +242,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();
// considering not reseting wind control
//g.pi_loiter_lat.reset_I();
//g.pi_loiter_lon.reset_I();
circle_angle = 0;
crosstrack_error = 0;

Loading…
Cancel
Save