【ROS】为节点开启 rqt_reconfigure 的动态调参服务
前言
本教程对应的 GitHub 仓库为:ROS-Cookbook。完整代码及更多示例请参考该仓库内容。
步骤 1:创建 ROS 包
cd ~/tutotial_ws/src
catkin_create_pkg rqt_tutotial rospy dynamic_reconfigure
注意:如果创建包时忘记添加
dynamic_reconfigure
依赖,可以手动补充。我们只需要修改两个文件:package.xml
和CMakeLists.txt
。
1. 修改 package.xml
非人话:声明 dynamic_reconfigure
为构建和运行时依赖。
说人话:告诉 ROS,在编译和运行这个包时,需要用到动态参数功能。
<build_depend>dynamic_reconfigure</build_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
2. 修改 CMakeLists.txt
(1) 在 find_package
中添加 dynamic_reconfigure
非人话:这样 CMake 才能识别 generate_dynamic_reconfigure_options
命令。
说人话:告诉 CMake,在构建这个包时,需要这个依赖包,才能支持动态参数功能。
find_package(catkin REQUIRED COMPONENTS
rospy
dynamic_reconfigure # <----- 添加这一行
)
(2) 在 catkin_package
中添加 CATKIN_DEPENDS
非人话:这能确保当其他包依赖你的包时,相关依赖能正确传递。
说人话:当别人依赖你这个包时,如果没有 dynamic_reconfigure
,功能就会出错。
catkin_package(
CATKIN_DEPENDS rospy dynamic_reconfigure # <----- 添加这一行
)
(3) catkin_package
中添加生成规则
非人话:让 catkin_make 在编译时根据你的 .cfg
脚本,自动生成可以 import 的 rqt_tutorialConfig.py
文件。
说人话:诉施工队(catkin_make)去读取这张参数表(.cfg
),并根据它来生成实际的python
代码
# 添加动态参数的生成规则
generate_dynamic_reconfigure_options(
cfg/rqt_tutorial.cfg # 注意:这里的路径和文件名必须与实际创建的 .cfg 文件保持一致
)
步骤 2:定义参数(.cfg
文件)
本次示例中,我们将定义两组参数:速度组 和 位置组,并通过 .cfg
文件进行配置。
按照 ROS 的规范,需要在当下功能包目录下创建一个名为 cfg
的文件夹(这是标准做法),并在其中创建参数配置文件 rqt_tutorial.cfg
。
#!/usr/bin/env python
# -*- coding: utf-8 -*-
PACKAGE = "rqt_tutorial" # 指定为当前功能包的包名
from dynamic_reconfigure.parameter_generator_catkin import * # 导入动态调参功能所需的库和工具
# 创建一个动态参数生成器的实例
# 相当于创建一个“参数工厂”,后面定义的所有动态参数都由这个工厂添加和管理
gen = ParameterGenerator()
# ===============================================================
# ------------------- A: 速度参数组 (speed) ----------------------
# ===============================================================
# 创建一个速度参数组
# 入参说明:
# 参数分组名:在配置文件中用于标识本组参数
# 显示方式:type="tab" 表示以标签页方式显示,适合参数较多时进行分类管理
# 默认展开状态:state=True 表示该组默认展开
speed_group = gen.add_group("A_speed", type="tab", state=True)
# 定义速度参数组中的两个参数
# 入参说明:
# 参数名:rqt中显示的参数名称
# 参数类型:例如 double_t 表示浮点数类型,int_t 表示整数类型
# 参数级别:用于决定参数的变化是否需要重新启动节点(0 表示不需要)
# 参数描述:鼠标悬停在参数名上时弹出的提示
# 初始值、最小值、最大值:用于限制调参范围
speed_group.add("speed_A", double_t, 0, "速度A", 1, 0, 10)
speed_group.add("speed_B", double_t, 0, "速度B", 2, 0, 10)
# ===============================================================
# ------------------- B: 位置参数组 (position) -------------------
# ===============================================================
# 创建一个位置参数组
# 与上面的速度参数组类似,同样使用标签页方式显示,默认展开
position_group = gen.add_group("B_position", type="tab", state=True)
# 定义位置参数组中的两个参数:X坐标和Y坐标
position_group.add("X_position", double_t, 0, "X坐标", 0.0, -10.0, 10.0)
position_group.add("Y_position", double_t, 0, "Y坐标", 0.0, -10.0, 10.0)
# ===============================================================
# ------------------ 最后:生成配置文件 --------------------------
# ===============================================================
# 入参说明:
# 包名:功能包名称
# 配置文件所在路径:一般与包名相同
# 类名:生成的配置类名
# 示例说明:
# 下述指令生成的配置文件为 rqt_tutorial.cfg
# 那么在 python 节点中导入配置类时写作:
# from rqt_tutorial.cfg import rqt_tutorialConfig
# 当该节点加载这个配置类时,就拥有了这些参数的初始值、范围信息(自动定义并且初始化)
# 创建 rqt 动态调参的服务时,可以与 rqt_reconfigure 工具进行动态交互调参
exit(gen.generate(PACKAGE, "rqt_tutorial", "rqt_tutorial"))
注意:请为 .cfg
文件添加执行权限!
chmod +x cfg/rqt_tutorial.cfg
步骤 3:编写ROS节点 (rqt_tutorial_node.py
)
目标说明:
-
创建一个 Python 脚本,作为 ROS 节点使用。
-
导入
.cfg
文件自动生成的配置类(rqt_tutorialConfig
)。- 导入该配置类后,节点即可访问
.cfg
文件中定义的所有动态参数。
- 导入该配置类后,节点即可访问
-
启动动态调参服务(
dynamic_reconfigure.server.Server
)。- 启动该服务后,节点将具备与
rqt_reconfigure
图形界面实时交互的能力。 - 当参数在界面中被修改时,该服务会自动触发绑定的回调函数。
- 启动该服务后,节点将具备与
-
编写回调函数,用于响应参数变化,获取并处理最新的参数值。
-
效果展示:在节点的主循环中打印当前参数值,便于观察调参结果的实时变化。
代码示意:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
# 1. 导入关键模块
# - Server: 这是启动动态调参服务的核心类
# - rqt_tutorialConfig: 这是catkin_make根据你的.cfg文件自动生成的Python类!它的名字是根据 gen.generate(..., "rqt_tutorial") 来的。
from dynamic_reconfigure.server import Server
from rqt_tutorial.cfg import rqt_tutorialConfig
# 定义动态调参器的类
class DynamicParamNode:
def __init__(self):
# 初始化ROS节点
rospy.init_node('rqt_tutorial_node', anonymous=False)
# 初始化将要被动态调整的参数变量
# 给它们一个初始值,但这些值很快会被.cfg文件中的默认值覆盖(只是为了提高代码可读性,在 __init__ 中就能清楚地看到这个类有哪些重要的成员变量,以及他们的初始值)
self.speed_a = 0.0
self.speed_b = 0.0
self.x_pos = 0.0
self.y_pos = 0.0
rospy.loginfo("rqt_tutorial节点已启动,等待参数更新...")
# 2. 创建动态调参服务实例 (关键一步!)
# - 第一个参数是自动生成的Config类
# - 第二个参数是回调函数,当参数被修改时,会自动调用 self.reconfigure_callback
# 当这行代码执行时,回调函数会立刻被调用一次,用.cfg中的默认值来初始化所有参数
self.srv = Server(rqt_tutorialConfig, self.reconfigure_callback)
# 启动主循环,用于持续打印参数值
# 创建类的实例时,会自动执行__init__方法中的代码,如果想在执行完__init__后继续执行其他逻辑,可以在这里调用一个run方法(代码的规范即是在实例的最后定义run函数)
self.run()
# 3. 编写回调函数 (参数更新时的响应函数)
def reconfigure_callback(self, config, level):
"""当rqt_reconfigure中的参数被改变时,此函数被自动调用"""
# level参数是一个位掩码,用于指示哪个参数组被改变了,我们暂时用不到它(我们的逻辑是参数一变就全同步,而并非“如果A组参数变化才同步,其他组变化不同步”这种按组做不同处理的逻辑)
# 将接收到的新参数值(config对象)赋给类的成员变量
# config对象的成员变量名,就是你在.cfg文件中定义的参数名!
self.speed_a = config.speed_A
self.speed_b = config.speed_B
self.x_pos = config.X_position
self.y_pos = config.Y_position
# 打印一条日志,让我们知道回调函数被触发了,并显示更新后的值
rospy.loginfo("""参数已更新:
Speed A: {speed_A}
Speed B: {speed_B}
Position X: {X_position}
Position Y: {Y_position}
""".format(**config))
# 注意:回调函数必须返回config对象,这是API的要求
return config
def run(self):
"""
节点的主循环,只是为了打印参数,让我们看到效果
run函数是在__init__函数最后调用的,这样可以确保在节点启动后初始化完成以后进入run函数
"""
rate = rospy.Rate(1) # 1 Hz (每秒打印一次)
while not rospy.is_shutdown():
rospy.loginfo("--- 当前参数值 ---")
rospy.loginfo(f"速度A: {self.speed_a:.2f}, 速度B: {self.speed_b:.2f}")
rospy.loginfo(f"坐标X: {self.x_pos:.2f}, 坐标Y: {self.y_pos:.2f}")
rospy.loginfo("---------------------")
rate.sleep()
if __name__ == "__main__":
try:
DynamicParamNode()
except rospy.ROSInterruptException:
pass
步骤 4:测试
使用 launch
文件启动节点,验证动态参数是否能在运行过程中被正确调节。
roslaunch rqt_tutorial rqt_tutorial.launch
测试效果如下图所示: