ROS2 rclcpp Parameter Callback [Tutorial]

In this ROS2 tutorial I will show you how to use an rclcpp parameter callback, so you can dynamically change parameters’ values while a node is alive.

With parameters you can already change the configuration of the node at runtime.

But after that, any change to any parameter won’t be taken into account. With a parameters callback you can make sure your rclcpp node is notified of any change and can update its values/take some actions accordingly.

(rclcpy callback parameter version for Python)

>> Watch this video as an additional resource to this article:


You want to learn ROS2 efficiently?

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


After watching the video, subscribe to the Robotics Back-End Youtube channel so you don’t miss the next tutorials!

Node setup

First, make sure you know how to create a ROS2 Cpp node and how to declare and get parameters with rclcpp.

Here’s a basis Cpp node with 3 declared parameters.

#include "rclcpp/rclcpp.hpp"

class TestParamsCallback : public rclcpp::Node
{
public:
    TestParamsCallback() : Node("test_params_rclcpp")
    {
        this->declare_parameter("motor_device_port", "/dev/ttyUSB0");
        this->declare_parameter("control_loop_frequency", 100);
        this->declare_parameter("simulation_mode", false);

        motor_device_port_ = this->get_parameter("motor_device_port").as_string();
        control_loop_frequency_ = this->get_parameter("control_loop_frequency").as_int();
        simulation_mode_ = this->get_parameter("simulation_mode").as_bool();
    }

private:
    std::string motor_device_port_;
    int control_loop_frequency_;
    bool simulation_mode_;
};


int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<TestParamsCallback>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

Here are the 3 parameters we use:

  • motor_device_port (string)
  • control_loop_frequency (int)
  • simulation_mode (bool)

Each of the param gets a default value. So, for our tests we don’t need to manually specify a value every time we start the node. Also, after being declared in the Node constructor, we retrieve the value for each param and store it inside a class attribute.

Now, when you start the node (from the terminal or via a launch file) you can set a value for all 3 parameters, or leave it empty to use the default ones.

After that, if you try to change a parameter’s value, well it will work on the environment, but your code won’t be notified. And this is why we’ll add a parameters callback.

Add an rclcpp parameter callback

The code

Let’s add an rclcpp parameter callback in our code.

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

class TestParamsCallback : 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";
        // Here update class attributes, do some actions, etc.
        return result;
    }

    TestParamsCallback() : Node("test_params_rclcpp")
    {
        this->declare_parameter("motor_device_port", "/dev/ttyUSB0");
        this->declare_parameter("control_loop_frequency", 100);
        this->declare_parameter("simulation_mode", false);

        motor_device_port_ = this->get_parameter("motor_device_port").as_string();
        control_loop_frequency_ = this->get_parameter("control_loop_frequency").as_int();
        simulation_mode_ = this->get_parameter("simulation_mode").as_bool();

        callback_handle_ = this->add_on_set_parameters_callback(
            std::bind(&TestParamsCallback::parametersCallback, this, std::placeholders::_1));
    }

private:
    std::string motor_device_port_;
    int control_loop_frequency_;
    bool simulation_mode_;

    OnSetParametersCallbackHandle::SharedPtr callback_handle_;
};

...

Here’s what we’ve added:

#include "rcl_interfaces/msg/set_parameters_result.hpp"

We need to import this because this is the return type of the parameters callback.

    rcl_interfaces::msg::SetParametersResult parametersCallback(
        const std::vector<rclcpp::Parameter> &parameters)
    {
        rcl_interfaces::msg::SetParametersResult result;
        result.successful = true;
        result.reason = "success";
        // Here update class attributes, do some actions, etc.
        return result;
    }

The rclcpp parameter callback. In this callback we get an array of rclcpp Parameter objects. Those are all the parameters which have been modified.

Inside the callback you are then free to do whatever you want with the info you got: update class attributes, start some actions, ignore the new values, etc.

