Dynamic Reconfigure

Change parameters on the fly during runtime with the help of dynamic_reconfigure and never ever restart your whole setup to tune your hardcoded parameters. We left dynamic_reconfigure behind, when we migrated to ROS2. ROS2 has built-in support for reconfigurable parameters.

What’s left is the rqt plugin which still is named dynamic_reconfigure. When we mention dynamic_reconfigure we either refer to this plugin or we refer to the mechanism of reconfiguring parameters during the runtime of the node.

Prerequisites

  • a ROS package for which you want to use dynamic_reconfigure and implement reconfigurable ROS parameters.

Attention

In this example this package will be called awesome_package. Replace occurences of this package name with your own package name. Do not copy-paste.

See also

You are not quite sure what the necessary steps to create a new package are? Go back to ROS Package.

Scenario

Imagine we have something like a PID-Controller (yeah, we thought it would be nice to have very applied example, i.e. it is very close to what you want to achieve yourself during this course) and we want to change the gains and maybe some other parameters as well while the node is running. Things we would like to configure could be:

  • PID gains

  • limits for the integral term (there are many more anti-windup strategies. Use your preferred search engine for some inspiration.)

  • Activate/Deactivate the integrator so the integrator is not accumulating control errors while the controller is not active.

Preparation

We create a PID controller node called my_controller.py.

Make it exectubale.

$ chmod +x ~/fav/ros2/src/awesome_package/nodes/my_controller.py

Add the node the list of nodes to install in the CMakeLists.txt.

1install(PROGRAMS
2  ...
3  nodes/some_other_node_that_might_also_be_in_this_list.py
4  nodes/setpoint_publisher.py
5  ...
6  DESTINATION lib/${PROJECT_NAME}
7)

Build the workspace. Keep in mind this is only necessary because we changed something in CMakeLists.txt. No rebuilt is required if we only modify an already existing node. Python code does not get compiled.

$ build_ros

See also

See Run A Node for more elaborate instructions for creating a node.

Write the Code

Boilerplate

Starting from a basic node setup:

my_controller.py
 1#!/usr/bin/env python3
 2
 3import rclpy
 4from rclpy.node import Node
 5
 6
 7class MyControlNode(Node):
 8
 9    def __init__(self):
10        super().__init__(node_name='my_controller')
11
12
13def main():
14    rclpy.init()
15    node = MyControlNode()
16    try:
17        rclpy.spin(node)
18    except KeyboardInterrupt:
19        pass
20
21
22if __name__ == '__main__':
23    main()

Note

Wondering what the try statement is good for? When hitting Ctrl + C, a keyboard interrupt is triggered. If unhandled this will cause annoying exceptions to be printed in the terminal, even though nothing bad happened. Hence the except KeyboardInterrupt will catch this exceptions. The pass keyboard instructs the python interpreter to do nothing.

In this example we won’t implement a PID controller. The node will only store the configuration parameters in variables and print them for demonstration purpose.

Declare Parameters

So let’s start with the parameters. We declare them but do not set default values. That is a choice we are making. This way we can make sure, that the values have to be provided when starting the node.

 1#!/usr/bin/env python3
 2
 3import rclpy
 4from hippo_msgs.msg import Float64Stamped
 5from rclpy.node import Node
 6
 7
 8class MyControlNode(Node):
 9
10    def __init__(self):
11        super().__init__(node_name='my_controller')
12        self.init_params()
13
14    def init_params(self):
15        self.declare_parameters(
16            namespace='',
17            parameters=[
18                ('gains.p', rclpy.Parameter.Type.DOUBLE),
19                ('gains.i', rclpy.Parameter.Type.DOUBLE),
20                ('gains.d', rclpy.Parameter.Type.DOUBLE),
21            ],
22        )
23        # the calls to get_parameter will raise an exception if the paramter
24        # value is not provided when the node is started.
25        param = self.get_parameter('gains.p')
26        self.get_logger().info(f'{param.name}={param.value}')
27        self.p_gain = param.value
28
29        param = self.get_parameter('gains.i')
30        self.get_logger().info(f'{param.name}={param.value}')
31        self.i_gain = param.value
32
33        param = self.get_parameter('gains.d')
34        self.get_logger().info(f'{param.name}={param.value}')
35        self.d_gain = param.value
36
37
38def main():
39    rclpy.init()
40    node = MyControlNode()
41    try:
42        rclpy.spin(node)
43    except KeyboardInterrupt:
44        pass
45
46
47if __name__ == '__main__':
48    main()

If we now run the node with

$ ros2 run awesome_package my_controller.py

an exception will be raised.

rclpy.exceptions.ParameterUninitializedException: The parameter 'gains.p' is not initialized
[ros2run]: Process exited with failure 1

This was to be expected. To test our node before we integrate it in a launch file setup, we can pass the arguments in the terminal with --ros-args and -p.

$ ros2 run awesome_package my_controller.py --ros-args -p gains.p:=1.0 -p gains.i:=0.01 -p gains.d:=0.0

No exception is raised! And the logs reflect our manually set parameter values 🥳.

Note

We will set these parameters in a more convenient way later on when we create a launch file setup.

We can see the parameters while the node is running

$ ros2 param list

yielding

$ ros2 param list
/my_controller:
  gains.d
  gains.i
  gains.p
  start_type_description_service
  use_sim_time

Get a parameter value

$ ros2 param get /my_controller gains.p
Double value is: 1.0

Hint

For almost any command you can run my_command --help to get information on how to use the command. This is also true for ros2 param, ros2 param get, ros2 param set, etc.

For example

$ ros2 param get --help

