ROS2 YAML For Parameters

In this tutorial you will see how to use YAML to handle your ROS2 parameters.

>> 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!

Why using YAML for ROS2 params

So, you start to write a ROS2 application and as you progress, you add more nodes, more features, more settings. You use ROS2 params in your nodes because that’s a nice way to set parameters at run time, without having to modify (+recompile) the file containing the code for the node.

(If you don’t know how to use params in your code, check out this rclpy params tutorial and this rclcpp params tutorial.)


You want to learn ROS2 efficiently?

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


But now your application has 4 nodes and 150 parameters. Managing parameters is becoming a real problem. Adding them from command line is now not an option anymore. You can add each one of them in a launch file, but that will also take many lines in your launch file, and for each different config you’d have to write different launch files.

You can see here how important it is to have a better system for writing parameters.

Create a YAML file in ROS2

YAML means “YAML Ain’t Markup Language”, which doesn’t really help. Let’s say it’s like JSON or XML, but much more human readable. It’s a great fit for loading a configuration file at run time, which is exactly what ROS2 params are about.

Possible types for YAML params

You can use all the available types for ROS2 params:

  • Boolean value
  • Integer number
  • Float number
  • String
  • Array of all the 4 previous types
  • Array of bytes

Write a YAML config file for a ROS2 node

Let’s write a YAML config file using all the available ROS2 param types.

There is a required minimal structure for ROS2 to know those are parameters to load for a given node.

First you write the name of the node, then “ros__parameters” with one indentation (2 or 4 spaces, recommended: 2), and then you can write the parameters with one more indentation. By adding more indentations you can create nested parameters.

your_amazing_node:
  ros__parameters:
    bool_value: True
    int_number: 5
    float_number: 3.14
    str_text: "Hello Universe"
    bool_array: [True, False, True]
    int_array: [10, 11, 12, 13]
    float_array: [7.5, 400.4]
    str_array: ['Nice', 'more', 'params']
    bytes_array: [0x01, 0xF1, 0xA2]
    nested_param:
      another_int: 7

Important: if the name is not exactly the same as the node name, parameters won’t be loaded, and ROS2 will not display the error. In this case, your node name (which can be different from the executable name) should be “your_amazing_node”.

Note: you can start parameters for multiple nodes in the same file. All you need to do is to write the same structure multiple times.

node_1:
  ros__parameters:
    some_text: "abc"

node_2:
  ros__parameters:
    int_number: 27
    float_param: 45.2

node_3:
  ros__parameters:
    int_number: 45

Where to put your ROS2 YAML config files?

Just before we launch the ROS2 YAML params, let’s see where you should put your files, so everything is correctly setup before we run the code. There is no particular rule as to where you have to put your config files. But here’s a common way to do it (kind of a convention now):

The same as you would put your launch files into a launch/ folder, you can put all your YAML config files into a config/ folder, directly at the root of your package.

Here’s an excerpt of what your package would look like (whether it’s a Python/Cpp package):

your_package/
├── config
│   └── params.yaml
├── launch
│   └── test_params.launch.py
├── package.xml
├── ...

Doing this will help other developers when working with your code, and help you when working with other’s code, because the architecture is the same. Sometimes, developers will use the name “param” for the folder, instead of “config”, but the way to handle YAML files is the same. Of course you can follow your own rules and place YAML files wherever you want, it will still work, but I advise you to follow this convention.

Load a YAML config file for a node

As a ROS2 parameter only exist within a node, we have to create a node first if we want to test our YAML config file. The node by itself doesn’t (and doesn’t need to) know if the parameters where launched from a YAML file.

Here’s a minimal Python node which simply declares all parameters used in this tutorial. You can then see how to make them match with the YAML file. The parameter declaration for a Cpp is the same, just using the rclcpp API.

import rclpy
from rclpy.node import Node

class TestYAMLParams(Node):

    def __init__(self):
        super().__init__('your_amazing_node')
        self.declare_parameters(
            namespace='',
            parameters=[
                ('bool_value', None),
                ('int_number', None),
                ('float_number', None),
                ('str_text', None),
                ('bool_array', None),
                ('int_array', None),
                ('float_array', None),
                ('str_array', None),
                ('bytes_array', None),
                ('nested_param.another_int', None)
            ])

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

if __name__ == '__main__':
    main()

Let’s now load those params!

From command line

This command will start your node with all params from your YAML config file.

$ ros2 run ros2_tutorials test_yaml_params --ros-args --params-file ~/ros2_ws/src/ros2_tutorials/config/params.yaml

Quite simple, isn’t it? Whether you have 1 or 400 params for your node, the command will stay the same.

When running this command by yourself, don’t forget to change the name of the package, name of the executable, and path to your YAML file.

From a launch file

Here’s a minimal ROS2 launch file which just launches one node with params from a YAML file.

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    ld = LaunchDescription()

    config = os.path.join(
        get_package_share_directory('ros2_tutorials'),
        'config',
        'params.yaml'
        )
        
    node=Node(
        package = 'ros2_tutorials',
        name = 'your_amazing_node',
        executable = 'test_yaml_params',
        parameters = [config]
    )

    ld.add_action(node)
    return ld

First we get the path of the YAML config file. In this example the file is expected to be in the “install/ros2_tutorials/share/ros2_tutorials/config/” folder of your ROS2 workspace.

Make sure you installed the YAML file in the right place.

For a Python package, in “setup.py”:

...
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py')),
        (os.path.join('share', package_name, 'config'), glob('config/*.yaml'))
    ],
...

For a Cpp package, in “CMakeLists.txt”:

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

Of course you can install the launch and config files wherever you want, the example above is just a suggestion.

Dump YAML file from existing params

Once you have a node and params launched, you can directly dump those parameters into a YAML file.

It’s a great way to get a global overview of your params for a node, in order to spot potential mistakes.

Also, in the case where you have to deal with an existing node (without an existing YAML config file), you can first run the node with its existing params and dump them into a YAML file. Next time you start your node you can load params directly from this file.

$ ros2 param dump /your_amazing_node
Saving to:  ./your_amazing_node.yaml

You can also print directly the params on the terminal if you want to copy-paste some of them in an existing config file, or look for mistakes.

$ ros2 param dump /your_amazing_node --print
your_amazing_node:
  ros__parameters:
    bool_array:
    - true
    - false
    - true
    bool_value: true
    bytes_array: !!python/object/apply:array.array
    - q
    - - 1
      - 241
      - 162
    float_array: !!python/object/apply:array.array
    - d
    - - 7.5
      - 400.4
    float_number: 3.14
    int_array: !!python/object/apply:array.array
    - q
    - - 10
      - 11
      - 12
      - 13
    int_number: 5
    nested_param:
      another_int: 7
    str_array:
    - Nice
    - more
    - params
    str_text: Hello Universe
    use_sim_time: false

ROS2 YAML params with namespaces

One last thing: let’s see how to handle params from YAML files when you want to put your nodes into namespaces.

We’ll use the same example as before, but this time we want the “your_awesome_node” to be in a “ns1” namespace. A few simple modifications are needed.

YAML config file:

ns1:
  your_amazing_node:
    ros__parameters:
      bool_value: True
      ...

To run node from terminal:

$ ros2 run ros2_tutorials test_yaml_params --ros-args -r __ns:=/ns1 --params-file ~/ros2_ws/src/ros2_tutorials/config/params.yaml

Launch file:

...
    node=Node(
        package = 'ros2_tutorials',
        namespace='ns1',
        name = 'your_amazing_node',
        executable = 'test_yaml_params',
        parameters = [config]
    )
...

And that’s it!

Conclusion on ROS2 YAML

With this tutorial you should have all the basics to launch your ROS2 params from YAML config files.

It’s very likely that you’ll have to use YAML often, either for your own ROS2 projects, or when working on other robots.

This tool will help you organize your project better, and allow you to test many different configurations for a single node in no time.

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