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

ROS2 Dashing overwrite default param via yaml

asked 2019-05-22 05:43:01 -0600

alsora gravatar image

updated 2019-05-22 06:12:58 -0600

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/Tutori...

https://index.ros.org/doc/ros2/Releas...

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/b...

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

Thank you

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-05-22 17:12:28 -0600

William gravatar image

You should declare them instead, as described here:

https://index.ros.org/doc/ros2/Releas...

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));
edit flag offensive delete link more

Comments

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.

alsora gravatar image alsora  ( 2019-05-23 03:40:03 -0600 )edit

It was very helpful for me,

great thanks! Mohamed

MH_Ahmed gravatar image MH_Ahmed  ( 2020-03-02 15:23:19 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2019-05-22 05:43:01 -0600

Seen: 1,356 times

Last updated: May 22 '19