0
$\begingroup$

Rosanswers logo

Hi,

I would like to understand how to use the new parameters API that will be introduced with ROS2 Dashing.

I read some links but it's still not clear.

https://index.ros.org/doc/ros2/Tutorials/Node-arguments/

https://index.ros.org/doc/ros2/Releases/Release-Dashing-Diademata/#declaring-parameters

My scenario is the following: a node has some parameters. The default values for these parameters have to be hardcoded within the node. When running the node, it should be possible to pass a .yaml file with some updated values for one ore more parameters.

This is my node

class MyNode : public rclcpp::Node
{
public:
  MyNode() : rclcpp::Node("my_name", 
                          "", 
                          rclcpp::NodeOptions().append_initial_parameter("my_param", 42))
  {  }
}

The problem is that, as pointed out in the source code, initial values passed to constructor overwrite yaml file sources

https://github.com/ros2/rclcpp/blob/b17bbf31b36f5d4d7363707facd9db57fabe5334/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp#L156

How should I change the code of my node in order let the hardcoded parameter to be overwritten from the yaml one?

Thank you


Originally posted by alsora on ROS Answers with karma: 1322 on 2019-05-22

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

You should declare them instead, as described here:

https://index.ros.org/doc/ros2/Releases/Release-Dashing-Diademata/#declaring-a-parameter-with-a-parameterdescriptor

Your example would be like this:

class MyNode : public rclcpp::Node
{
public:
  MyNode(
    const std::string & name = "my_name",
    const std::string & namespace_ = "",
    const rclcpp::NodeOptions & options = rclcpp::NodeOptions)
  : rclcpp::Node(name, namespace_, options)
  {
    int64_t actual_value = this->declare_parameter("my_param", 42);
    // actual_value may be 42 or another value if overridden by the YAML file passed on the command-line
  }
}

The "initial parameter values" in the NodeOptions are most similar to having values in a YAML file, they're overrides, not declarations, e.g. you could override the default value programmatically like this:

auto my_node = std::make_shared<MyNode>("my_name", "", rclcpp::NodeOptions().append_initial_parameter("my_param", 1337));

Originally posted by William with karma: 17335 on 2019-05-22

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by alsora on 2019-05-23:
Thank you, it works perfectly. Before opening the question I tried that in the parameters_blackboard demo. But, in that executable, the rclcpp::NodeOptions are set to automatically_declare_initial_parameters(true) and this was causing an error.

Comment by MH_Ahmed on 2020-03-02:
It was very helpful for me,

great thanks! Mohamed

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.