rclpy Params Tutorial – Get and Set ROS2 Params with Python

In this rclpy params tutorial you’ll learn how to get and set ROS2 params with rclpy, inside a Python node.

ROS2 params allow you to provide configuration for a node at run time. All params specified for a node are specific to this node and only exist while the node is alive.

It’s very useful, you can start your node with different settings each time, without having to change your Python code.

(For the same params tutorial with Cpp, checkout the rclcpp params tutorial)

Let’s get started!

Setup code and declare ROS2 params with rclpy

First things first: you have to declare every ROS2 param you’ll use in your node. Usually this is one of the first thing you do in the node’s constructor.


You want to learn ROS2 efficiently?

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


It’s important: if you don’t declare a parameter in your node’s code, you will get an error when you try to get or set it (ParameterNotDeclaredException exception).

Declaring a parameter does not mean you set a value, it just means that this parameter exists.

Declare params with rclpy

Here’s a minimal ROS2 Python node which declares 3 parameters (with no default value, we’ll see later how to do that):

import rclpy
from rclpy.node import Node

class TestParams(Node):

    def __init__(self):
        super().__init__('test_params_rclpy')

        self.declare_parameter('my_str', rclpy.Parameter.Type.STRING)
        self.declare_parameter('my_int', rclpy.Parameter.Type.INTEGER)
        self.declare_parameter('my_double_array', rclpy.Parameter.Type.DOUBLE_ARRAY)

# The following is just to start the node
def main(args=None):
    rclpy.init(args=args)
    node = TestParams()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

Note: you also need to provide either a default value (more on that later), or the type for each parameter. If you have autocompletion, you can easily find the available types by writing first “rclpy.Parameter.Type”.

You can also declare multiple parameters at once.

def __init__(self):
    super().__init__('test_params_rclpy')

    self.declare_parameters(
        namespace='',
        parameters=[
            ('my_str', rclpy.Parameter.Type.STRING),
            ('my_int', rclpy.Parameter.Type.INTEGER),
            ('my_double_array', rclpy.Parameter.Type.DOUBLE_ARRAY)
        ]
    )

And, if you ever need to, at any moment you can also undeclare a parameter: self.undeclare_parameter('my_str').

Run your node without params

Let’s see what happens when you simply run this node without setting any parameter value:

$ ros2 run ros2_tutorials test_params_rclpy

In another terminal, run:

$ ros2 param list
/test_params_rclpy:
  my_double_array
  my_int
  my_str
  use_sim_time

As you can see the node “test_params_rclpy” now contains 3 ROS2 params – in addition to the “use_sim_time” param, automatically created for each node.

Those parameters are just declared, they are not set yet. If you try to get one from the terminal – with “ros2 param get”, you’ll get an exception like this in your node:

rclpy.exceptions.ParameterUninitializedException: The parameter 'my_str' is not initialized

This can be avoided if you set some default values (see more on that later), or if you specify the params values when you run the node.

Run your node with params

Let’s add parameters when we start the node with ros2 run:

$ ros2 run ros2_tutorials test_params_rclpy --ros-args -p my_str:="Hello world" -p my_int:=5 -p my_double_array:="[4.4, 5.5, 6.6]"

The names of params must be identical to the ones we declared in the node’s code.

You can also use a ROS2 launch file instead of adding all your params manually in the terminal (additional improvement: you can also set all your params in a YAML config file).

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='ros2_tutorials',
            executable='test_params_rclpy',
            parameters=[
                {'my_str': 'Hello world'},
                {'my_int': 5},
                {'my_double_array': [4.4, 5.5, 6.6]}
            ],
            output='screen',
            emulate_tty=True
        )
    ])

And here’s the result you should get after starting the node:

$ ros2 param get /test_params_rclpy my_str
String value is: Hello world

So, what happened? The node starts and declares a parameter named “my_str” in its constructor. When launching the node, you also give a value for the “my_str” parameter. As the parameter is declared, the value is set.

To insist on the importance of declaring your ROS2 params, let’s run the node with a parameter which was not declared before.

$ ros2 run ros2_tutorials test_params_rclpy --ros-args -p my_other_str:="Guess it won't work"

In another terminal:

$ ros2 param list
/test_params_rclpy:
  my_double_array
  my_int
  my_str
  use_sim_time
$ ros2 param get /test_params_rclpy my_other_str
Parameter not set.

The “my_other_str” param does not appear in the list!

