ROS2 rclpy Parameter Callback [Tutorial]

After starting a ROS2 node with some parameters, you want to be able to dynamically change those parameters and get notified inside your code? Well, the rclpy parameter callback is what you need to use. (if you were using ROS1 before, this is the same as dynamic_reconfigure, but better).

In this tutorial I will show you how to implement a rclpy parameter callback, and give you some best practices.

(rclcpp callback parameter version for Cpp)

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

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


You want to learn ROS2 efficiently?

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


Initialization

First, make sure you know how to create an rclpy Node and how to declare and get parameters with rclpy.

Starter code

We’ll start from this code.

import rclpy
from rclpy.node import Node

class TestParamsCallback(Node):
    def __init__(self):
        super().__init__('test_params_callback_rclpy')
        self.declare_parameter('camera_device_port', '/dev/ttyACM0')
        self.declare_parameter('simulation_mode', False)
        self.declare_parameter('battery_percentage_warning', 15.0)

        self.camera_device_port_ = self.get_parameter('camera_device_port').value
        self.simulation_mode_ = self.get_parameter('simulation_mode').value
        self.battery_percentage_warning_ = self.get_parameter('battery_percentage_warning').value

def main(args=None):
    rclpy.init(args=args)
    node = TestParamsCallback()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

Here we declare 3 parameters:

  • camera_device_port (string)
  • simulation_mode (bool)
  • battery_percentage_warning (float, could also be int)

We set a default value for each parameter. So, if we don’t manually set a value when we run the node (from the terminal or a launch file), the params will still be defined. After that we get the values for each parameter and we store them inside some class attributes.

What happens if you change a parameter with no callback

Now, let’s make a small experiment. Open 2 terminals.

On terminal 1, start the node with ros2 run.

On terminal 2, change a parameter’s value.

# Terminal 2
$ ros2 param list
/test_params_callback_rclpy:
  battery_percentage_warning
  camera_device_port
  simulation_mode
  use_sim_time
$ ros2 param set /test_params_callback_rclpy battery_percentage_warning 20.3
Set parameter successful
$ ros2 param get /test_params_callback_rclpy battery_percentage_warning 
Double value is: 20.3

The parameter battery_percentage_warning has changed, but in the code, the value inside the self.battery_percentage_warning_ attribute is still the old one!

You won’t get any error by doing this. But if you change a parameter’s value after it’s been read by the node, then the node won’t be able to know it if you don’t notify it. Hence we need to add a callback to notify the node as soon as the parameter has been modified.

Add an rclpy parameter callback

The code

Let’s add an rclpy parameter callback in our node.

import rclpy
from rclpy.node import Node
from rcl_interfaces.msg import SetParametersResult

class TestParamsCallback(Node):

    def parameters_callback(self, params):
        # do some actions, validate parameters, update class attributes, etc.
        return SetParametersResult(successful=True)

    def __init__(self):
        super().__init__('test_params_callback_rclpy')
        self.declare_parameter('camera_device_port', '/dev/ttyACM0')
        self.declare_parameter('simulation_mode', False)
        self.declare_parameter('battery_percentage_warning', 15.0)

        self.camera_device_port_ = self.get_parameter('camera_device_port').value
        self.simulation_mode_ = self.get_parameter('simulation_mode').value
        self.battery_percentage_warning_ = self.get_parameter('battery_percentage_warning').value

        self.add_on_set_parameters_callback(self.parameters_callback)

...

Here’s what we’ve added:

First of all, we create a new method in our node class – “parameters_callback”. This method will be used as the callback.

So, in the callback function, you’ll receive an array of all modified parameters. You are then free to do anything you want from this information: modify variables inside your code, do some actions, or even ignore the info.

After you’ve processed the parameter array, you’ll have to return a SetParameterResult message, containing a boolean flag. This will be up to you to decide if things were successful or not. We’ll see more examples about that later in this tutorial.

As you use SetParameterResult, you need to import it from “rcl_interfaces.msg”.

And finally, to register the callback, use the add_on_set_parameters_callback(callback) method directly on the node object, using “self”.

Testing – get all modified params and print them

If you want to easily check what you receive in the callback, you can simply print all parameters using:

def parameters_callback(self, params):
    for param in params:
        print(vars(param))
    return SetParametersResult(successful=True)

What you’ll get is an array of rclpy Parameter objects. So, by using vars() on each Parameter you’ll get all the info they contain.

Now, let’s test our callback. Open 2 terminals.

On terminal 1, start the node.

On terminal 2, modify a parameter.

$ ros2 param set /test_params_callback_rclpy battery_percentage_warning 20.3 
Set parameter successful

Here is what you’ll see on terminal 1:

$ ros2 run my_py_pkg test_py_params_callback
{'_type_': <Type.DOUBLE: 3>, '_name': 'battery_percentage_warning', '_value': 20.3}

Great! Now we know what’s inside the parameters array. Here we have modified only one param so we get only one.

In this example we get a Parameter object with those attributes:

  • type_ (pay attention to the additional underscore)
  • name
  • value

With those info you have everything you need to update your class attributes and do some actions.

Update class attributes in callback

You can simply check for each param you’ve declared (using the param’s name). Once you’ve found a match you can update the corresponding class attribute in your program.

