Skip to content
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

Add antiwindup to PID controller #38

Closed

Conversation

paulbovbel
Copy link

Resolve #34, adding a clamp on the internal integral error state rather than the output integral term.

@adolfo-rt
Copy link
Member

Please add some documentation and tests for the new functionality. From reading the existing tests, it seems that i_term clamping is referred to as an integral windup prevention strategy. It would be desirable to have available anti-windup strategies unambiguously documented.

More specifically, I would expect from reading the code API docs to understand the features and usage of the class. I would further expect to find reasonable usage examples from inspecting the test suite. The code might be there (except for the tests), but doc-wise I don't think the point is getting across.

@carlosjoserg carlosjoserg mentioned this pull request May 28, 2015
@carlosjoserg
Copy link
Contributor

Hi, I'm not sure this is actually implementing an anti-windup method, and in fact, I don't think it is changing anything at all from the previous PID implementation, but correct me if I'm wrong at something.

I'm going to go through the added feature, that is, when antiwindup_= true.

  1. The integral of the error is clamped here.
  2. Take the lower-clamped case: i_error = gains.i_min_ / gains.i_gain_.
  3. The integral term is computed here, which gives you:
    • i_term = gains.i_gain_ * i_error_
    • i_term = gains.i_gain_ * ( gains.i_min_ / gains.i_gain_ )
    • i_term = gains.i_min_

Same happens if you go through the upper-saturated case, you end up with i_term = gains.i_max_. And this is the same behavior as before when following the antiwindup_ = false case as seen here.

This is because the clamping is done on the i_term_ (before and after this PR) instead on the cmd_. The windup phenomena appears in the latter, where the clamping should be IMO, since the motivation of having a command that is physically plausible (for instance, sending 181 degrees to a half-turn valve is useless) should apply to the sum of all contributions.

If you don't really need an anti-windup method, and just want to get rid of the clamping, I would change the name antiwindup_ -> clamping_ to enable/disable the clamping. But still, clamping the cmd_ instead of the i_term_ should be discussed as well.

@paulbovbel
Copy link
Author

@carlosjoserg, clamping command output is certainly a feasible augmentation to the PID implementation, however it's distinct from antiwindup.

The existing controller behaviour is to clamp the integral output (i_term) of the controller to gains.i_max/i_min, without actually preventing windup.

There are many flavours of antiwindup, however the one I'm going with is "Preventing the integral term from accumulating above or below pre-determined bounds", which is done in this pull by limiting the controller's state (i_error_) from climbing above the limit determined from gains.i_max/i_min.

@paulbovbel paulbovbel mentioned this pull request Jun 2, 2015
@paulbovbel
Copy link
Author

Tests added, depends on #44

@paulbovbel
Copy link
Author

Or #42 which does the same thing, as well as adding tests.

@carlosjoserg
Copy link
Contributor

Ok, now I see! It is because of the clamping on the new i_term_ implementation that you see the windup, thanks.

Still I have a suggestion: Why not to use gains.i_max and gains.i_min for the i_error_ clamping directly to avoid the division by gains.i_gain_? If so, that would imply the saturation of cmd_ instead of i_term_, which might use other two parameters like gains.cmd_min / gains.cmd_max.

And perhaps the flag name could be like antiwindup_clamping_ instead of antiwindup_ to clarify the used method.

@paulbovbel
Copy link
Author

@carlosjoserg, because we are reusing gains.i_max from the previous implementation, where it is in the scale of i_term (and hence cmd_) and not i_error. This is reasonable because a user would want to parametrize the windup limit in the context of the controller's output cmd_ value.

@guihomework
Copy link
Contributor

@paulbovbel thanks for adding this antiwindup. We are highly interested in this feature.
However when testing your implementation on some shadow robot code, where gains of the pid are negative in their controllers, the antiwindup i_error limitation was saturating to i_max/i_gain in the wrong direction due to minus sign in i_gain. I solved it by adding a fabs on i_gain in the computation
i_error_ = std::max(gains.i_min_ / std::fabs(gains.i_gain_), std::min(i_error_, gains.i_max_ / std::fabs(gains.i_gain_)));

Maybe a test should be added to consider negative gains too unless this is never allowed / unsupported.

Please also add the antiwindup to the second computeCommand, Shadow uses this one:
double Pid::computeCommand(double error, ros::Duration dt)

