mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
PID: don't reset _last_error on reset_I()
resetting _last_error when you have a non-zero D term causes the D contribution to the next call to be massively amplified. This can cause crazy behaviour on auto takeoff in ArduPlane if you have a non-zero D term for the roll or picth controllers Thanks to Chris Miser for providing the tlog that allowed this bug to be found.
This commit is contained in:
parent
332b728ebf
commit
c55e6d3e6a
@ -78,7 +78,6 @@ void
|
||||
PID::reset_I()
|
||||
{
|
||||
_integrator = 0;
|
||||
_last_error = 0;
|
||||
_last_derivative = 0;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user