Browse Source

ACM : Attitude : added nav param reset

mission-4.1.18
Jason Short 12 years ago
parent
commit
5ad38a32bf
  1. 6
      ArduCopter/Attitude.pde

6
ArduCopter/Attitude.pde

@ -529,6 +529,12 @@ static void reset_nav_params(void)
// Will be set by new command, used by loiter // Will be set by new command, used by loiter
long_error = 0; long_error = 0;
lat_error = 0; lat_error = 0;
nav_lon = 0;
nav_lat = 0;
nav_roll = 0;
nav_pitch = 0;
auto_roll = 0;
auto_pitch = 0;
// make sure we stick to Nav yaw on takeoff // make sure we stick to Nav yaw on takeoff
auto_yaw = nav_yaw; auto_yaw = nav_yaw;

Loading…
Cancel
Save