From dc35b2f6bc065d1fd3c37a52215f863e441525bc Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 11 Oct 2023 11:02:55 -0700 Subject: [PATCH] AC_PID: If PD max limiting isn't active clear the flag --- libraries/AC_PID/AC_PID.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index bf154a59d7..8d3349252c 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -172,6 +172,7 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, P_out *= boost; D_out *= boost; + _pid_info.PD_limit = false; // Apply PD sum limit if enabled if (is_positive(_kpdmax)) { const float PD_sum_abs = fabsf(P_out + D_out);