rclcpp Params Tutorial – Get and Set ROS2 Params with Cpp

In this rclcpp params tutorial you’ll see how to get and set ROS2 params with rclcpp, in a Cpp node.

If you want to do the same with Python, check out the rclpy tutorial.

Setup code and declare ROS2 params with rclcpp

Before you use a ROS2 param in your Cpp code, you must declare it. If you don’t do that, you won’t be able to access it and you’ll get an error instead (rclcpp::exceptions::ParameterNotDeclaredException).

Declare params with rclcpp

Let’s declare 3 parameters in the constructor of our ROS2 Cpp node.

#include "rclcpp/rclcpp.hpp"

class TestParams : public rclcpp::Node
{
public:
    TestParams() : Node("test_params_rclcpp") {
        this->declare_parameter("my_str", rclcpp::PARAMETER_STRING);
        this->declare_parameter("my_int", rclcpp::PARAMETER_INTEGER);
        this->declare_parameter("my_double_array", rclcpp::PARAMETER_DOUBLE_ARRAY);
    }

private:
};

// Code below is just to start the node
int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<TestParams>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

Make sure to provide the type for each parameter (or a default value, see more later). For the type, just start with “rclcpp::PARAMETER_” and you should see all available types using auto-completion.

If, at some point, you need to undeclare a parameter, you can do so with undeclare_parameter(param_name), for example this->undeclare_parameter("my_str");.


You want to learn ROS2 efficiently?

Check out ROS2 For Beginners and learn ROS2 step by step, in 1 week.


Run your node

Here are the commands we’ll use to run the node:

  • Without any parameter’s value set:
$ ros2 run ros2_tutorials test_params_rclcpp
  • With parameters which correctly match the ones we declared in the code:
$ ros2 run ros2_tutorials test_params_rclcpp --ros-args -p my_str:="Hello Cpp" -p my_int:=12 -p my_double_array:="[3.3, 4.4, 5.5]"

You can also use a launch file to start everything without manually typing the parameters in the terminal (improvement: use a YAML file to store your params).

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='ros2_tutorials',
            executable='test_params_rclcpp',
            parameters=[
                {'my_str': 'Hello Cpp'},
                {'my_int': 12},
                {'my_double_array': [3.3, 4.4, 5.5]}
            ],
            output='screen',
            emulate_tty=True
        )
    ])

You can experiment running your node with our without setting values for parameters. Also, try to see what happens when you set a value for a parameter which was not declared (hint: the parameter won’t appear when you do ros2 param list).

For a more detail test, check out the tests made in the Python version of this tutorial.

Get params with rclcpp

Your parameters have been declared from within your node. Now you can get their value.

Get params one by one

TestParams() : Node("test_params_rclcpp")
{
    this->declare_parameter("my_str", rclcpp::PARAMETER_STRING);
    this->declare_parameter("my_int", rclcpp::PARAMETER_INTEGER);
    this->declare_parameter("my_double_array", rclcpp::PARAMETER_DOUBLE_ARRAY);

    rclcpp::Parameter str_param = this->get_parameter("my_str");
    rclcpp::Parameter int_param = this->get_parameter("my_int");
    rclcpp::Parameter double_array_param = this->get_parameter("my_double_array");

    std::string my_str = str_param.as_string();
    int my_int = int_param.as_int();
    std::vector<double> my_double_array = double_array_param.as_double_array();

    RCLCPP_INFO(this->get_logger(), "str: %s, int: %s, double[]: %s",
                str_param.value_to_string().c_str(),
                int_param.value_to_string().c_str(),
                double_array_param.value_to_string().c_str());
}

The get_parameter(param_name) method will return the parameter as a rclcpp::Parameter object.

Then, to get the parameter’s value in the correct type, you can use a helper method – there is one for each parameter type: as_string(), as_int(), as_double(), as_bool(), as_string_array(), as_int_array(), as_double_array(), as_bool_array(), as_byte_array().

For example, for a string array: std::vector<std::string> param_value = param.as_string_array();. Use the auto keyword for more simplicity: auto param_value = param.as_string_array();.

You also get another helper method, useful for logging: value_to_string(). This will convert the parameter – with any type – to a string representation.

Another way to get params:

