-
Notifications
You must be signed in to change notification settings - Fork 111
Description
When passing the AntiwindupStrategy
value to the non-deprecated set_gains
method that throws a call of overloaded ... is ambiguous
error.
Since #298 there are several set_gains
definitions passing the parameters directly. Only one of them
control_toolbox/control_toolbox/include/control_toolbox/pid.hpp
Lines 663 to 665 in f652c3d
void set_gains( | |
double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation, | |
AntiwindupStrategy antiwindup_strat); |
is not marked deprecated, but calling this isn't possible, since the call is ambiguous with
control_toolbox/control_toolbox/include/control_toolbox/pid.hpp
Lines 640 to 643 in f652c3d
void set_gains( | |
double p, double i, double d, double i_max, double i_min, double u_max, double u_min, | |
double trk_tc = 0.0, bool saturation = false, bool antiwindup = false, | |
AntiwindupStrategy antiwindup_strat = AntiwindupStrategy::NONE); |
AntiwindupStrategy
class. However, the boolean and integer value can also be casted to doubles which is why the other definition is valid, as well.
I was quite surprised that the non-deprecated notation wasn't used in the tests, at all. I assume that's due to the fact that the deprecated definitions should be removed soon. However, given that, it seems a bit cumbersome to migrate to the new structure.
Steps to reproduce
I am currently attempting to migrate https://github.com/ros-controls/ros2_controllers/blob/e3cc6d8c71fb6fe0dc4e28a50c730ec67edbd09d/joint_trajectory_controller/src/joint_trajectory_controller.cpp#L1669
from
pids_[i]->set_gains(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
There also is not straightforward replacement specifying i_min
and i_max
but not u_max
and u_min
.
Workaround
To workaround this, the call can obviously be creating a AntiwindupStrategy
directly:
pids_[i]->set_gains(gains.p, gains.i, gains.d, 0.0, 0.0, 0.0, false,
control_toolbox::AntiwindupStrategy(control_toolbox::AntiwindupStrategy::NONE));