mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
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:
parent
d41467424b
commit
3dcf4cfb55
@ -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();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user