Use this kind of help. This way you can figure out yourself how to use all these tools without relying on other people’s tutorials.

We can also set the parameter value, for example

$ ros2 param set /my_controller gains.p 3.0

But currently our node does not handle these changes of the parameters.

Handle Parameter Changes

 1#!/usr/bin/env python3
 2
 3import rclpy
 4from hippo_msgs.msg import Float64Stamped
 5from rclpy.node import Node
 6from rcl_interfaces.msg import SetParametersResult
 7
 8
 9class MyControlNode(Node):
10
11    def __init__(self):
12        super().__init__(node_name='my_controller')
13        self.init_params()
14
15    def init_params(self):
16        self.declare_parameters(
17            namespace='',
18            parameters=[
19                ('gains.p', rclpy.Parameter.Type.DOUBLE),
20                ('gains.i', rclpy.Parameter.Type.DOUBLE),
21                ('gains.d', rclpy.Parameter.Type.DOUBLE),
22            ],
23        )
24        # the calls to get_parameter will raise an exception if the paramter
25        # value is not provided when the node is started.
26        param = self.get_parameter('gains.p')
27        self.get_logger().info(f'{param.name}={param.value}')
28        self.p_gain = param.value
29
30        param = self.get_parameter('gains.i')
31        self.get_logger().info(f'{param.name}={param.value}')
32        self.i_gain = param.value
33
34        param = self.get_parameter('gains.d')
35        self.get_logger().info(f'{param.name}={param.value}')
36        self.d_gain = param.value
37
38        self.add_on_set_parameters_callback(self.on_params_changed)
39
40    def on_params_changed(self, params):
41        param: rclpy.Parameter
42        for param in params:
43            self.get_logger().info(f'Try to set [{param.name}] = {param.value}')
44            if param.name == 'gains.p':
45                self.p_gain = param.value
46            elif param.name == 'gains.i':
47                self.i_gain = param.value
48            elif param.name == 'gains.d':
49                self.d_gain = param.value
50            else:
51                continue
52        return SetParametersResult(successful=True, reason='Parameter set')
53
54
55def main():
56    rclpy.init()
57    node = MyControlNode()
58    try:
59        rclpy.spin(node)
60    except KeyboardInterrupt:
61        pass
62
63
64if __name__ == '__main__':
65    main()

Try setting different values for the declared parameters with ros2 param set as explained above. Verify that the logs of the node should reflect the parameter changes.

Use Paramter Files

Parameter files can exist at arbitrary paths. It is common practice to have the default parameters in a config directory inside our package. We create it for this tutorial package with

$ mkdir ~/fav/ros2/src/awesome_package/config

and create a controller_params.yaml file to store the parameters.

The content of the file is

controller_params.yaml
/**: # wildcard for the node name
  ros__parameters:
    gains:
      p: 1.0
      i: 0.0
      d: 0.0

Make sure to tell the build system about your config directory. We do this by making sure your CMakeLists.txt of our package contains the following lines:

install(
  DIRECTORY launch config
  DESTINATION share/${PROJECT_NAME}
)

Note

Not sure what the launch entry does? Please read our guide on how to write a launch setup.

After we have done this, we need to rebuild our workspace to install the newly added config directory and the corresponding config file.

$ build_ros

An example showing you how to load this parameter file during your launch setup is shown below. Lines corresponding to the loading of the parameters are highlighted.

 1from ament_index_python.packages import get_package_share_path
 2from launch_ros.actions import Node, PushRosNamespace
 3
 4from launch import LaunchDescription
 5from launch.actions import (
 6    DeclareLaunchArgument,
 7    GroupAction,
 8)
 9from launch.substitutions import LaunchConfiguration
10
11
12def generate_launch_description() -> LaunchDescription:
13    launch_description = LaunchDescription()
14
15    # we ALWAYS use this argument as namespace
16    arg = DeclareLaunchArgument('vehicle_name')
17    launch_description.add_action(arg)
18
19    package_path = get_package_share_path('awesome_package')
20    param_file_path = str(package_path / 'config/controller_params.yaml')
21    # expose the parameter to the launch command line
22    param_file_arg = DeclareLaunchArgument('controller_config_file',
23                                           default_value=param_file_path)
24    launch_description.add_action(param_file_arg)
25
26    node = Node(executable='my_controller.py',
27                package='awesome_package',
28                parameters=[
29                    LaunchConfiguration('controller_config_file'),
30                ])
31    group = GroupAction([
32        PushRosNamespace(LaunchConfiguration('vehicle_name')),
33        node,
34    ])
35    launch_description.add_action(group)
36
37    return launch_description

We have added a new file! Hence, we rebuild our workspace with build_ros 🥳.

A default parameter file is chosen in line 20. If we run our setup with

$ ros2 launch awesome_package controller.launch.py vehicle_name:=bluerov00

we can tell by the logging output, that our parameters have been loaded from the parameter file:

[INFO] [my_controller.py-1]: process started with pid [11493]
[my_controller.py-1] [INFO] [bluerov00.my_controller]: gains.p=1.0
[my_controller.py-1] [INFO] [bluerov00.my_controller]: gains.i=0.0
[my_controller.py-1] [INFO] [bluerov00.my_controller]: gains.d=0.0

We can test several values for our gains, by editing the controller_params.yaml file. From now on no rebuilt of our workspace is required, since we do not add directories or files to our package. The modification of our files does not require a rebuilt.

Use rqt to Change Parameters

Run

$ rqt

and open the dynamic_reconfigure plugin as shown below

../_images/dyn_rqt_plugin_open.png

This way to change parameter values might be less tedious than doing it via the command line.