def parameters_callback(self, params):
    for param in params:
        if param.name == "battery_percentage_warning":
            self.battery_percentage_warning_ = param.value
    return SetParametersResult(successful=True)

Remove parameters callback

When the node is killed and goes out of scope, the parameters callback is automatically removed.

Now, for any reason, if you want to remove the callback during the execution, you can do so with self.remove_on_set_parameters_callback(self.parameters_callback). After that, if you modify a parameter outside the node, the node won’t be notified anymore.

Process data inside the rclpy callback

Well, once you’ve successfully setup the rclpy parameters callback, then what you do inside it is up to you. For 10 different applications you have 10 different ways of processing the data.

But here I’m going to show you some common use cases, tips, and best practices so you can get an idea of how to best use the callback.

Execute an action

Let’s take a simple example: the camera_device_port. Let’s say you want to switch to another camera from a different port, or you’ve simply unplugged/plugged the camera again and the device name has changed from “/dev/ttyACM0” to “/dev/ttyACM1”.

So, you will modify the parameter’s value, and in the callback, you’ll probably want to restart the camera initialization sequence.

And one important thing: as you are currently inside a callback, it is not a good idea to spend too much time there. So, set a flag inside the callback, and check for that flag in another thread, so you can execute the action and not block the callback thread.

def camera_monitoring_thread(self):
    if self.restart_camera:
        self.get_logger().info("Restarting camera with port: " + str(self.camera_device_port_))
        self.restart_camera = False

def parameters_callback(self, params):
    for param in params:
        if param.name == "camera_device_port":
            self.camera_device_port_ = param.value
            self.restart_camera = True
    return SetParametersResult(successful=True)

Check the parameter’s type

A parameter’s type is actually evaluated after you’ve set the value. If you had a boolean parameter, and you try to assign a string to it, well it will work. And then you’ll probably get an exception in your code later on when you try to use the value.

So how to make sure the parameters you get in the callback have the correct type?

You can easily check the type with the “type_” attribute, and compare it with the type you want from the Parameter object. For example: Parameter.Type.STRING.

Here are all the available types for Parameters:

  • BOOL
  • BOOL_ARRAY
  • BYTE_ARRAY
  • DOUBLE
  • DOUBLE_ARRAY
  • INTEGER
  • INTEGER_ARRAY
  • STRING
  • STRING_ARRAY
  • NOT_SET (declared but undefined)
...
from rclpy.parameter import Parameter
...

def parameters_callback(self, params):
    for param in params:
        if param.name == "battery_percentage_warning":
            if param.type_ in [Parameter.Type.DOUBLE, Parameter.Type.INTEGER]:
                self.battery_percentage_warning_ = param.value
            else:
                return SetParametersResult(successful=False)
    return SetParametersResult(successful=True)

Don’t forget to import the Parameter object in your file.

In this example we’ve decided that we can accept both double and integer numbers for the battery_percentage_warning_ attribute.

And here you can see that if we don’t get a correct type, we return the result “successful=False”. We only return “succcessful=True” if the type matches what we expect.

So, if you open 2 terminals, run the node in terminal 1, and try to change the parameter’s value in terminal 2:

$ ros2 param set /test_params_callback_rclpy battery_percentage_warning 2
Set parameter successful
$ ros2 param set /test_params_callback_rclpy battery_percentage_warning 3.4
Set parameter successful
$ ros2 param set /test_params_callback_rclpy battery_percentage_warning "This is a string, won't work"
Setting parameter failed

As you can see, when we send a value with a different type than integer or double, we get “Setting parameter failed”. In this case, the parameter will not be updated and the previous value remains.

So, as a best practice, always check the type of parameters in your parameters callbacks.

Validate data

Even if you’ve checked the type, the value you receive might not be correct for your application. For example, for the battery_percentage_warning_, you’d expect to get a value between 0 and 100. If you receive 256.8 instead, well, this is still a correct value because the type (double) is accepted.

So, for some of your parameters you might add an additional step, specific to your application.

Here’s an example where we validate the type (and sometimes data) for each parameter we’ve declared.

def parameters_callback(self, params):
    success = False
    for param in params:
        if param.name == "camera_device_port":
            if param.type_ == Parameter.Type.STRING:
                if param.value.startswith('/dev/tty'):
                    success = True
                    self.camera_device_port_ = param.value
                    self.restart_camera = True
        if param.name == "battery_percentage_warning":
            if param.type_ in [Parameter.Type.DOUBLE, Parameter.Type.INTEGER]:
                if param.value >= 0.0 and param.value < 100.0:
                    success = True
                    self.battery_percentage_warning_ = param.value
        if param.name == "simulation_mode":
            if param.type_ == Parameter.Type.BOOL:
                success = True
                self.simulation_mode_ = param.value
    return SetParametersResult(successful=success)

Now, your parameters callback function looks good and you can update your parameters in a safe way.

Conclusion – rclpy parameter callback

Using parameters in ROS2 is a great way to change a node’s configuration at run time.

With the rclpy parameters callback functionality, you can also modify dynamically any parameter while the node is alive, and get notified inside the code.

Make sure to validate both the type and the value from any parameter before you modify a variable or class attribute. Also, if you need to execute an action after a parameter has been updated, do the action in a different thread so the callback can exit quickly.

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