AC_PID: If PD max limiting isn't active clear the flag

This commit is contained in:
Michael du Breuil 2023-10-11 11:02:55 -07:00 committed by Andrew Tridgell
parent 00a5c92635
commit dc35b2f6bc
1 changed files with 1 additions and 0 deletions

View File

@ -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);