How to manipulate parameters at runtime | ROS2 Humble Python Tutorial
What you will learn:
How to manipulate multiple parameters in ROS2 from the command line using parameter services
Overview
Parameters in ROS 2 can be get, set, listed, and described through a set of services for nodes that are already running. In fact, the well-known and convenient ros2 param
command-line tool is a wrapper around these service calls that makes it easy to manipulate parameters from the command-line.
In this tutorial, you will learn how to manipulate multiple parameters in ROS2 from the command line using parameter services rather than ros2 param
commands which can only work with one parameter at a time. You will get an introduction to using all of the parameter services via the CLI, not just SetParameters
:
srv/GetParameterTypes
srv/DescribeParameters
srv/SetParametersAtomically
srv/GetParameters
srv/ListParameters
srv/SetParameters
Prerequisite:
- Basic understanding of parameters
- Familiarity with using the
ros2 param
command-line tool - Basic knowledge of services
If you want to learn more advanced ROS 2 topics, including parameters and more, in a practical, hands-on way, check out the course Intermediate ROS 2: https://app.theconstruct.ai/courses/113
Opening the rosject
In order to follow this tutorial, we need to have ROS2 installed in our system, and ideally a ros2_ws (ROS2 Workspace). To make your life easier, we have already prepared a rosject for that: https://app.theconstruct.ai/l/6111a6de/
Just by copying the rosject (clicking the link above), you will have a setup already prepared for you.
After the rosject has been successfully copied to your own area, you should see a Run button. Just click that button to launch the rosject.
After pressing the Run button, you should have the rosject loaded. Now, let’s head to the next section to get some real practice.
In order to interact with ROS2, we need a terminal.
Let’s open a terminal by clicking the Open a new terminal button.
Create a ROS2 python package with a simple node that has two parameters
Create a python package called python_parameters
:
cd ~/ros2_ws/src/ ros2 pkg create --build-type ament_python python_parameters --dependencies rclpy
Create a python node called python_parameters_node.py
:
touch python_parameters/python_parameters/python_parameters_node.py
Here is a simple node with two parameters of type string (to paste in python_parameters_node.py
):
- The parameters are:
my_parameter
with valueme
and descriptionThis parameter is mine!
your_parameter
with valueyou
and descriptionThis parameter is yours!
You can also have other types as listed in the documentation.
- The node has a timer callback with a period of 1 second just to log what the current parameters are.
import rclpy import rclpy.node from rcl_interfaces.msg import ParameterDescriptor class MinimalParam(rclpy.node.Node): def __init__(self): super().__init__('minimal_param_node') my_parameter_descriptor = ParameterDescriptor(description='This parameter is mine!') self.declare_parameter('my_parameter', 'me', my_parameter_descriptor) your_parameter_descriptor = ParameterDescriptor(description='This parameter is yours!') self.declare_parameter('your_parameter', 'you', your_parameter_descriptor) self.timer = self.create_timer(1, self.timer_callback) def timer_callback(self): my_param = self.get_parameter('my_parameter').get_parameter_value().string_value self.get_logger().info('I am %s!' % my_param) your_param = self.get_parameter('your_parameter').get_parameter_value().string_value self.get_logger().info('You are %s!' % your_param) def main(): rclpy.init() node = MinimalParam() rclpy.spin(node) if __name__ == '__main__': main()
Configure the package and test
Modify setup.py
State the entry point:
entry_points={ 'console_scripts': [ 'minimal_param_node = python_parameters.python_parameters_node:main', ], },
Compile the package
cd ~/ros2_ws/ colcon build --packages-select python_parameters
Run the node
In one terminal, start the node:
source ~/ros2_ws/install/setup.bash ros2 run python_parameters minimal_param_node
You should get something like this:
[INFO] [1713695285.349594469] [minimal_param_node]: I am me! [INFO] [1713695285.349875641] [minimal_param_node]: You are you! [INFO] [1713695286.337758113] [minimal_param_node]: I am me! [INFO] [1713695286.338776447] [minimal_param_node]: You are you! [INFO] [1713695287.337323765] [minimal_param_node]: I am me! [INFO] [1713695287.338010397] [minimal_param_node]: You are you!
Setting a parameter using ros2 param set
In a different terminal, get a list of all parameters:
ros2 param list
You should see both my_parameter
and your_parameter
in the output:
/minimal_param_node: my_parameter use_sim_time your_parameter
The usual way to set parameters dynamically during runtime is to use the ros2 param set
. For example we can modify the value of your_parameter
to be 'a student'
:
ros2 param set /minimal_param_node your_parameter 'a student'
You can see that the value of your_parameter
has changed:
[INFO] [1713695285.349594469] [minimal_param_node]: I am me! [INFO] [1713695285.349875641] [minimal_param_node]: You are a student! [INFO] [1713695286.337758113] [minimal_param_node]: I am me! [INFO] [1713695286.338776447] [minimal_param_node]: You are a student! [INFO] [1713695287.337323765] [minimal_param_node]: I am me! [INFO] [1713695287.338010397] [minimal_param_node]: You are a student!
However if you want to set multiple parameters at once, you need to use the SetParameters
service as shown in the following section.
Setting multiple parameters using SetParameters
service type
Kill and restart the node to reset the parameter values before continuing onto this section.
Begin by listing all active services along with their types:
ros2 service list -t
You should see 6 services including the one that we need named /minimal_param_node/set_parameters
with type rcl_interfaces/srv/SetParameters
:
/minimal_param_node/describe_parameters [rcl_interfaces/srv/DescribeParameters] /minimal_param_node/get_parameter_types [rcl_interfaces/srv/GetParameterTypes] /minimal_param_node/get_parameters [rcl_interfaces/srv/GetParameters] /minimal_param_node/list_parameters [rcl_interfaces/srv/ListParameters] /minimal_param_node/set_parameters [rcl_interfaces/srv/SetParameters] /minimal_param_node/set_parameters_atomically [rcl_interfaces/srv/SetParametersAtomically]
Then determine the request message fields by looking at the documentation or running this:
ros2 interface show rcl_interfaces/srv/SetParameters
The result is this:
# A list of parameters to set. Parameter[] parameters string name ParameterValue value uint8 type bool bool_value int64 integer_value float64 double_value string string_value byte[] byte_array_value bool[] bool_array_value int64[] integer_array_value float64[] double_array_value string[] string_array_value --- # Indicates whether setting each parameter succeeded or not and why. SetParametersResult[] results bool successful string reason
This means we need to send a list of parameters each with a name
and value
. So our service call should look something like this:
ros2 service call /minimal_param_node/set_parameters rcl_interfaces/srv/SetParameters "{parameters: [{name: 'my_parameter', value: {type: 4, string_value: 'a teacher'}}, {name: 'your_parameter', value: {type: 4, string_value: 'a student'}}]}"
Here, we want to set the my_parameter
value to ‘a teacher’
and the your_parameter
value to ‘a student’
. Note that each value
contains a type
that we specify using an enumerator integer. In this case, we used 4 to specify the type as a string
.
As a result of running the service call, the terminal running the node should look like this
[INFO] [1713695815.623062990] [minimal_param_node]: I am a teacher! [INFO] [1713695815.623966588] [minimal_param_node]: You are a student! [INFO] [1713695816.623087905] [minimal_param_node]: I am a teacher! [INFO] [1713695816.624100118] [minimal_param_node]: You are a student! [INFO] [1713695817.622963432] [minimal_param_node]: I am a teacher! [INFO] [1713695817.623739529] [minimal_param_node]: You are a student!
Note that this service only modifies parameters that succeed in being set. For example if you give an incorrect type, then it will not be modified. In the following service call, my_parameter
is specified incorrectly as an integer type using 2, whilst your_parameter
is correctly specified as a string. Kill and restart the node first to reset the parameter values before running:
ros2 service call /minimal_param_node/set_parameters rcl_interfaces/srv/SetParameters "{parameters: [{name: 'my_parameter', value: {type: 2, string_value: 'a teacher'}}, {name: 'your_parameter', value: {type: 4, string_value: 'a student'}}]}"
As you can see, only your_parameter
has changed:
[INFO] [1713748978.412585151] [minimal_param_node]: I am me! [INFO] [1713748978.413301978] [minimal_param_node]: You are a student! [INFO] [1713748979.413749236] [minimal_param_node]: I am me! [INFO] [1713748979.414882976] [minimal_param_node]: You are a student! [INFO] [1713748980.413437082] [minimal_param_node]: I am me! [INFO] [1713748980.414682416] [minimal_param_node]: You are a student!
Calling other parameter services
Kill and restart the node to reset the parameter values before continuing onto this section.
SetParametersAtomically
This attempts to set the given list of parameter values just like SetParameters
. However if any parameter fails to be set, then none of them are set.
- Sending the same request from before where
my_parameter
was set to the wrong type results in none of the parameters being modified.
ros2 service call /minimal_param_node/set_parameters_atomically rcl_interfaces/srv/SetParametersAtomically "{parameters: [{name: 'my_parameter', value: {type: 2, string_value: 'a teacher'}}, {name: 'your_parameter', value: {type: 4, string_value: 'a student'}}]}"
- This service call (where both types are correct) successfully sets both values.
ros2 service call /minimal_param_node/set_parameters_atomically rcl_interfaces/srv/SetParametersAtomically "{parameters: [{name: 'my_parameter', value: {type: 4, string_value: 'a teacher'}}, {name: 'your_parameter', value: {type: 4, string_value: 'a student'}}]}"
GetParameters
This service call returns a list of parameter values.
ros2 service call /minimal_param_node/get_parameters rcl_interfaces/srv/GetParameters "{names: ['my_parameter', 'your_parameter']}"
GetParameterTypes
This service call returns a list of parameter types.
ros2 service call /minimal_param_node/get_parameter_types rcl_interfaces/srv/GetParameterTypes "{names: ['my_parameter', 'your_parameter']}"
DescribeParameters
This service call returns a list of parameter descriptors.
ros2 service call /minimal_param_node/describe_parameters rcl_interfaces/srv/DescribeParameters "{names: ['my_parameter', 'your_parameter']}"
ListParameters
This service call returns a list of available parameters given an optional list of parameter prefixes. In this case it returns a list of all parameters starting with ‘my’
and ‘your’
.
ros2 service call /minimal_param_node/list_parameters rcl_interfaces/srv/ListParameters "{prefixes: ['my', 'your']}"
Now you know how to manipulate parameters at runtime
Congratulations. You now have a basic understanding of parameters.
To learn more advanced topics about ROS 2, have a look at the course below:
- Intermediate ROS 2: https://app.theconstruct.ai/courses/113
We hope this post was really helpful to you.
This tutorial is created by Robotics Ambassador Ernest.