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:
Andrew Tridgell 2012-11-27 13:34:58 +11:00
parent 3f0e8dd358
commit f6fce1e238
1 changed files with 0 additions and 1 deletions

View File

@ -78,7 +78,6 @@ void
PID::reset_I()
{
_integrator = 0;
_last_error = 0;
_last_derivative = 0;
}