tutorial
ROS

How to Use ROS 2 Parameters

Set up your ROS 2 nodes at startup to tailor their behavior to your specific needs.

tutorial
ROS

In our previous posts, we've talked about how ROS 2 nodes can leverage different ways of communicating with each other. They can use topics to publish continuous communication streams, or use services and actions to make individual requests.

ROS 2 parameters are slightly different from these concepts – rather than being a way for nodes to communicate, they are a way to configure your nodes so that they can have slightly different behaviors when they launch in different contexts.

In this tutorial, we will cover when and why you would use ROS 2 parameters – as well as how you can read and set parameter values using both YAML configuration files and CLI commands.

How ROS 2 parameters work

ROS 2 nodes first declare the parameters they can accept (1), then read the parameter values passed to them during startup – via the command line interface (2) or a YAML configuration file (3) – to determine their behavior. Parameters can be integers, floating point numbers, booleans, string, or arrays of the previous types.

alt_text

By setting different parameter values in different contexts, a node can modify its behavior to work in various scenarios. For example, a node that controls a robot's speed can be configured with different speed limits, depending on whether the robot will be deployed.

When to use ROS 2 parameters

Let’s suppose you have two identical robots in two different warehouses. While their general responsibilities are the same – i.e. locating, loading, and moving inventory – these robots will have different names, move at different speeds, and navigate through different sets of waypoints. By using ROS 2 parameters, you can modify each robot’s internal variables to differentiate their behavior based on their home warehouse.

For this tutorial, let’s assume “RobotA” will be in Warehouse A and go back and forth in a corridor at a max speed of 1.4 m/s. “RobotB” will be in Warehouse B and navigate a more complicated set of waypoints at a max speed of 5.6 m/s.

waypoints

To differentiate how our robots behave, we will define three parameters for them to read at startup – robot_name, max_speed and waypoints.

Creating a node with ROS 2 parameters

Let’s create our node, define its parameters, and read the parameters' values from the command line interface.

Start by creating a new package in your ROS 2 workspace:

$ cd ros2_ws/src
$ ros2 pkg create params_pkg --dependencies rclcpp

language-bash

In the src/ folder of your package, create a new robot_node.cpp file with the following dependencies:

// Standard C++ API for interacting with ROS 2
#include <rclcpp/rclcpp.hpp>
// Useful namespace for durations
using namespace std::chrono_literals;

language-cpp

Declare a new RobotNode class that inherits from Node and contains our parameter values as its private attributes:

class RobotNode : public rclcpp::Node{
private:
 // Declare the node's private attributes
 std::string robot_name_;
 float max_speed_;
 std::vector<std::string> waypoints_;

language-cpp

Next, add a constructor that defines your robot_name, max_speed and waypoints parameters:

public:
 // Initialize class
 RobotNode(const std::string & name)
 :Node(name){
 // Declare parameters
 declare_parameter("robot_name", ""); // defaults to ""
 declare_parameter("max_speed", 0.0); // defaults to 0.0
 declare_parameter("waypoints", rclcpp::PARAMETER_STRING_ARRAY); // no default value

language-cpp

Once the node declares the parameters, it is ready to read them:

// Now, we can read the parameters
get_parameter("robot_name", robot_name_);
get_parameter("max_speed", max_speed_);
get_parameter("waypoints", waypoints_);

language-cpp

Now that we’ve gotten the parameters and stored them in the class attributes, we can now check the values passed:

// Show the robot's attributes loaded with parameters
RCLCPP_INFO(get_logger(),"Hi! I'm '%s'", robot_name_.c_str());
RCLCPP_INFO(get_logger(),"My max speed is %.1f", max_speed_);
RCLCPP_INFO(get_logger(),"I will follow the waypoints: ");

for (unsigned int i = 0; i < waypoints_.size(); i++) {
 RCLCPP_INFO(get_logger(),"%d) %s", i + 1, waypoints_[i].c_str());
}

language-cpp

Add a class destructor to avoid compilation problems:

// Destructor of the node
 ~RobotNode() {
   RCLCPP_INFO(get_logger(), "'%s' says bye!", robot_name_.c_str());
 }
};

language-cpp

Finally, create the main function to execute your node.

int main(int argc, char const *argv[]){
 rclcpp::init(argc, argv);
 auto robot_node = std::make_shared<RobotNode>("robot_node");
 return 0;
}

language-cpp

Modify your CMakeLists.txt file to include your executable and install it in the project’s lib folder:

add_executable(robot_node src/robot_node.cpp)
ament_target_dependencies(robot_node rclcpp)

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

Compile the package with $ colcon build and source your workspace.

Running your executable should give you the following output:

$ ros2 run params_pkg robot_node
 [INFO] [1662052019.811200279] [robot_node]: Hi! I'm ''
 [INFO] [1662052019.811248058] [robot_node]: My max speed is 0.0
 [INFO] [1662052019.811256235] [robot_node]: I will follow the waypoints:
 [INFO] [1662052019.811264074] [robot_node]: '' says bye!

To pass the parameters to the node during startup, we have to add them with the argument --ros-args -p <param>:=<value>. You can pass as many parameters as you like:

$ ros2 run params_pkg robot_node --ros-args -p robot_name:=”RobotA” -p max_speed:=1.0 -p waypoints:=["Home"]
 [INFO] [1662052355.934808595] [robot_node]: Hi! I'm '”RobotA”'
 [INFO] [1662052355.934874889] [robot_node]: My max speed is 1.0
 [INFO] [1662052355.934885245] [robot_node]: I will follow the waypoints:
 [INFO] [1662052355.934889172] [robot_node]: 1) Home
 [INFO] [1662052355.934895189] [robot_node]: '”RobotA”' says bye!

We have successfully configured our node with three parameters!