If you’ve already started to experiment with ROS2 parameters and wondered why your parameters don’t appear, well this is probably because you didn’t declare them.

Get params with rclpy

Now that you’ve declared parameters in your code, let’s retrieve them in the node’s code!

Get params one by one

def __init__(self):
    super().__init__('test_params_rclpy')

    self.declare_parameter('my_str', rclpy.Parameter.Type.STRING) 
    self.declare_parameter('my_int', rclpy.Parameter.Type.INTEGER)    
    self.declare_parameter('my_double_array', rclpy.Parameter.Type.DOUBLE_ARRAY)

    param_str = self.get_parameter('my_str')
    param_int = self.get_parameter('my_int')
    param_double_array = self.get_parameter('my_double_array')

    self.get_logger().info("str: %s, int: %s, double[]: %s" %
                           (str(param_str.value),
                            str(param_int.value),
                            str(param_double_array.value),))

Use the get_parameter(name) method to get the value for one declared parameter. In fact, this method won’t return the value, it will return a Parameter object. The value is stored in the “value” attribute of the Parameter, as you can see when we print the params with the rclpy logger.

$ ros2 run ros2_tutorials test_params_rclpy --ros-args -p my_str:="Hello world" -p my_int:=5 -p my_double_array:="[4.4, 5.5, 6.6]"
[INFO] [test_params_rclpy]: str: Hello world, int: 5, double[]: [4.4, 5.5, 6.6]

Get multiple params at once

You can also get all your parameters with get_parameters(List[name]).

...
(param_str, param_int, param_double_array) = self.get_parameters(
            ['my_str', 'my_int', 'my_double_array'])
...

Set default values

You may want to set default values for parameters which were not set when you start your node.

...        
self.declare_parameter('my_str', 'default value')
self.declare_parameter('my_int', 7)
self.declare_parameter('my_double_array', [1.1, 2.2])
...

Or all at once:

...
self.declare_parameters(
    namespace='',
    parameters=[
        ('my_str', "default value"),
        ('my_int', 7),
        ('my_double_array', [1.1, 2.2])
    ]
)
...

When you start your node:

$ ros2 run ros2_tutorials test_params_rclpy --ros-args -p my_int:=5
[INFO] [test_params_rclpy]: str: default value, int: 5, double[]: [1.1, 2.2]

Here we only set the “my_int” parameter to 5. The default value (7) is not used.

For the 2 other parameters (“my_str” and “my_double_array”), as we did not specify any value, then they take the default value.

Again, if you forget to declare a parameter

Let’s say you forgot to declare the “my_str” parameter and then try to access it (for reading or writing).

def __init__(self):
    super().__init__('test_params_rclpy')
    
    # self.declare_parameter('my_str') --> not declared!

    param_str = self.get_parameter('my_str')

As soon as you start your node – even if you specify a parameter value for “my_str”, you’ll get an ParameterNotDeclaredException error.

$ start node
...
    raise ParameterNotDeclaredException(name)
rclpy.exceptions.ParameterNotDeclaredException: ('Invalid access to undeclared parameter(s)', 'my_str')

So:

  • Any parameter not declared within a node won’t appear in the parameter list, and won’t be available.
  • Any time you try to access a parameter in your code without declaring it first, you’ll get an error.

Set params with rclpy

If you just want to set a parameter’s value in case it is not specified when you start the node, then prefer using a default value (as you saw before in this tutorial).

However, if you want to impose a parameter’s value from your code, you can use the set_parameters(List[Parameters]) method. If the parameter’s value was already set before, it will be overridden.

from rclpy.parameter import Parameter
...

def __init__(self):
    super().__init__('test_params_rclpy')

    self.declare_parameter('my_str', rclpy.Parameter.Type.STRING) 
    self.declare_parameter('my_int', rclpy.Parameter.Type.INTEGER) 
    self.declare_parameter('my_double_array', rclpy.Parameter.Type.DOUBLE_ARRAY)

    param_str = Parameter('my_str', Parameter.Type.STRING, 'Set from code')
    param_int = Parameter('my_int', Parameter.Type.INTEGER, 12)
    param_double_array = Parameter('my_double_array', Parameter.Type.DOUBLE_ARRAY, [1.1, 2.2])

    self.set_parameters([param_str, param_int, param_double_array])

A Parameter object takes 3 arguments: name, type, and value. Don’t forget to add the dependency for the Parameter class.

