Browse Source

Plane: reset steering integrator on mode change and when not moving

this prevents an old integrator from causing problems on takeoff
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
daa32f9b62
  1. 5
      ArduPlane/Attitude.pde
  2. 1
      ArduPlane/system.pde

5
ArduPlane/Attitude.pde

@ -364,6 +364,11 @@ static void stabilize() @@ -364,6 +364,11 @@ static void stabilize()
rollController.reset_I();
pitchController.reset_I();
yawController.reset_I();
// if moving very slowly also zero the steering integrator
if (gps.ground_speed() < 1) {
steerController.reset_I();
}
}
}

1
ArduPlane/system.pde

@ -390,6 +390,7 @@ static void set_mode(enum FlightMode mode) @@ -390,6 +390,7 @@ static void set_mode(enum FlightMode mode)
rollController.reset_I();
pitchController.reset_I();
yawController.reset_I();
steerController.reset_I();
}
// exit_mode - perform any cleanup required when leaving a flight mode

Loading…
Cancel
Save