And depending on your application and the data you receive here, it will be up to you to decide whether things are successful or not. You will have to return a SetParameterResult, containing a boolean flag “successful” and an optional string “reason” to give more info about why it’s successful/not successful.

        callback_handle_ = this->add_on_set_parameters_callback(
            std::bind(&TestParamsCallback::parametersCallback, this, std::placeholders::_1));

This is how you add an rclcpp parameter callback to your node. Use the add_on_set_parameters_callback() method directly from your node object (using “this->”). You can notice the particular syntax using std::bind(), needed because we are inside a class.

    OnSetParametersCallbackHandle::SharedPtr callback_handle_;

And lastly, this is where you’ll store the rclcpp callback handle. No surprise here: in ROS2 with C++, almost everything is a shared pointer.

Get info for each received param

If you want to easily see what you get in the parameters callback, you can use a code like this.

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 &param: parameters)
    {
        RCLCPP_INFO(this->get_logger(), "%s", param.get_name().c_str());
        RCLCPP_INFO(this->get_logger(), "%s", param.get_type_name().c_str());
        RCLCPP_INFO(this->get_logger(), "%s", param.value_to_string().c_str());
    }
    return result;
}

With those functions (get_name(), get_type_name(), and value_to_string()), you can get a string representation for all the important info contained inside the Parameter object. Then you just need to print them using RCLCPP_INFO().

Let’s make a test. Open 2 terminals.

On terminal 1, start the node.

On terminal 2, modify a parameter.

$ ros2 param set /test_params_rclcpp motor_device_port "abc"
Set parameter successful

Now if you look at terminal 1 where the node is running:

$ ros2 run my_cpp_pkg test_params_callback
[INFO] [1609323981.935474125] [test_params_rclcpp]: motor_device_port
[INFO] [1609323981.935588821] [test_params_rclcpp]: string
[INFO] [1609323981.935603513] [test_params_rclcpp]: abc

With this you know exactly what you’ve received.

Update class attributes in the callback

When the callback is triggered, you can go through all parameter’s name. When you find a match, you can update the class attribute or variable accordingly.

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 &param: parameters)
    {
        if (param.get_name() == "motor_device_port")
        {
            motor_device_port_ = param.as_string();
        }
    }
    return result;
}

Remove parameter callback

After the node gets killed, the parameter callback will automatically be destroyed.

You can however decide to remove the callback at anytime, simply by using the method remove_on_set_parameters_callback(), for example here this->remove_on_set_parameters_callback(callback_handle_.get());. After that you can still modify parameters outside of the node, but the node won’t get notified anymore.

Improve your rclcpp callback: process the data

There are many ways to process the data and decide on what to do inside the callback. In the end it depends on what you need for your application.

Here I’m going to show you some best practices to improve your callback code, that you can probably use in every node you create.

Execute an action

A change of parameter may also trigger an action.

For example, let’s say your node controls a motor. The motor is plugged to your computer and is recognized thanks to a device port name. And now you’ve disconnected/reconnected the motor, and the device port changed from “/dev/ttyUSB0” to “/dev/ttyUSB1”.

If the port changed, you’ll probably need to redo some parts of the initialization for the motor. But pay attention here: as you are inside a callback you don’t want to spend too much time there. So what you’ll do is set a flag that will be used in a different thread to re-initialize the motor.

This will look like this:

void motorThread()
{
    // ...
    if (restart_motor_)
    {
        // restart motor with new device port
        restart_motor_ = false;
    }
    // ...
}

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 &param: parameters)
    {
        if (param.get_name() == "motor_device_port")
        {
            motor_device_port_ = param.as_string();
            restart_motor_ = true;

        }
    }
    return result;
}

Check parameter’s type

The type for a parameter is dynamically evaluated. First you create or update a parameter with a value, and then the type will be set.

So, this can lead to all sorts of errors in your code.

If we take our previous example, we expect a string for the motor_device_port parameter.

Now, open 2 terminals. On terminal 1 start the node.

On terminal 2, try to set a non-string value for the parameter.

