Skip to main content

7. 参数系统与 Launch 文件

现在有好几个节点,每次启动要开多个终端,连杆长度散落在每个文件里。这一讲用参数系统集中管理配置,用 Launch 文件一键启动整个系统。


前言:系统变复杂了

经过前几讲,我们已经有了好几个节点:

  • kinematics_publisher:发布关节角
  • kinematics_subscriber:订阅并验证
  • ik_service_node:IK 服务端
  • move_to_action_server:Action 服务端

每次启动都要开 4 个终端,每个终端都要 source install/setup.bash,连杆长度 L1=1.0, L2=0.8 散落在每个文件里。

改一次连杆长度,要改 4 个文件。这不是工程,这是噩梦。

参数系统解决"配置散落"的问题,Launch 文件解决"多终端启动"的问题。


7.1 ROS2 参数系统

7.1.1 参数是什么

参数是节点在运行时可读写的键值对,支持的类型包括:

类型示例
boolTrue / False
int10
double1.0
string"base_link"
list[1.0, 0.8]

7.1.2 在节点中声明和读取参数

class KinematicsPublisher(Node):
def __init__(self):
super().__init__('kinematics_publisher')

# 第一步:声明参数(名称,默认值)
self.declare_parameter('l1', 1.0)
self.declare_parameter('l2', 0.8)
self.declare_parameter('publish_rate', 1.0)

# 第二步:读取参数值
self.L1 = self.get_parameter('l1').value
self.L2 = self.get_parameter('l2').value
rate = self.get_parameter('publish_rate').value

self.timer = self.create_timer(1.0 / rate, self.timer_callback)
self.get_logger().info(f'参数: L1={self.L1}, L2={self.L2}, 频率={rate}Hz')

必须先 declare_parameterget_parameter,否则会报错。

7.1.3 启动时通过命令行传参

ros2 run my_robot_basics kinematics_publisher \
--ros-args -p l1:=1.2 -p l2:=1.0 -p publish_rate:=2.0

-p 参数名:=值 是命令行传参的格式。

7.1.4 运行时动态修改参数

节点运行时,可以在另一个终端动态修改参数:

# 查看节点的所有参数
ros2 param list /kinematics_publisher

# 读取某个参数
ros2 param get /kinematics_publisher l1

# 修改参数(立即生效,如果节点支持的话)
ros2 param set /kinematics_publisher publish_rate 5.0

7.2 参数回调——响应动态修改

默认情况下,get_parameter 只在节点启动时读取一次。如果想让节点响应运行时的参数修改,需要注册回调:

from rcl_interfaces.msg import SetParametersResult

class KinematicsPublisher(Node):
def __init__(self):
super().__init__('kinematics_publisher')
self.declare_parameter('publish_rate', 1.0)

# add_on_set_parameters_callback:注册参数变化监听器
# 每当有人调用 ros2 param set 修改参数时,param_callback 会被调用
# 注意:默认情况下 get_parameter() 只在启动时读取一次,不会自动响应修改
# 只有注册了这个回调,节点才能在运行时响应参数变化
self.add_on_set_parameters_callback(self.param_callback)

rate = self.get_parameter('publish_rate').value
self.timer = self.create_timer(1.0 / rate, self.timer_callback)

def param_callback(self, params):
# params:本次被修改的参数列表(可能同时修改多个)
for param in params:
if param.name == 'publish_rate' and param.value > 0:
# 取消旧定时器,用新频率创建新定时器
# cancel() 停止定时器但不销毁节点,下次 create_timer 会替换它
self.timer.cancel()
self.timer = self.create_timer(1.0 / param.value, self.timer_callback)
self.get_logger().info(f'发布频率已更新为 {param.value} Hz')
# 必须返回 SetParametersResult,successful=True 表示接受这次修改
# 如果返回 successful=False,ros2 param set 会报错,参数不会被修改
return SetParametersResult(successful=True)

7.3 YAML 参数文件

7.3.1 为什么需要 YAML

当参数超过 3 个,命令行传参就很繁琐。YAML 文件让配置集中管理、版本可追踪。

7.3.2 创建配置目录和文件

mkdir -p $ROS_WS/src/my_robot_basics/config
vim $ROS_WS/src/my_robot_basics/config/robot_params.yaml
# robot_params.yaml
# 节点名必须和代码里 super().__init__('节点名') 一致

kinematics_publisher:
ros__parameters:
l1: 1.0
l2: 0.8
publish_rate: 1.0

ik_service_node:
ros__parameters:
l1: 1.0
l2: 0.8

move_to_action_server:
ros__parameters:
l1: 1.0
l2: 0.8
simulate_steps: 5
step_duration: 0.5

