监控参数变化 (Python)
目标: 学习使用 ParameterEventHandler 类来监控和响应参数更改。
教程级别: 中级
时间: 20 分钟
背景
节点通常需要对其自身参数或其他节点参数的变化做出响应。 ParameterEventHandler 类可以轻松监听参数变化,以便您的代码可以对其做出响应。 本教程将向您展示如何使用 Python 版本的 ParameterEventHandler 类来监视节点自身参数的变化以及另一个节点参数的变化。
先决条件
在开始本教程之前,您应该首先完成以下教程:
任务
在本教程中,您将创建一个新包来包含一些示例代码,编写一些 Python 代码以使用 ParameterEventHandler 类,并测试生成的代码。
1 创建包
首先,打开一个新终端并 source your ROS 2 installation,以便 ros2
命令可以正常工作。
按照 these instructions 创建一个名为 ros2_ws
的新工作区。
回想一下,应该在 src
目录中创建包,而不是在工作区的根目录中创建包。
因此,导航到 ros2_ws/src
,然后在那里创建一个新包:
ros2 pkg create --build-type ament_python --license Apache-2.0 python_parameter_event_handler --dependencies rclpy
您的终端将返回一条消息,验证您的包“python_parameter_event_handler”及其所有必要的文件和文件夹的创建。
“–dependencies”参数将自动将必要的依赖项行添加到“package.xml”和“CMakeLists.txt”中。
1.1 更新 package.xml
因为您在创建包时使用了“–dependencies”选项,所以您不必手动将依赖项添加到“package.xml”。 不过,与往常一样,请确保将描述、维护者电子邮件和姓名以及许可证信息添加到“package.xml”。
<description>Python parameter events client tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache-2.0</license>
2 编写 Python 节点
在 ros2_ws/src/python_parameter_event_handler/python_parameter_event_handler
目录中,创建一个名为 parameter_event_handler.py
的新文件,并将以下代码粘贴到其中:
import rclpy
import rclpy.node
import rclpy.parameter
from rclpy.parameter_event_handler import ParameterEventHandler
class SampleNodeWithParameters(rclpy.node.Node):
def __init__(self):
super().__init__('node_with_parameters')
self.declare_parameter('an_int_param', 0)
self.handler = ParameterEventHandler(self)
self.callback_handle = self.handler.add_parameter_callback(
parameter_name="an_int_param",
node_name="node_with_parameters",
callback=self.callback,
)
def callback(self, p: rclpy.parameter.Parameter) -> None:
self.get_logger().info(f"Received an update to parameter: {p.name}: {rclpy.parameter.parameter_value_to_python(p.value)}")
def main():
rclpy.init()
node = SampleNodeWithParameters()
rclpy.spin(node)
rclpy.shutdown()
2.1 检查代码
顶部的“import”语句用于导入包依赖项。
import rclpy
import rclpy.node
import rclpy.parameter
from rclpy.parameter_event_handler import ParameterEventHandler
下一段代码创建类“SampleNodeWithParameters”和构造函数。 该类的构造函数声明一个整数参数“an_int_param”,默认值为 0。 接下来,代码创建一个“ParameterEventHandler”,用于监视参数的变化。
class SampleNodeWithParameters(rclpy.node.Node):
def __init__(self):
super().__init__('node_with_parameters')
self.declare_parameter('an_int_param', 0)
self.handler = ParameterEventHandler(self)
最后,我们添加参数回调并获取新回调的回调处理程序。
Note
保存“add_parameter_callback”返回的句柄非常重要;否则回调将无法正确注册。
self.callback_handle = self.handler.add_parameter_callback(
parameter_name="an_int_param",
node_name="node_with_parameters",
callback=self.callback,
)
对于回调函数,我们使用“SampleNodeWithParameters”类的“callback”方法。
def callback(self, p: rclpy.parameter.Parameter) -> None:
self.get_logger().info(f"Received an update to parameter: {p.name}: {rclpy.parameter.parameter_value_to_python(p.value)}")
在“SampleNodeWithParameters”之后是一个典型的“main”函数,它初始化 ROS、旋转示例节点以便它可以发送和接收消息,然后在用户在控制台输入^C 后关闭。
def main():
rclpy.init()
node = SampleNodeWithParameters()
rclpy.spin(node)
rclpy.shutdown()
2.2 添加入口点
打开 setup.py
文件。
再次将 maintainer
、maintainer_email
、description
和 license
字段与您的 package.xml
匹配:
maintainer='YourName',
maintainer_email='you@email.com',
description='Python parameter tutorial',
license='Apache-2.0',
在“entry_points”字段的“console_scripts”括号内添加以下行:
entry_points={
'console_scripts': [
'node_with_parameters = python_parameter_event_handler.parameter_event_handler:main',
],
},
3 构建并运行
在构建之前,最好在工作区(“ros2_ws”)的根目录中运行“rosdep”来检查是否缺少依赖项:
rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y
rosdep only runs on Linux, so you can skip ahead to next step.
rosdep only runs on Linux, so you can skip ahead to next step.
导航回到工作区的根目录“ros2_ws”,并构建新的包:
colcon build --packages-select python_parameter_event_handler
打开一个新终端,导航到“ros2_ws”,并获取安装文件:
. install/setup.bash
. install/setup.bash
call install\setup.bat
现在运行节点:
ros2 run python_parameter_event_handler node_with_parameters
该节点现在处于活动状态,具有单个参数,每当更新此参数时都会打印一条消息。 要测试这一点,请打开另一个终端并像以前一样获取 ROS 设置文件,然后执行以下命令:
ros2 param set node_with_parameters an_int_param 43
运行节点的终端将显示类似以下内容的消息:
[INFO] [1698483083.315084660] [node_with_parameters]: Received an update to parameter: an_int_param: 43
我们之前在节点中设置的回调已被调用,并显示了新的更新值。
现在,您可以使用终端中的 ^C 终止正在运行的parameter_event_handler 示例。
3.1 监视另一个节点的参数更改
您还可以使用 ParameterEventHandler 监视另一个节点的参数更改。
让我们更新 SampleNodeWithParameters 类以监视另一个节点中参数的更改。
我们将使用parameter_blackboard 演示应用程序来托管我们将监视其更新的双参数。
首先更新构造函数以在现有代码后添加以下代码:
def __init__(...):
...
self.callback_handle = self.handler.add_parameter_callback(
parameter_name="a_double_param",
node_name="parameter_blackboard",
callback=self.callback,
)
在终端中,导航回工作区的根目录“ros2_ws”,并像之前一样构建更新的包:
colcon build --packages-select python_parameter_event_handler
然后获取安装文件:
. install/setup.bash
. install/setup.bash
call install\setup.bat
现在,为了测试远程参数的监控,首先运行新建的parameter_event_handler代码:
ros2 run python_parameter_event_handler node_with_parameters
接下来,从另一个终端(已初始化 ROS)运行参数黑板演示应用程序,如下所示:
ros2 run demo_nodes_cpp parameter_blackboard
最后,从第三个终端(已初始化 ROS),让我们在 paramter_blackboard 节点上设置一个参数:
ros2 param set parameter_blackboard a_double_param 3.45
执行此命令后,您应该在parameter_event_handler窗口中看到输出,表明在参数更新时调用了回调函数:
[INFO] [1699821958.757770223] [node_with_parameters]: Received an update to parameter: a_double_param: 3.45
摘要
您创建了一个带有参数的节点,并使用 ParameterEventHandler 类设置回调来监视该参数的更改。 您还使用同一个类来监视远程节点的更改。 ParameterEventHandler 是一种监视参数更改的便捷方法,以便您可以响应更新的值。
相关内容
要了解如何将 ROS 1 参数文件适配到 ROS 2,请参阅 将 YAML 参数文件从 ROS 1 迁移到 ROS2 教程。