$ ros2 param set /test_params_rclcpp motor_device_port 3
Set parameter successful

And going back to terminal 1… You’ll see that your node has crashed.

$ ros2 run my_cpp_pkg test_params_callback
terminate called after throwing an instance of 'rclcpp::ParameterTypeException'
  what():  expected [string] got [integer]

As the type is not strictly identical, you get an exception.

So, what you need to do, when you get the name of the parameter in your code, is to also check if the type is valid.

rcl_interfaces::msg::SetParametersResult parametersCallback(
    const std::vector<rclcpp::Parameter> &parameters)
{
    rcl_interfaces::msg::SetParametersResult result;
    result.successful = false;
    result.reason = "";
    for (const auto &param : parameters)
    {
        if (param.get_name() == "motor_device_port")
        {
            if (param.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
            {
                motor_device_port_ = param.as_string();
                restart_motor_ = true;
                result.successful = true;
            }
        }
    }
    return result;
}

Here we are sure than when we execute param.as_string(), we have a string. So, no error in the code.

Also, you can notice that now in the program, the default value for the success flag is “false”. We only set it to “true” if we can actually update the class attribute.

If your function returns a not successful result, the parameter’s value will not be updated.

$ ros2 param set /test_params_rclcpp motor_device_port "abc"
Set parameter successful
$ ros2 param set /test_params_rclcpp motor_device_port 3
Setting parameter failed
$ ros2 param get /test_params_rclcpp motor_device_port 
String value is: abc

When we try to give an integer value to the parameter, first the callback will be triggered. If the result is not successful, the parameter won’t be updated, and we get “Setting parameter failed”.

Validate data

One additional improvement we can add is data validation.

OK, now you’re sure that the name and the type of your parameters are correct in the callback.

For example, for the control_loop_frequency parameter, we can make sure we only get integer numbers (as the frequency is defined in Hz here). But, what if I send a negative value, or a value too high (ex: 4000 Hz)? For now there is no protection against that, and this can lead to other errors in your program execution.

So, a best practice is to also validate any data you get in the rclcpp parameter callback.

rcl_interfaces::msg::SetParametersResult parametersCallback(
    const std::vector<rclcpp::Parameter> &parameters)
{
    rcl_interfaces::msg::SetParametersResult result;
    result.successful = false;
    result.reason = "";
    for (const auto &param : parameters)
    {
        if (param.get_name() == "motor_device_port")
        {
            if (param.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
            {
                if (param.as_string().rfind("/dev/tty", 0) == 0) // starts with
                {
                    motor_device_port_ = param.as_string();
                    restart_motor_ = true;
                    result.successful = true;
                }
            }
        }
        if (param.get_name() == "control_loop_frequency")
        {
            if (param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
            {
                if (param.as_int() >= 1 && param.as_int() < 1000)
                {
                    control_loop_frequency_ = param.as_int();
                    result.successful = true;
                }
            }
        }
        if (param.get_name() == "simulation_mode")
        {
            if (param.get_type() == rclcpp::ParameterType::PARAMETER_BOOL)
            {
                simulation_mode_ = param.as_bool();
                result.successful = true;
            }
        }
    }
    return result;
}

Now, you can handle the result in different ways: setting it to false or true by default, and update it accordingly. Also, something I’ve not done here, is to provide an explanation – in “result.reason” – when the parameter’s value is rejected. For example, if you get 8000 for the control_loop_frequency, then you might return something like “control loop frequency must be between 1 and 999 Hz”.

Conclusion – rclcpp parameter callback

The ROS2 parameter feature is very powerful to start a node multiple times with different configurations – without having to compile it again.

With the rclcpp parameter callback, you can go even further and get notified whenever a parameters has been modified while the node is alive.

As best practices, make sure you validate the type and the value of any parameter, before you take them into account. If not valid, return false for “result.successful”, so the parameter will keep its previous value and type.

And finally, if you decide to trigger any action after a parameter has been changed, then execute this action in a different thread so the callback can exit as soon as possible.

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