...
rclcpp::Parameter str_param;
rclcpp::Parameter int_param;
rclcpp::Parameter double_array_param;

this->get_parameter("my_str", str_param);
this->get_parameter("my_int", int_param);
this->get_parameter("my_double_array", double_array_param);
...

The main difference between the 2 methods is how you’ll handle errors when you try to get a parameter which was not declared.

With the first one, you get a “rclcpp::exceptions::ParameterNotDeclaredException” exception. With the second one, the method returns a boolean telling you if the value could be retrieved (= declared + set).

Get a list of params

You can get multiple params at once with get_parameters(param_list).

...
std::vector<std::string> param_names = {"my_str", "my_int", "my_double_array"};

std::vector<rclcpp::Parameter> params = this->get_parameters(param_names);

for (auto &param : params)
{
    RCLCPP_INFO(this->get_logger(), "param name: %s, value: %s",
                param.get_name().c_str(), param.value_to_string().c_str());
}
...

You can easily retrieve which param is which, using the get_name() method.

Set default values

You can set default values for your parameters directly when you declare them.

...
this->declare_parameter("my_str", "Default for string");
this->declare_parameter("my_int", 42);
this->declare_parameter("my_double_array", std::vector<double>{7.7, 8.8});
...

If you run your node with no parameter:

$ ros2 run ros2_tutorials test_params_rclcpp
[INFO] [test_params_rclcpp]: str: Default for string, int: 42, double[]: [7.7, 8.8]

The default values for parameters were applied. This way you can ensure that a parameter is never “null”.

Set params with rclcpp

You can set (and impose) a value for a ROS2 parameter, directly from you node. Note that it’s different from setting a default value. A default value will only be used if no other value is passed to the node. Setting a parameter from your node means that it will override any value previously set, from inside or outside the node.

Here’s how to set parameters one by one:

TestParams() : Node("test_params_rclcpp")
{
    this->declare_parameter("my_str", rclcpp::PARAMETER_STRING); 
    this->declare_parameter("my_int", rclcpp::PARAMETER_INTEGER); 
    this->declare_parameter("my_double_array", rclcpp::PARAMETER_DOUBLE_ARRAY);

    rclcpp::Parameter str_param("my_str", "Hola from code");
    this->set_parameter(str_param);

    // you can also do:

    this->set_parameter(rclcpp::Parameter("my_int", 77));
    this->set_parameter(rclcpp::Parameter("my_double_array", std::vector<double>{8.8, 9.9}));
}

Simply create a Parameter object, using 2 arguments: the parameter’s name and value.

If you now start the node, you will see that the 3 parameters are set, and the default value for “my_str” parameter is not used.

$ ros2 run ros2_tutorials test_params_rclcpp

# In another terminal:
$ ros2 param get /test_params_rclcpp my_str
String value is: Hola from code

You can also set multiple parameters at once:

...
this->set_parameters(std::vector<rclcpp::Parameter>{
    rclcpp::Parameter("my_str", "Hola from code"),
    rclcpp::Parameter("my_int", 77),
    rclcpp::Parameter("my_double_array", std::vector<double>{8.8, 9.9})
});
...

Allow undeclared parameters with rclcpp

In ROS2 the way to work with params is to always declare them before you use them.

In some specific situations you might want to allow undeclared parameters. For example if your node is not able to know every parameter’s name when it’s started. Maybe your application requires you to dynamically set new parameters (with new names) when you start, or to add parameters after launch time.

Well, there is a solution for that. Note, however, that you should always use the ROS2 way of doing things – declaring every parameter. Allowing undeclared parameters should only be done when you don’t have any other choice.

TestParams() : Node("test_params_rclcpp",
                    rclcpp::NodeOptions()
                        .allow_undeclared_parameters(true)
                        .automatically_declare_parameters_from_overrides(true))
{
    rclcpp::Parameter str_param;
    rclcpp::Parameter int_param;
    rclcpp::Parameter double_array_param;

    this->get_parameter_or("my_str", str_param, rclcpp::Parameter("my_str", "Hi"));
    this->get_parameter_or("my_int", int_param, rclcpp::Parameter("my_int", 48));
    this->get_parameter_or("my_double_array", double_array_param,
                           rclcpp::Parameter("my_double_array", std::vector<double>{12.12, 13.13}));

    RCLCPP_INFO(this->get_logger(), "str: %s, int: %s, double[]: %s",
                str_param.value_to_string().c_str(),
                int_param.value_to_string().c_str(),
                double_array_param.value_to_string().c_str());
}

