Browse Source

Loiter I reset

master
Jason Short 13 years ago
parent
commit
1ef7f9fe62
  1. 2
      ArduCopter/ArduCopter.pde
  2. 8
      ArduCopter/Attitude.pde

2
ArduCopter/ArduCopter.pde

@ -1391,8 +1391,6 @@ static void update_navigation() @@ -1391,8 +1391,6 @@ static void update_navigation()
// reset LOITER to current position
next_WP = current_loc;
// clear Loiter Iterms
//reset_nav();
}else{
// this is also set by GPS in update_nav
wp_control = LOITER_MODE;

8
ArduCopter/Attitude.pde

@ -239,12 +239,12 @@ static void reset_nav(void) @@ -239,12 +239,12 @@ static void reset_nav(void)
nav_throttle = 0;
invalid_throttle = true;
//g.pi_nav_lat.reset_I();
//g.pi_nav_lon.reset_I();
g.pi_nav_lat.reset_I();
g.pi_nav_lon.reset_I();
// considering not reseting wind control
//g.pi_loiter_lat.reset_I();
//g.pi_loiter_lon.reset_I();
g.pi_loiter_lat.reset_I();
g.pi_loiter_lon.reset_I();
circle_angle = 0;
crosstrack_error = 0;

Loading…
Cancel
Save