注意:YAML 里的键名是 ros__parameters(双下划线),不是单下划线。

7.3.3 让 YAML 文件随包安装

setup.pydata_files 里加入:

data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
('share/' + package_name + '/config', ['config/robot_params.yaml']), # 新增
],

7.3.4 通过命令行加载 YAML

ros2 run my_robot_basics kinematics_publisher \
--ros-args --params-file $ROS_WS/src/my_robot_basics/config/robot_params.yaml

7.4 Launch 文件

7.4.1 Launch 文件是什么

Launch 文件是一个 Python 脚本,描述"系统由哪些节点组成、怎么启动"。

一条命令

ros2 launch my_robot_basics demo.launch.py

同时启动:kinematics_publisher + ik_service_node + move_to_action_server

所有节点共享同一份参数配置

7.4.2 创建 Launch 目录

mkdir -p $ROS_WS/src/my_robot_basics/launch
vim $ROS_WS/src/my_robot_basics/launch/demo.launch.py

7.4.3 最小 Launch 文件

# launch/demo.launch.py
# 运行方式:ros2 launch my_robot_basics demo.launch.py

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():
# get_package_share_directory():获取包安装后的 share 目录路径
# 不能用相对路径,因为 ros2 launch 的工作目录不固定
# 包安装后,config 文件会被复制到 install/<pkg>/share/<pkg>/config/
# 这个函数返回的就是那个路径,确保无论从哪里启动都能找到文件
config = os.path.join(
get_package_share_directory('my_robot_basics'),
'config',
'robot_params.yaml'
)

return LaunchDescription([
# 关节角发布节点
Node(
package='my_robot_basics', # 包名,对应 setup.py 里的 package_name
executable='kinematics_publisher', # 入口点名,对应 console_scripts 里的键
name='kinematics_publisher', # 运行时节点名,覆盖代码里 super().__init__() 的名字
parameters=[config], # 加载 YAML 参数文件,节点启动时自动读取
output='screen', # 日志输出到当前终端,不写则只存文件
),

# IK 服务节点
Node(
package='my_robot_basics',
executable='ik_service_node',
name='ik_service_node',
parameters=[config],
output='screen',
),

# Action 服务节点
Node(
package='my_robot_basics',
executable='move_to_action_server',
name='move_to_action_server',
parameters=[config],
output='screen',
),
])

7.4.4 注册 Launch 文件

setup.pydata_files 里加入:

('share/' + package_name + '/launch', ['launch/demo.launch.py']), # 新增

7.4.5 构建并运行

cd $ROS_WS
colcon build --packages-select my_robot_basics
source install/setup.bash

# 一键启动所有节点
ros2 launch my_robot_basics demo.launch.py

所有节点的日志会混合输出到同一个终端,每行前面有节点名前缀,方便区分。


7.5 Launch 进阶——参数覆盖与条件启动

7.5.1 在 Launch 中覆盖单个参数

有时候想在 YAML 基础上临时调高某个节点的发布频率,不需要改 YAML 文件,直接在 Launch 里覆盖即可。

编辑 demo.launch.py

vim $ROS_WS/src/my_robot_basics/launch/demo.launch.py

kinematics_publisherNode(...) 改为:

Node(
package='my_robot_basics',
executable='kinematics_publisher',
name='kinematics_publisher',
parameters=[
config, # 先加载 YAML(l1=1.0, l2=0.8, publish_rate=1.0)
{'publish_rate': 2.0}, # 再覆盖单个参数,最终生效值是 2.0
],
output='screen',
),

parameters 是列表,后面的字典会覆盖前面 YAML 里的同名参数,其余参数保持 YAML 的值不变。

7.5.2 通过命令行向 Launch 传参

如果想在启动时灵活指定频率,而不是每次都改文件,可以给 Launch 文件声明参数。

编辑 demo.launch.py

vim $ROS_WS/src/my_robot_basics/launch/demo.launch.py

在文件顶部的 import 区域追加两行:

from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration

然后把 generate_launch_description() 改为:

def generate_launch_description():
config = os.path.join(
get_package_share_directory('my_robot_basics'),
'config',
'robot_params.yaml'
)

# 声明 Launch 参数:名称、默认值、描述
# 用户可以在 ros2 launch 命令后用 key:=value 覆盖默认值
rate_arg = DeclareLaunchArgument(
'publish_rate',
default_value='1.0',
description='关节角发布频率(Hz)'
)

