ROS2 parameters
Parameters Hierarchy
- Declare node with parameters name that using dot(.) to describe the yaml struct
- Create struct yaml file
params.yaml |
---|
| /param_demo:
ros__parameters:
camera:
resolution:
width: 640
use_sim_time: false
|
simple_node.py |
---|
| #!/usr/bin/env python3
import rclpy
from rclpy.node import Node
NAME = "param_demo"
class ParamDemo(Node):
def __init__(self):
super().__init__(NAME)
self.param1 = self.declare_parameter("camera.resolution.width", 640)
self.t = self.create_timer(1.0, self.timer_handler)
def timer_handler(self):
self.get_logger().info(f"{self.get_parameter('camera.resolution.width').value}")
def main(args=None):
rclpy.init(args=args)
node = ParamDemo()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()
|
run node with parameter file |
---|
| ros2 run my_package my_node --ros-args --params-file params.yaml
|
usage

update from cli |
---|
| ros2 param set /param_demo camera.resolution.width 1200
|
update string node with numeric value
The failure happens only if we set the parameter value as string numeric (number in Quotation marks)
| # parameter declaration
self.param1 = self.declare_parameter("param1", value="1")
|
| ros2 param set /param_demo param1 "12"
#
Setting parameter failed: Wrong parameter type, expected 'Type.STRING' got 'Type.INTEGER'
|
| # use double quotation
ros2 param set /param_demo param1 '"12"'
|