Plane: reset roll/pitch integrators while tailsitter active

this prevents integrator buildup while flying in hover
This commit is contained in:
Andrew Tridgell 2017-02-18 22:23:58 +11:00
parent 41b9d7c2c9
commit 07ab04897d

View File

@ -41,6 +41,8 @@ void QuadPlane::tailsitter_output(void)
{
if (tailsitter_active()) {
motors_output();
plane.pitchController.reset_I();
plane.rollController.reset_I();
}
}