mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_PID: If PD max limiting isn't active clear the flag
This commit is contained in:
parent
00a5c92635
commit
dc35b2f6bc
@ -172,6 +172,7 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit,
|
|||||||
P_out *= boost;
|
P_out *= boost;
|
||||||
D_out *= boost;
|
D_out *= boost;
|
||||||
|
|
||||||
|
_pid_info.PD_limit = false;
|
||||||
// Apply PD sum limit if enabled
|
// Apply PD sum limit if enabled
|
||||||
if (is_positive(_kpdmax)) {
|
if (is_positive(_kpdmax)) {
|
||||||
const float PD_sum_abs = fabsf(P_out + D_out);
|
const float PD_sum_abs = fabsf(P_out + D_out);
|
||||||
|
Loading…
Reference in New Issue
Block a user