hope this can be fixed and merged soon since it solves one issue on our Shadow hands controllers.
thanks.

@paulbovbel
Copy link
Author

@guihomework, I've only added the code to one computeCommand implementation, waiting on #44 to chain them together.

Thanks for testing these changes out - can you the fabs fix to https://github.com/clearpathrobotics/control_toolbox/tree/antiwindup-fix please?

I am happy to write some tests, but I know @adolfo-rt is very busy, and I want to make sure we settle on the implementation before I spend time writing the tests.

@guihomework
Copy link
Contributor

clearpathrobotics#1 with the fix only on the current implementation of the antiwindup

@adolfo-rt
Copy link
Member

I'm now in the process of merging pending PRs. I can take another look at this one once the negative gains issue is fixed and some tests are in place.

@paulbovbel
Copy link
Author

Negative gains issue has been fixed and tests have been added, ping for review.

@paulbovbel paulbovbel force-pushed the antiwindup-fix branch 2 times, most recently from 9192c5c to 1272ac2 Compare August 12, 2015 16:37
@guihomework
Copy link
Contributor

dear @paulbovbel we are using your branch + merged pid_state in our fork (waiting for this to be merged upstream, and this was fine until we wanted to rebuild today. I updated to the latest rebased and fixed branch but you added some parameters to the set function that is not covered yet by ros_controllers. Do you have a branch that already has some code fixes of ros_controller to handle these ?

ros_controllers/effort_controllers/src/joint_velocity_controller.cpp:92:45: error: no matching function for call to ‘control_toolbox::Pid::setGains(const double&, const double&, const double&, const double&, const double&)’
   pid_controller_.setGains(p,i,d,i_max,i_min);

thanks in advance

@paulbovbel
Copy link
Author

@guihomework, thanks for picking up on that. also required:

ros-controls/ros_controllers#195
ros-controls/control_msgs#15

@adolfo-rt, I have propagated the changes to add an antiwindup bool to control_msgs/JointControllerState. This probably wouldn't fly for indigo, but would you consider merging this change set into jade instead?

@guihomework
Copy link
Contributor

@paulbovbel thanks for quick reacting on that.
Meanwhile, on my own branch I have added a backward compatibility setGains and getGains (the same way you did in ros_controllers) but in the control_toolbox directly, so that ros_controllers do not need to be updated. This was the quickest fix I could find to compile.
I understand you prefer to get that to jade with the changes being applied in both repositories, but we are instantiating the control_toolbox in our own controllers and there I set the antiwindup, I don't need to it in ros_controllers yet (but other might need it and I need it to compile only to get rqt_jtc). Would be nice if the non ABI breaking of control_toolbox made it to indigo, with the new feature only optional.

@guihomework
Copy link
Contributor

@paulbovbel I found another bug in the handling of the antiwindup read from the parameter server.

Due to a python software converting by error a True into a 1, I got antiwindup: 1 in my pid controller configuration yaml.
I did not care because I thought a 1 was read as true, since I could read back true on the parameter server. But the pid controller did not apply antiwindup. I investigated.
The problem comes from a misunderstanding of param and a bug in the controller pid.

If a param is not a True/False boolean, param reading to a bool will fail and hence false is initialized in the pid controller as the default false value. Fine. But why can I read my 1 converted into True on the parameter server after the pid controller has initialized where I should see 1 or false at least ?

The Gains struct does not get its member antiwindup initialized to the real value read from the parameter server when init with a nodehandle is used https://github.com/clearpathrobotics/control_toolbox/blob/antiwindup-fix/src/pid.cpp#L93. This is the only init where setGains passes the Gains struct and not individual values.
For some reason the uninitialized Gains.antiwindup_ value turned into true.
Then the gains_buffer_ gets a true, which is used by the DynamicReconfigure, which sets back the true on the parameter server.
Double errors are really tricky to find !

The solution is to initialize the Gains.antiwindup_ and then at least the 1 is converted into false, which should help the user to see the problem.

If you want I can provide a patch, but this is a rather straight forward one liner add I think
gains.antiwindup_ = antiwindup_;
to be added there https://github.com/clearpathrobotics/control_toolbox/blob/antiwindup-fix/src/pid.cpp#L128

However, because the internal variable antiwindup_ is used in the computeCommand, this means that the dynamicReconfiguration of antiwindup will not be effective since it only changes the gains struct and not the private antiwindup_.
Why not use directly the Gains.antiwindup_ everywhere ?

@@ -45,6 +45,7 @@ def generate(gen):
gen.add( "d" , double_t, 1,"Derivative gain.", 1.0 , 0 , 1000)
gen.add( "i_clamp_min" , double_t, 1,"Min bounds for the integral windup", -10.0 , -1000 , 0)
gen.add( "i_clamp_max" , double_t, 1,"Max bounds for the integral windup", 10.0 , 0 , 1000)
gen.add( "antiwindup" , bool_t, 1,"Antiwindup.", True)
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What's the default for the antiwindup parameter? It seems to be true in this dynamic_reconfigure config here, but false in the constructor.

@meyerj
Copy link

meyerj commented Nov 13, 2015

Is there a real need for adding the antiwindup boolean property and all the API changes?

Actually both settings clamp the integrator output to gains.i_min_/i_max_. The old implementation could be simply considered as wrong, because it limited the effect of a winding up integrator on the output, but not the integrator state itself. There is a use case for limiting the overall output of all terms as returned by double Pid::computeCommand() because those limits are simply enforced by any real actor, and hitting them should also stop/limit the internal integrator. But limiting only the integral term?

In my opinion the antiwindup property can be omitted completely in favor of the new implementation or, if set to false, should disable the integrator clamping completely. I am aware that such a change would not be fully backwards-compatible, but the new i_error_ limiting also effectively limits the i_term and the overall control behavior can only improve with a correct anti-windup.

On the other side I would suggest to introduce an output_limit_min and output_limit_max parameter pair, because limiting the output in the caller's code without stopping the integrator can also lead to integrator wind-up issues.

if(antiwindup_)
{
// Prevent i_error_ from climbing higher than permitted by i_max_/i_min_
i_error_ = std::max(gains.i_min_ / std::fabs(gains.i_gain_), std::min(i_error_, gains.i_max_ / std::fabs(gains.i_gain_)));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: factor out the clamp implementation to improve readability. The function could live in an anonymous namespace in this file. If it's not used outside the file, you can inline it as well (in the cpp).

namespace
{
inline double clamp(val, min, max) {return std::max(min, std::min(val, max));}
}

@guihomework
Copy link
Contributor

@meyerj regarding your suggested output_limit_min parameter. I would argue that the controllers using the PID can easily clamp the overall output if desired, but the integral term and/or integral error cannot be clamped from outside, hence some clamping inside.
I don't know how a permanently integrated antiwindup would affect other controllers, but I would not mind, all the controllers we need can benefit from the antiwindup.

If the antiwindup parameter is maintained, the default values should indeed be consistent everywhere.

@meyerj
Copy link

meyerj commented Nov 16, 2015

@meyerj regarding your suggested output_limit_min parameter. I would argue that the controllers using the PID can easily clamp the overall output if desired, but the integral term and/or integral error cannot be clamped from outside, hence some clamping inside.

That's exactly the point: No. In almost all practical use cases the limitation is the hardware (or the hardware interface), which only sees the overall output (sum of the proportional, integral and differential terms). Whenever this limit is reached, the anti-windup mechanism should stop the integrator, because the control error cannot be further reduced by "applying more force". Otherwise, if the internal integrator state continues to "charge" up, the control system eventually cannot recover fast enough once the set point would come back to a feasible region.

So the limitation of the integral term only like in the current implementation looks quite weird to me, because the output is still unbounded and if only the user of the Pid class would apply some saturation limits, there is no way to prevent internal wind-up. In practice, limiting the integral term alone might be enough because the other terms are usually somehow bounded by the inputs, but where should the gains.i_min_/i_max_ parameters come from if not from some real limitations of the control action?

Here is how the Simulink PID controller block handles anti-windup, just for reference:
http://nl.mathworks.com/help/simulink/slref/pidcontroller.html#br58hii-1

What I would propose is to apply the clamping method if antiwindup is true, and the none method otherwise. The clamping could be triggered by exceeding the new output limits or by exceeding the internal integral term limits, for backwards compatibility.

@guihomework
Copy link
Contributor

@meyerj the simulink approach is one solution.
I am speaking with intuition now, and only from observation on my system. I cannot speak in the general case unfortunately.
I am wondering if this approach would not perturb the controllers I use (sr_mechanism_controllers of the shadow hand). In case there is a huge position error (which should not occur if you use a trajectory generator), the integral term would be stopped from increasing as soon as the PID saturates, from the P error * P gain participating a lot in the PID output, and would only start to "charge" when the error reduces, probably leading to slower reach of the null steady state error because the iTerm did not charge up before.
You can argue that if such a case occurs, this is because my PID gains are badly chosen. Maybe. But with a 20 DOF hand, tendon-driven with unmodelable friction, with coupling (24DOF total), I can ensure it is really hard to tune those PIDs nicely. I would like to keep my system working.
Probably simpler hardware design would not care of the changes you suggests.

If you have a branch that does anti-windup regarding global output saturation, I would be glad to test it, and possibly contradict my intuition.

The Shadow controllers have limitations for absolute hardware maximum (or soft maximum let's say), to not send values above what the hardware can do. The PID output is not sent directly to the joint_effort command as there is a feed-forward term too or a friction compensation term (that do not exist yet in PID controller) added to that. I need a second output limitation anyway.
So one should not assume that the PID is the last element before the hardware. A controller should take care of the limitation too imho. This was my reason for not necessarily adding a new limitation in the PID. I do not know the general case. Could a bad design in our case. We might have gone for a new FPIDfriction toolbox that does all the computation, the controller just calling the compute method. Then the saturation would indeed be in this toolbox.

I suppose the imin/imax parameter should be kept also for backward compatibility.
So a new parameter for output limitation would change the API too.

@paulbovbel
Copy link
Author

I think the general approach with a package like this one is that the default functionality/implemenation must be respected, since it's used downstream by many unaware users.

@guihomework thanks for spotting that. I'll have to re-evaluate how I've used the Gains struct and make sure everything works well.

@bmagyar
Copy link
Member

bmagyar commented Apr 15, 2016

Any updates here? Not likely to make it into the first Kinetic release but better to start pushing for it now.

@guihomework
Copy link
Contributor

I was hoping it could be even integrated in indigo at some point...
I am using it at a daily basis and cannot run my controllers without (on the shadow hand), but due to this being a low-level package, I have to rebuild ros_controllers and gazebo_ros_pkgs to use this feature everywhere. Would be nice to get it merged upstream.

@bmagyar
Copy link
Member

bmagyar commented Apr 18, 2016

I'm open to merge things for Kinetic. Merging to Indigo and Jade will need more attention that I do not wish to decide on alone.

@paulbovbel any updates? Could you please do a rebase & a new PR against kinetic-devel?

@paulbovbel
Copy link
Author

Will have time to work on this on March 27th. Is this blocking release for you @bmagyar?

@bmagyar
Copy link
Member

bmagyar commented Apr 22, 2016

I'm rolling everything out as soon as the anti windup stuff is merged to
kinetic-devel here. The blunt answer is yes.

I would prefer to not to start with a planned API update but perhaps that's
the good way to go.
What's your take on it?
On 22 Apr 2016 15:40, "Paul Bovbel" notifications@github.com wrote:

Will have time to work on this on March 27th. Is this blocking release for
you @bmagyar https://github.com/bmagyar?


You are receiving this because you were mentioned.
Reply to this email directly or view it on GitHub
#38 (comment)

@paulbovbel
Copy link
Author

paulbovbel commented Apr 22, 2016

The core stuff works, I just have to examine the whole chain of components that depend on control_toolbox and make sure I don't break anything, it seems like a deep rabbit hole with ros_controllers. Not particularly difficult but time consuming and I want to do it right. Wednesday should be good.

@bmagyar
Copy link
Member

bmagyar commented Apr 22, 2016

I think I may be able to release ros_control without control_toolbox. The dependency is old and I could cut it. Hoping pre-release will succeed

@bmagyar
Copy link
Member

bmagyar commented Apr 23, 2016

@paulbovbel , I cut the dependency of control_toolbox to ros_control, it wasn't used at all there. Now only ros_controllers is blocked but that's not an issue for ros-kinetic-desktop-full. Take your time, make sure that everything's fine.

@paulbovbel
Copy link
Author

@guihomework, thanks for your patience and testing, I've corrected the issues you highlighted.

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

Successfully merging this pull request may close these issues.

None yet

6 participants