Setting multiple parameter values with a YAML file

Now let's imagine that we want to pass many more parameters to our node. It may get tiresome passing these values one by one via the CLI. To streamline this process, we can leverage YAML configuration files.

A YAML configuration file contains the parameters and their values in an easy-to-read and -write format. A single YAML file can be used to configure multiple nodes, each with their parameters.

Let’s create a warehouseA.yaml file for our first robot:

/robot_node:
ros__parameters:
robot_name: "RobotA"
max_speed: 1.4
waypoints: ["Home", "Corridor", "Home"]

And a warehouseB.yaml file for our second robot:

/robot_node:
 ros__parameters:
   robot_name: "RobotB"
   max_speed: 5.6
   waypoints: ["Home", "Room 1", "Room 2", "Corridor", "Home"]

Store these YAML files in a newly created params/ folder in your package.

Let’s try running our node with our new warehouseA.yaml file:

$ ros2 run params_pkg robot_node --ros-args --params-file src/ros2_tutorials/params_pkg/params/warehouseA.yaml
 [INFO] [1662053436.492847422] [robot_node]: Hi! I'm 'RobotA'
 [INFO] [1662053436.492900840] [robot_node]: My max speed is 1.4
 [INFO] [1662053436.492913840] [robot_node]: I will follow the waypoints:
 [INFO] [1662053436.492919919] [robot_node]: 1) Home
 [INFO] [1662053436.492926436] [robot_node]: 2) Corridor
 [INFO] [1662053436.492935137] [robot_node]: 3) Home
 [INFO] [1662053436.492944130] [robot_node]: 'RobotA' says bye!

Running it with warehouseB.yaml should give you a slightly different output:

$ ros2 run params_pkg robot_node --ros-args --params-file src/ros2_tutorials/params_pkg/params/warehouseB.yaml
 [INFO] [1662053563.992857830] [robot_node]: Hi! I'm 'RobotB'
 [INFO] [1662053563.992925219] [robot_node]: My max speed is 5.6
 [INFO] [1662053563.992933833] [robot_node]: I will follow the waypoints:
 [INFO] [1662053563.992938301] [robot_node]: 1) Home
 [INFO] [1662053563.992943552] [robot_node]: 2) Room 1
 [INFO] [1662053563.992947848] [robot_node]: 3) Room 2
 [INFO] [1662053563.992951743] [robot_node]: 4) Corridor
 [INFO] [1662053563.992955688] [robot_node]: 5) Home
 [INFO] [1662053563.992960346] [robot_node]: 'RobotB' says bye!

We have successfully passed different parameters to the same node using YAML files! These configuration files make parameters much easier to modify and read.

Using CLI commands

ROS 2 includes useful CLI commands to manage parameters once the nodes have been started. Let’s see some of these commands in action. Start by opening two terminals. In the first terminal, run our robot_node like before:

$ ros2 run params_pkg robot_node --ros-args --params-file src/ros2_tutorials/params_pkg/params/warehouseA.yaml

In the second terminal, get a list of declared parameters:

$ ros2 param list
 /robot_node:
   max_speed
   robot_name
   use_sim_time
   waypoints

Now that we know the parameter names, let’s get the values:

$ ros2 param get /robot_node robot_name
 String value is: RobotA

Get all the parameters and store their values directly in a YAML file:

$ ros2 param dump /robot_node

To change a parameter in a node that is already running, add a timer to your node that checks periodically for a new max_speed parameter value:

class RobotNode : public rclcpp::Node{
private:
 ...

 // Define a timer for periodic check
 rclcpp::TimerBase::SharedPtr timer_;

Then create the timer in the constructor:

 // Initializer of the Class
 RobotNode(const std::string & name)
 :Node(name){
   ...

   // Create a periodic timer of 1 second
   timer_ = create_wall_timer(1s, std::bind(&RobotNode::timerCallback, this));
}

Finally, define a timerCallback to check the parameter and print its new values:

 // Timer function to show the changes in max_speed
 void timerCallback(){
   // Store current max speed
   last_max_speed_ = max_speed_;
   // Get the speed parameter again to check for changes
   get_parameter("max_speed", max_speed_);
   // Print new max speed
   if (max_speed_ != last_max_speed_) {
     RCLCPP_INFO(get_logger(),"My NEW max speed is %.1f", max_speed_);
   }
 }

Don’t forget to spin your node:

int main(int argc, char const *argv[]){
 ...
 rclcpp::spin(robot_node); // Add this line
 return 0;
}

Compile your code, and execute the node:

$ ros2 run params_pkg robot_node --ros-args --params-file src/ros2_tutorials/params_pkg/params/warehouseA.yaml

In another terminal, change the robot's max_speed to 2.0:

$ ros2 param set /robot_node max_speed 2.0

You’ll see that your robot_node will receive the new max_speed and print it in the terminal.

Terminal output

L: Running robot_node with the original parameters. R: Setting a new max_speed with ros2 param.

Using Foxglove to visualize parameters

Use the Parameters panel to visualize all the parameters of the running nodes easily. Remember to use foxglove-bridge for best performance. Install it with sudo apt install ros-$ROS_DISTRO-foxglove-bridge and run it with ros2 launch foxglove_bridge foxglove_bridge_launch.xml.

Summary

ROS 2 parameters make the same node work in different situations, making it possible to reuse your code to add capabilities. We hope this tutorial helped you better understand how you might use parameters in the larger scheme of your robot’s architecture.

For a reference to all the code covered in this post, check out our foxglove/tutorials GitHub repo.

As always, feel free to reach out to the Foxglove team in our Discord community to ask questions, give us feedback, and request a topic for the next tutorial! Also check out additional high-level information about visualizing your ROS data using Foxglove and get started here.

Read more

Start building with Foxglove.

Get started for free