Plane: removed resetting integrators on mode change

this removes the zero of roll, pitch and yaw integrator on mode
change, now only doing the steering integrator.

The zeroing was from the early days when our controllers were not as
good. It should not be needed any more.
This commit is contained in:
Andrew Tridgell 2016-12-14 20:22:56 +11:00
parent d41467424b
commit 3dcf4cfb55

View File

@ -497,10 +497,7 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
if (should_log(MASK_LOG_MODE))
DataFlash.Log_Write_Mode(control_mode);
// reset attitude integrators on mode change
rollController.reset_I();
pitchController.reset_I();
yawController.reset_I();
// reset steering integrator on mode change
steerController.reset_I();
}