ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Converting dynamic reconfigure to ros2 parameters

asked 2019-01-10 10:15:55 -0500

lucasw gravatar image

updated 2019-01-10 17:51:51 -0500

This isn't a very clear question, mostly just a dump of my current understanding of how to use ros2 parameters and hopefully any misconceptions can be addressed in comments or answers.

I have many ros1 nodes that use dynamic reconfigure that I'm converting to ros2, and it appears ros2 parameters can provide the same functionality with approximately the same resource costs and lines of code.

The example code in https://github.com/ros2/demos is nice but the use of modern C++ isn't always helpful, it multiplies the cognitive load in the jump from ros1 to ros2 and the use of auto is less self-documenting except in the trivial cases where the type of the auto is on right side of the same line of code. Adding older style examples that duplicate functionality of the existing examples would be good but then doubles the number of examples to be gone through by a new user.

https://github.com/lucasw/ros2_cpp_py has some of what I think is the right way for path of least resistance in updating ros1 code:

  • set_parameter_if_not_set() followed by get_parameter_or() for all parameters in the constructor/init. (or the other way around, the order doesn't matter). This makes sure any other node can see all the parameters used internally by this node, that parameter yaml values are in use.

Putting this into the class which inherits from rclcpp::Node is roughly the same as the dynamic reconfigure boiler plate:

rclcpp::AsyncParametersClient::SharedPtr parameters_client_;
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr param_sub_;
void onParameterEvent(const rcl_interfaces::msg::ParameterEvent::SharedPtr event);

Then at constructor/init time:

parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this);
param_sub_ = parameters_client_->on_parameter_event(
    std::bind(&CppTest::onParameterEvent, this, std::placeholders::_1));

This is where parameter handling got confusing:

void CppTest::onParameterEvent(const rcl_interfaces::msg::ParameterEvent::SharedPtr event) {
...
}

It appears that onParameterEvent will get a message for every parameter event in the same namespace, so two nodes with parameter event handlers will get events meant for each other, which is especially bad if the multiple nodes use parameters with the same names. Leaving the node name blank in AsyncParametersClient appears identical to the following, and doesn't help with filtering out unwanted events:

const std::string full_name = std::string(get_namespace()) + std::string(get_name());
parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this, full_name);

(Is that behavior that might change post-crystal?)

The parameter handling behind the scenes knows which node a parameter is meant for, but in the parameter event handler the event->node string can be used to filter out unwanted updates:

const std::string full_name = std::string(get_namespace()) + std::string(get_name());
if (event->node != full_name) {
  return;
}

What to do inside onParameterEvent() is less clear. In many of my nodes there is a timer update function getting called so many times a second which runs processing code only if parameters have changed (or new messages arrived on input topics), so I could simply set a flag in onParameterEvent and then get the current value of every parameter with ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-01-15 07:33:53 -0500

lucasw gravatar image

updated 2019-01-15 07:41:14 -0500

I couldn't get on_parameter_event to work when the node was within a namespace, but the object is already a Node so doesn't need a parameters client for itself, that is redundant- so get rid parameters_client_ and param_sub_ and onParameterEvent above inside the class that is the receiving end of set parameters.

Instead:

class CppTest : public rclcpp::Node {
...

  register_param_change_callback(
        std::bind(&CppTest::onParameterChange, this, _1));

...
rcl_interfaces::msg::SetParametersResult CppTest::onParameterChange(
    std::vector<rclcpp::Parameter> parameters)
{
  // this doesn't do any checking, it just assumes the parameter
  // changes are good
  dirty_ = true;
  auto result = rcl_interfaces::msg::SetParametersResult();
  result.successful = true;
  return result;
}
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-01-10 10:15:55 -0500

Seen: 1,935 times

Last updated: Jan 15 '19