If you start this node, and get each parameter in another window with ros2 param get, you’ll see the values set in the code.

$ ros2 param get /test_params_rclpy my_str
String value is: Set from code

Here’s what happens with the “my_str” parameter:

  • First it is declared in the code, so it can be set.
  • When you start the node, either you provide a value for “my_str”, or the default value will be used.
  • But, then “my_str” is set from the code, and the new value replaces any previous value.

Allow undeclared params with rclpy

Well, well, well.

After everything I told you about the errors due to undeclared parameters, I’m now about to tell you how to allow them.

The default way to work with parameters is to first declare them, then use them.

However, there is one case where this could lead to a problem: if, for some reasons, your node is not aware of all parameters it should have when it is started.

Here’s how to do.

def __init__(self):
    super().__init__('test_params_rclpy',
                     allow_undeclared_parameters=True,
                     automatically_declare_parameters_from_overrides=True)

    param_str = self.get_parameter_or(
        'my_str', Parameter('str', Parameter.Type.STRING, 'Is there anybody out there?'))
    param_int = self.get_parameter_or(
        'my_int', Parameter('abc', Parameter.Type.INTEGER, 8))
    param_double_array = self.get_parameter_or(
        'my_double_array', Parameter('def', Parameter.Type.DOUBLE_ARRAY, [1.1, 2.2]))

    self.get_logger().info("Params: %s, %s, %s" %
                           (str(param_int.value),
                            str(param_str.value),
                            str(param_double_array.value),))

You have to add 2 arguments to the node you’re creating:

  • allow_undeclared_parameters.
  • automatically_declare_parameters_from_overrides.

Basically, when you set a parameter from outside the node, the parameter will be declared for this node, even if you didn’t declare it within the node.

Then you can use the get_parameter_or(name, Parameter) method. This method will check if the parameter is declared. If yes, the parameter is retrieved. If not, you can specify a default parameter. It’s probably a best practice to always set default parameters when doing this.

Let’s run this node with a non declared parameter:

$ ros2 run ros2_tutorials test_params_rclpy --ros-args -p this_is_a_non_declared_param:="This will work"
[INFO] [test_params_rclpy]: Params: 8, Is there anybody out there?, [1.1, 2.2]

# In another terminal:
$ ros2 param list
/test_params_rclpy:
  this_is_a_non_declared_param
  use_sim_time
$ ros2 param get /test_params_rclpy this_is_a_non_declared_param 
String value is: This will work

2 things here:

  • The new parameter we set from command line appears in the list, which means it has been automatically declared. Also it’s value is set.
  • The 3 parameters we’re trying to get from the code are not declared anywhere (from within our outside the node), so we get the default value.

To conclude on that: as a general rule, always declare your parameters first, and follow the ROS2 way of doing things. Only allow undeclared parameters for a good reason.

rclpy parameter callback

A great thing about ROS2 params, is that you can modify them at any time. And there is a simple way to notify your node when a param is modified.

You can add a callback with add_on_set_parameters_callback(function) that will be called every time a parameter’s value has been changed from the outside.

(For ROS1 users, this is the same mechanism as dynamic_reconfigure in ROS1, but here it’s directly implemented inside nodes, and much simpler to setup)

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

class TestParams(Node):

    def parameter_callback(self, params):
        for param in params:
            if param.name == 'my_str' and param.type_ == Parameter.Type.STRING:
                self.my_str = param.value
        return SetParametersResult(successful=True)

    def __init__(self):
        super().__init__('test_params_rclpy')

        self.declare_parameter('my_str', 'default value')
        self.my_str = self.get_parameter('my_str').value
        self.get_logger().info("New value set: %s" % self.my_str)
        self.add_on_set_parameters_callback(self.parameter_callback)

What you do inside the callback is up to you and depends on your application (to go further on this, check out this more complete rclpy parameter callback tutorial). You may wish to store the new parameter’s value, change a behavior in your node, or simply ignore all changes.

Going further with ROS2 params

In this tutorial you have learned how to get and set parameters from a Python node, using rclpy. You saw the importance of declaring parameters.

Now, if you want to go further with ROS2 params:

Also, one thing you could wish to do, is to have some parameters globally available to all nodes. As you know, ROS2 parameters are specific to a node and only exist with this node. If you want to set a parameter shared by multiple nodes, one way you could achieve that is to create a dedicated node only for global params. You’d launch this node first, and always keep it alive so other nodes can retrieve parameters (and get notified) from it.

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