In the node’s constructor you have to pass some additional node options, through the NodeOptions object with 2 flags set as true:

  • allow_undeclared_parameters.
  • automatically_declare_parameters_from_overrides.

Here in this example I’ve directly created the NodeOptions object in the constructor, but you can also instantiate it in your main and pass it as a reference.

So, when running this node, any parameter that you set from outside the node will be declared and set, even if you don’t declare it from within the node. Also you won’t get any error if you try to access a parameter which was not declared before. If the parameter doesn’t exist, you’ll just get a null value. That’s why, when doing this, it’s better to always set a default value for each parameter.

To get a parameter with those settings, use the get_parameter_or(param_name, param_object, default_param) method. It will fill the param_object with either the retrieved parameter (if it exists), or the default value.

If we start this node with those 2 parameters:

$ ros2 run ros2_tutorials test_params_rclcpp --ros-args -p my_int:=55 -p intruder:="You'll see me in the list"
[INFO] [test_params_rclcpp]: str: Hi, int: 55, double[]: [12.12, 13.13]

# In another terminal:
$ ros2 param list
/test_params_rclcpp:
  intruder
  my_int
  use_sim_time
$ ros2 param get /test_params_rclcpp intruder 
String value is: You'll see me in the list

The “my_int” parameter is declared because we set it from command line. The node will retrieve the correct value. The 2 other parameters are not declared, default values will be used.

Note that the additional undeclared parameter appears on the list and you can get its value.

A final note on this: by default, do what ROS2 suggests that you do. Declare all parameters you’ll need before you use them. Only allow undeclared parameters if you don’t have the choice.

rclcpp parameter callback

Even after you’ve declared and set your parameters, you can modify them from outside your node. And, if you wish to, you can get notified from within your node, so you can do something whenever a parameter has been changed.

(for ROS1 users, this is very similar to dynamic_reconfigure, but here it’s directly integrated in the node’s API, you don’t have to setup anything else.)

#include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"

class TestParams : public rclcpp::Node
{
public:
    rcl_interfaces::msg::SetParametersResult parametersCallback(
        const std::vector<rclcpp::Parameter> &parameters)
    {
        rcl_interfaces::msg::SetParametersResult result;
        result.successful = true;
        result.reason = "success";
        for (const auto &parameter : parameters)
        {
            if (parameter.get_name() == "my_str" &&
                parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
            {
                my_str_ = parameter.as_string();
                RCLCPP_INFO(this->get_logger(), "Parameter 'my_str' changed: %s", my_str_.c_str());
            }
        }
        return result;
    }

    TestParams() : Node("test_params_rclcpp")
    {
        this->declare_parameter("my_str", "default value");
        my_str_ = this->get_parameter("my_str").as_string();

        this->set_on_parameters_set_callback(
            std::bind(&TestParams::parametersCallback, this, std::placeholders::_1));
    }

private:
    std::string my_str_;
};

Use this template to handle any change made to any parameters you’ve declared. Check for the name and the type to be sure the value is correct.

Now what you do with this callback is up to you and depends on your application (to go further on this, check out this more complete rclcpp parameter callback tutorial).

Going further with ROS2 params

In this tutorial you’ve learned how to get and set ROS2 parameters with rclcpp, from your Cpp node. One thing worth repeating: don’t forget to declare your parameters before you use them.

To go further from this point:

Also, as ROS2 parameters are specific to a node, you can only be sure your parameters exist as long as your node is alive. What if you want some parameters to be in the global scope, available for all nodes? Well, if you ever need to have some global settings, one way to solve that issue is to create a node holding global parameters. Launch this node first and keep it alive as long as your application is alive. Then, other nodes from your application will be able to use ROS2 communication features to get params from this “global param node”.

Want to learn how to program with ROS2?

Don't miss this opportunity:

ROS2 For Beginners - Step by Step Course


[NEW] ROS 2 Book


Or, learn with a video course