return LaunchDescription([
rate_arg, # 必须放在 LaunchDescription 里才会生效

Node(
package='my_robot_basics',
executable='kinematics_publisher',
name='kinematics_publisher',
parameters=[
config,
# LaunchConfiguration('publish_rate') 在运行时读取命令行传入的值
{'publish_rate': LaunchConfiguration('publish_rate')},
],
output='screen',
),

Node(
package='my_robot_basics',
executable='ik_service_node',
name='ik_service_node',
parameters=[config],
output='screen',
),

Node(
package='my_robot_basics',
executable='move_to_action_server',
name='move_to_action_server',
parameters=[config],
output='screen',
),
])

启动时传参:

# 使用默认频率 1.0 Hz
ros2 launch my_robot_basics demo.launch.py

# 覆盖为 5.0 Hz
ros2 launch my_robot_basics demo.launch.py publish_rate:=5.0

修改完后重新构建:

cd $ROS_WS
colcon build --packages-select my_robot_basics
source install/setup.bash

7.5.3 包含另一个 Launch 文件

当系统变大,可以把 Launch 拆成多个文件再组合:

from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('my_robot_basics'),
'/launch/sensors.launch.py'
])
)

7.6 完整 setup.py 参考

经过本讲的修改,setup.pydata_files 应该是这样的:

data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
('share/' + package_name + '/config', ['config/robot_params.yaml']),
('share/' + package_name + '/launch', ['launch/demo.launch.py']),
],

7.7 常见错误

7.7.1 错误一:参数没有生效

症状:节点启动后打印的参数值还是默认值。

排查

# 确认参数文件路径正确
ros2 param list /kinematics_publisher

# 确认 YAML 里的节点名和代码里的节点名完全一致
# YAML 顶层键 == super().__init__('节点名') 里的字符串

7.7.2 错误二:Launch 找不到参数文件

FileNotFoundError: .../config/robot_params.yaml

原因:data_files 里没有包含 config 目录,或者构建后没有重新 source

colcon build --packages-select my_robot_basics
source install/setup.bash

7.7.3 错误三:忘记 declare_parameter

rclpy.exceptions.ParameterNotDeclaredException: Parameter 'l1' is not declared

必须先声明再读取:

# 正确顺序
self.declare_parameter('l1', 1.0) # 先声明
self.L1 = self.get_parameter('l1').value # 再读取

7.8 练习题

7.8.1 练习 1:参数化 kinematics_publisher

修改 kinematics_publisher.py,把 L1L2publish_rate 改为参数,启动时打印读取到的参数值。

参考答案:见 7.1.2 的代码示例。


7.8.2 练习 2:用 YAML 统一管理参数

创建 config/robot_params.yaml,把所有节点的参数集中写入,通过 Launch 文件加载。

验证方法:

ros2 launch my_robot_basics demo.launch.py
# 观察各节点启动日志,确认参数值和 YAML 一致

7.8.3 练习 3:给 Launch 添加命令行参数

修改 demo.launch.py,支持通过命令行传入 l1l2,覆盖 YAML 中的默认值:

ros2 launch my_robot_basics demo.launch.py l1:=1.5 l2:=1.0

本讲核心总结

概念一句话理解
参数声明declare_parameter(名称, 默认值),必须在 get_parameter 之前调用
YAML 参数文件顶层键是节点名,ros__parameters 下是参数键值对
Launch 文件Python 脚本,描述系统由哪些节点组成,一键启动
get_package_share_directory获取包的安装目录,用于定位 config/launch 文件
data_filessetup.py 里声明需要安装的非 Python 文件(config、launch)
参数覆盖Launch 中可以先加载 YAML,再用字典覆盖单个参数

参考代码

本讲对应的完整参考代码位于:

ros_ws/reference/src/my_robot_basics/
├── config/robot_params.yaml ← 7.3 YAML 参数文件
└── launch/demo.launch.py ← 7.4 Launch 文件

使用方式

mkdir -p $ROS_WS/src/my_robot_basics/config
mkdir -p $ROS_WS/src/my_robot_basics/launch
cp $ROS_WS/reference/src/my_robot_basics/config/robot_params.yaml \
$ROS_WS/src/my_robot_basics/config/
cp $ROS_WS/reference/src/my_robot_basics/launch/demo.launch.py \
$ROS_WS/src/my_robot_basics/launch/

同时参考 reference/src/my_robot_basics/setup.pydata_files 的写法,确认 config 和 launch 目录已注册。


下一讲预告

8. tf2 坐标变换管理

现在我们的节点能通信、能配置、能一键启动了。但机械臂的坐标系关系还散落在运动学函数里,没有接入 ROS2 的坐标系管理系统。

下一讲我们会:

  • 理解 tf2 为什么是机器人系统的核心基础设施
  • TransformBroadcaster 把关节角变成坐标系广播
  • TransformListener 查询任意两个坐标系之间的变换
  • 在 RViz2 里第一次看到机械臂的坐标系树动起来