Skip to content
Snippets Groups Projects
Commit daa32f9b authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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

this prevents an old integrator from causing problems on takeoff
parent e9a9e332
No related branches found
No related tags found
No related merge requests found
......@@ -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();
}
}
}
......
......@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment