ROS2 Global Parameters [How To]

In this tutorial I will show you how to create a sort of “global parameter server” node to keep ROS2 global parameters for all your other nodes.

The thing is, in ROS2, params are specific to a specific node. You set params for a node, you start the node, and if you kill the node, the params are gone ( if you don’t know how ROS2 params work, first read: how to get/set params from a node with Python and Cpp).

So, what can you do if you want to:

  • Keep some parameters alive for the entire duration of the application,
  • And have parameters that are used by multiple nodes?

Well, there is a way to solve that problem. You create a node that keeps some global parameters. When you start your application, the first thing you do is start this node, which stays alive as long as your application is alive. Then, any node you create at launch time, or at any time after that, can retrieve parameters from this “global parameter server”.

Note that doing this is not necessarily the best solution for your application. It’s actually kind of a hack, and goes in the opposite way of how ROS2 was designed. So, before you do that, be sure there is no other option.

At the end of the tutorials I’ll give some more thoughts about when you should not use this technique, and some more warnings. Please read them if you decide to go with ROS2 global parameters.


You want to learn ROS2 efficiently?

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


Also note that this tutorial provides you with ONE way to do this, it’s not necessarily THE way you should follow. However, it works, so you can get inspired by it and find the best implementation for your own application.

Alright, let’s get started!

Create a ROS2 global parameter server node

Usually it’s a good practice to have a “my_robot_bringup” package which contains different launch files and configurations for your robot. For this tutorial we’ll create the node inside this package.

Here’s the architecture for the package:

my_robot_bringup/
├── CMakeLists.txt
├── package.xml
├── config
│   ├── global_params.yaml
├── include
│   └── my_robot_bringup
├── launch
│   └── my_robot.launch.py
└── src
    └── global_parameter_server_node.cpp

In your ROS2 workspace, execute ros2 pkg create my_robot_bringup to init the package. Then, follow the next points to see how to setup the package.

The parameter server node

Let’s create a node in the src/ folder of “my_robot_bringup” package. The node will be really minimal and simple.

#include "rclcpp/rclcpp.hpp"

class GlobalParameterServer : public rclcpp::Node
{
public:
    GlobalParameterServer() : Node("global_parameter_server",
                                   rclcpp::NodeOptions()
                                       .allow_undeclared_parameters(true)
                                       .automatically_declare_parameters_from_overrides(true)) {}

private:
};

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

As you can see, the node is empty. We just need a node running so we can add some parameters to it, that’s it!

The following code does the same thing, and is even more minimal. In fact, we don’t need to write a class for the node, we can just create a rclcpp::Node object and give it some settings.

#include "rclcpp/rclcpp.hpp"

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    rclcpp::NodeOptions options;
    options.allow_undeclared_parameters(true);
    options.automatically_declare_parameters_from_overrides(true);
    auto node = std::make_shared<rclcpp::Node>("global_parameter_server", options);
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

The only important thing to do here is to add the 2 following flags:

  • allow_undeclared_parameters.
  • automatically_declare_parameters_from_overrides.

This will declare any param we add to this node (through a YAML config file) without having to declare them in the code.

Note that I used Cpp to create the global parameter server node. You could use Python and it would also work. But apart from those few lines of code there is nothing more to add, so even if you are not confident in Cpp you should not have any problem.

ROS2 YAML parameters

Create a config/ folder at the root of your package, and put a YAML config file into it. This file will hold the ROS2 global parameters we want in the application.

global_parameter_server:
  ros__parameters:
    my_global_param: "Test"

For this example we just have one string parameter, named “my_global_param”.

Launch file

Now you can add a launch/ folder. Inside this new folder create a launch file. This will be your “main” launch file, which will start your application.

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

def generate_launch_description():
    ld = LaunchDescription()

    global_parameters = os.path.join(
        get_package_share_directory('my_robot_bringup'),
        'config',
        'global_params.yaml'
    )

    global_param_node = Node(
        package='my_robot_bringup',
        executable='global_parameter_server',
        name='global_parameter_server',
        parameters=[global_parameters]
    )

    ld.add_action(global_param_node)

    return ld

The first thing we add in this launch file is the global parameter node. We load the parameters from the previous YAML file into this node. Everything else should come after.

Configuration

In order to correctly install the node, launch and config files, we have a few things to write into CMakeLists.txt.

...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

add_executable(global_parameter_server src/global_parameter_server_node.cpp)
ament_target_dependencies(global_parameter_server rclcpp)

install(TARGETS
  global_parameter_server
  DESTINATION lib/${PROJECT_NAME}
)

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

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

Basically this will create an executable for the node we wrote, and will install the executable, launch file, and YAML file in the right place.

Also, don’t forget to add <depend>rclcpp</depend> in your package.xml.

Compile and run

Now compile the bringup package containing the global parameter server with colcon build --packages-select my_robot_bringup.

In another terminal, source your environment and start the launch file.

$ ros2 launch my_robot_bringup my_robot.launch.py 
[INFO] [launch]: All log files can be found below /home/ros/.ros/log/2020-04-28-09-34-56-784084-ros-vm-9075
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [global_parameter_server-1]: process started with pid [9086]

You can now see, and get the ROS2 global parameters.

$ ros2 param list
/global_parameter_server:
  my_global_param
  use_sim_time
/launch_ros_9075:
  use_sim_time
$ ros2 param get /global_parameter_server my_global_param 
String value is: Test

Perfect! Now, any node you create will be able to retrieve those params. Just remember to keep this node alive while all other nodes are alive, and that’s it.

Note: the name is important here, every node will have to know the “global_parameter_server” name.

Get a ROS2 global param in your code

Now that your global parameter server is running for your whole application or for a sub-system, you need to know how to get those parameters from your other nodes.

You can’t get them using the classic Node API: functions like get_parameter() in Python or Cpp only work for params defined within the node.

What we’ll do is simply make a call to the service associated with params.

$ ros2 service list
/global_parameter_server/describe_parameters
/global_parameter_server/get_parameter_types
/global_parameter_server/get_parameters # --> this one!
/global_parameter_server/list_parameters
/global_parameter_server/set_parameters
/global_parameter_server/set_parameters_atomically
...

Python

import rclpy
from rclpy.node import Node
from rcl_interfaces.srv import GetParameters

class TestGetGlobalParam(Node):

    def callback_global_param(self, future):
        try:
            result = future.result()
        except Exception as e:
            self.get_logger().warn("service call failed %r" % (e,))
        else:
            param = result.values[0]
            self.get_logger().info("Got global param: %s" % (param.string_value,))

    def __init__(self):
        super().__init__("test_get_global_param")

        self.client = self.create_client(GetParameters,
                                         '/global_parameter_server/get_parameters')

        request = GetParameters.Request()
        request.names = ['my_global_param']

        self.client.wait_for_service()

        future = self.client.call_async(request)
        future.add_done_callback(self.callback_global_param)

This is a standard Python service call using an async call and futures. You send a list of names for the params you want, and in return you get a list of values for those params.

Cpp

#include "rclcpp/rclcpp.hpp"

class TestGetGlobalParam : public rclcpp::Node
{
public:
    TestGetGlobalParam() : Node("test_get_global_param")
    {
        parameters_client = 
            std::make_shared<rclcpp::AsyncParametersClient>(this, "/global_parameter_server");
        parameters_client->wait_for_service();

        auto parameters_future = parameters_client->get_parameters(
            {"my_global_param"},
            std::bind(&TestGetGlobalParam::callbackGlobalParam, this, std::placeholders::_1));
    }

    void callbackGlobalParam(std::shared_future<std::vector<rclcpp::Parameter>> future)
    {
        auto result = future.get();
        auto param = result.at(0);
        RCLCPP_INFO(this->get_logger(), "Got global param: %s", param.as_string().c_str());
    }

private:
    std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client;
};

For Cpp you can use either a service call, or directly the AsyncParametersClient helper, which is a wrapper around parameter services.

Now it’s complete: you have one global parameter server node, and you’re able to get those global params from your other nodes.

Add a namespace to make your ROS2 global params less… global

If your application is quite small or has only one robot for example, you might be fine with having real global parameters. But otherwise it could be better to add a little bit more scope to them.

So, they don’t become global to the entire application, but global to a subpart, a system. If you have 2 robots with namespaces /robot1 and /robot2, then you might want to have a different set of “global” parameters for each robot.

Let’s make a quick test.

In the config/ folder, create 2 files:

robot1_global_params.yaml.

robot1:
  global_parameter_server:
    ros__parameters:
      my_global_param: "Hello from robot1"

robot2_global_params.yaml.

robot2:
  global_parameter_server:
    ros__parameters:
      my_global_param: "Hello from robot2"

The launch file becomes:

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

def generate_launch_description():
    ld = LaunchDescription()

    robot1_global_parameters = os.path.join(
        get_package_share_directory('my_robot_bringup'),
        'config',
        'robot1_global_params.yaml'
    )

    robot2_global_parameters = os.path.join(
        get_package_share_directory('my_robot_bringup'),
        'config',
        'robot2_global_params.yaml'
    )

    global_param_node_robot1 = Node(
        node_namespace='/robot1',
        package='my_robot_bringup',
        executable='global_parameter_server',
        name='global_parameter_server',
        parameters=[robot1_global_parameters]
    )

    global_param_node_robot2 = Node(
        node_namespace='/robot2',
        package='my_robot_bringup',
        executable='global_parameter_server',
        name='global_parameter_server',
        parameters=[robot2_global_parameters]
    )

    ld.add_action(global_param_node_robot1)
    ld.add_action(global_param_node_robot2)

    return ld

As you can see here, the first node is inside the /robot1 namespace. It’s important that associated params in the YAML file are also under /robot1. The namespace name needs to match exactly. Same applies to /robot2.

Now, compile your package again, and start your launch file.

In another terminal, you can check the params.

$ ros2 param list
/robot1/global_parameter_server:
  my_global_param
  use_sim_time
/robot2/global_parameter_server:
  my_global_param
  use_sim_time
/launch_ros_9250:
  use_sim_time
$ ros2 param get /robot1/global_parameter_server my_global_param 
String value is: Hello from robot1
$ ros2 param get /robot2/global_parameter_server my_global_param 
String value is: Hello from robot2

Alright, with this setup you have a global param for the /robot1 namespace, and another global param – same name, different value – for the /robot2 namespace. This is just an example of what you can do. There is an infinite number of possibilities, and it all comes down to what you really need in your application.

ROS2 global parameters: good idea or not?

If you’re starting your ROS2 application and directly implement a global parameter server, well, stop right now and think twice.

There are many debates on what’s the best way to handle “global” parameters, and one of the question you should ask first is not “how to do” but “do I need to do that for my application?”.

ROS2, by design, and for good reasons, makes you create parameters that are specific to a node. Unless you’re a true ROS expert, it might be good to try to follow the framework rules and conventions.

Here are some alternatives:

  • If that’s possible for you, you could create a variable on top of your launch file, and pass it to all of your nodes as a parameter. Thus, all nodes (at launch time) will get this parameter. However, if you manually add another node after that, it won’t be able to retrieve the parameter from a “global” source.
  • Some robots, like the turtlebot3, uses an environment variable for the robot’s name. Not necessarily what you should do, but that’s an option.
  • Instead of a global parameter node, you could have a database (for example with sqlite) containing global values.

Also, it could be interesting to look at your design choices. Maybe you have to create global parameters because of a poorly designed application. In this case it’s maybe better to work on your design instead of finding little hacks to make things work.

If you have carefully examined the situation, and there is no other way than to create a global parameter server, then try to reduce the scope. If the parameters only apply to a sub-system, then don’t make them global to your application. Every application is different, so adapt this technique every time you need to use it. This is not a “one size fits all” solution.

All in all, the most important thing is that your robot works correctly, and that you keep your code modular enough, so you can scale your application later without too much hassle. If you manage to do that, with our without global parameters, well, that’s a job well done!

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