From f6fce1e2382f672d913601492318e963da5d7cd8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Nov 2012 13:34:58 +1100 Subject: [PATCH] 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. --- libraries/PID/PID.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index cb027140f6..97741f3a98 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -78,7 +78,6 @@ void PID::reset_I() { _integrator = 0; - _last_error = 0; _last_derivative = 0; }