Skip to content

Understanding the Anti-Windup Action #276

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
ViktorCVS opened this issue Jan 21, 2025 · 7 comments · May be fixed by #298
Open

Understanding the Anti-Windup Action #276

ViktorCVS opened this issue Jan 21, 2025 · 7 comments · May be fixed by #298
Labels

Comments

@ViktorCVS
Copy link

I'm creating this issue to gain a better understanding of the Anti-Windup Action in the PID controller code (pid.cpp#L160C1-L173C4).

Currently, when antiwindup is set to true, the integral error is capped between i_max and i_min, which aligns with the expected anti-windup functionality by preventing the integral term from accumulating excessively. However, when antiwindup is set to false, the integral contribution to the output is also capped between i_max and i_min (which is also an anti-windup technique).

This raises a couple of questions. First, is it necessary to cap the integral contribution to the output when the package already has an antiwindup parameter that manages the integral error? Second, in unstable systems, systems with high-frequency behavior, or systems with noise, the proportional and derivative parts of the error might also exceed the actuator limits. Shouldn't the system limit the entire output (or the individual contributions) rather than just the integral contribution to ensure stability and prevent the proportional and derivative terms from causing actuator saturation (if this feature is necessary)?

As suggestions for a simple improvement, I would either remove the second block (pid.cpp#L170C1-L173C4), implement it also in the proportional and/or derivative contributions, or implement it in the final output cmd_ (pid.cpp#L179).

However, it would still be unclear why there's a parameter that activates the Anti-Windup action whether you set it to true or not. A more robust improvement, if this saturation is required, is to expand it to the other contributions (and/or for the entire control output) and add new parameters to clarify which value is saturating what. I would like to work on this, but first, I thought it was a good idea to bring up this discussion to assess the necessity of this change.

@christophfroehlich
Copy link
Contributor

I agree with you, I stumbled upon this already once but haven't questioned it that much back then.

The part was added with this commit de6346b, but there is no discussion about that I could find.

I agree that it should be possible to limit the output independent of anti-windup. But i_clamp_max has the wrong name therefore -> we have to add new parameters (default is no clamping). With the two new limits in place, we could then use the same values to clamp the integral action in case anti-windup is true and i_clamp_max is not set. So we don't change the behavior that much to avoid breaking existing configurations.

@christophfroehlich
Copy link
Contributor

If you want to work on this, could you base your work on top of #246 please (and maybe you can also leave your review there?). I hope we can get that merged soon.

@ViktorCVS
Copy link
Author

Sure!

@bijoua29
Copy link

I think the antiwindup flag should mean something. Currently, the code is applying antiwindup, regardless of the flag. We should only apply antiwindup if the flag is set. This may be a breaking change but if you set the antiwindup to false, the expectation should be that it is not preventing windup.

Also, I am not sure any saturation limiting of output should be done in the pid component. In many cases, the variable that is the output of the pid is not the actual command sent to the actuator. It may undergo some transformation before settling on the command to the actuator. And the actuator command is what usually needs to be saturated. So, the saturation limiting, in this case, is done outside of the pid component. But I don't have any strenuous objection to adding it here if others think it is useful.

@ViktorCVS
Copy link
Author

Thanks! Regarding your concern about output saturation, it will be implemented as a boolean option, allowing users to decide whether to limit the output. This option can be applied in several ways:

It can saturate the command sent to the actuator (I).
It can saturate the signal before the transformation you mentioned (II), which might be useful for some users.
It can define a maximum PID output value for safety reasons (III), protecting people or equipment (not necessarily the actuator).

This feature would be beneficial for my applications, and I believe it could also be useful for other users. I've uploaded the PR today (#298); it would be awesome if you had some time to take a look and offer some recommendations.

@bijoua29
Copy link

@ViktorCVS Sure, will take a look at the PR

Copy link
Contributor

This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants