control_toolbox icon indicating copy to clipboard operation
control_toolbox copied to clipboard

PID controller handling of parameters in ROS 2

Open SammyRamone opened this issue 3 years ago • 2 comments

I was switching my code, which uses the PID controller from this project, from ROS1 to ROS2 and ran into the following issue: When the PID controller is created a reference on the node is taken as a parameter. I assumed that this should be a reference to the node that is using this PID controller. The description of the constructor (https://github.com/ros-controls/control_toolbox/blob/ros2-master/include/control_toolbox/pid_ros.hpp#L58-L61) seemed to suggest that I only need to put it in a correct namespace. Therefore, I programmed something like this:

std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("node");
node->declare_parameter<double>("pid.p", 0.0);
node->declare_parameter<double>("pid.i", 0.0);
node->declare_parameter<double>("pid.d", 0.0);
node->declare_parameter<double>("pid.i_clamp_max", 0.0);
node->declare_parameter<double>("pid.i_clamp_min", 0.0);
node->declare_parameter<bool>("pid.antiwindup", false);
control_toolbox::PidROS pid = control_toolbox::PidROS(node, "pid");
pid.initPid();
node->declare_parameter<double>("not_related_to_pid", 0.0);
double not_related_to_pid;
node->get_parameter("not_related_to_pid", not_related_to_pid);

Executing this leads to following error:

[Node-4] terminate called after throwing an instance of 'rclcpp::exceptions::InvalidParameterValueException'
[Node-4]   what():  parameter 'not_related_to_pid' could not be set: Invalid parameter

I think, the reason is that the pid controller sets the add_on_set_parameters_callback here: https://github.com/ros-controls/control_toolbox/blob/d7462e982e40bfdebddbcff8849c611caf8c8422/src/pid_ros.cpp#L281-L326 This is now for the whole node and therefore any other not PID related parameters will result in errors.

I managed to fix this by creating a seperate node for the pid controller.

std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("node");
std::shared_ptr<rclcpp::Node> node_pid = rclcpp::Node::make_shared("pid");
node_pid->declare_parameter<double>("p", 0.0);
node_pid->declare_parameter<double>("i", 0.0);
node_pid->declare_parameter<double>("d", 0.0);
node_pid->declare_parameter<double>("i_clamp_max", 0.0);
node_pid->declare_parameter<double>("i_clamp_min", 0.0);
node_pid->declare_parameter<bool>("antiwindup", false);
control_toolbox::PidROS pid = control_toolbox::PidROS(node_pid, "");
pid.initPid();
node->declare_parameter<double>("not_related_to_pid", 0.0);
double not_related_to_pid;
node->get_parameter("not_related_to_pid", not_related_to_pid);

My question is now: Is this intended behavior? Should every PID controller have its own node? If yes, I think the description of the constructor should be improved or a clearer error message should be thrown to point out that it needs it own node.

Additionally, I needed to declare the parameters of the controller before calling pid.initPid() to load yaml parameters from a launch file correctly. I think this is because the PID controller only calls the decleration https://github.com/ros-controls/control_toolbox/blob/d7462e982e40bfdebddbcff8849c611caf8c8422/src/pid_ros.cpp#L144-L149 after trying to get the parameters https://github.com/ros-controls/control_toolbox/blob/d7462e982e40bfdebddbcff8849c611caf8c8422/src/pid_ros.cpp#L114-L118

SammyRamone avatar Feb 22 '22 18:02 SammyRamone

This should be fixed with #125

progtologist avatar Jun 30 '22 18:06 progtologist