编写一个简单的发布者和订阅者(Python)
**目标:**使用Python创建和运行发布者和订阅者节点。
教程级别: 初学者
背景
在本教程中,您将创建 节点,以字符串消息的形式通过 话题 互相传递信息。这里使用的示例是一个简单的“说话者”和“侦听者”系统;一个节点发布数据,另一个节点订阅该话题以接收数据。
这些示例中使用的代码可以在 这里 找到。
任务
1 创建一个包
在一个新的终端中 源化你的 ROS 2 安装,这样 ros2
命令才能正常工作。
进入在 上一个教程 中创建的 ros2_ws
目录。
记住,包应该创建在 src
目录中,而不是工作空间的根目录。所以,进入 ros2_ws/src
目录,并运行包创建命令:
ros2 pkg create --build-type ament_python py_pubsub
你的终端将返回一条消息,验证已创建名为 py_pubsub
的软件包及其所有必要的文件和文件夹。
2 编写发布者节点
进入 ros2_ws/src/py_pubsub/py_pubsub
目录。请记住,该目录是一个与嵌套的ROS 2软件包同名的 Python包。
通过输入以下命令下载示例 talker 代码:
wget https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py
wget https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py
在 Windows 命令行提示符中:
curl -sk https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py -o publisher_member_function.py
或者在powershell中执行:
curl https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py -o publisher_member_function.py
现在会在``__init__.py``旁边出现一个名为``publisher_member_function.py``的新文件。
使用您偏爱的文本编辑器打开该文件。
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(String, 'topic', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
msg = String()
msg.data = 'Hello World: %d' % self.i
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
2.1 检查代码
在注释之后的第一行代码中导入``rclpy``,以便可以使用其``Node``类。
import rclpy
from rclpy.node import Node
下一条语句导入了内置的字符串消息类型,节点使用该类型来结构化在主题上传递的数据。
from std_msgs.msg import String
这些行表示节点的依赖关系。请记住,依赖项必须添加到``package.xml``中,在下一节中将进行此操作。
接下来,创建了``MinimalPublisher``类,它继承自(或是``Node``的子类)。
class MinimalPublisher(Node):
以下是该类构造函数的定义。super().__init__``调用了``Node``类的构造函数,并向其传递了节点名称,本例中为``minimal_publisher
。
``create_publisher``声明该节点发布类型为``String``(从``std_msgs.msg``模块导入),在名为``topic``的主题上,且“队列大小”为10。队列大小是一个必需的QoS(服务质量)设置,它限制了如果订阅者接收消息的速度不够快时,排队消息的数量。
首先,创建一个定时器,并设置每0.5秒执行一次回调函数。``self.i``是在回调函数中使用的计数器。
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(String, 'topic', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
``timer_callback``创建一个带有计数器值附加的消息,并使用``get_logger().info``将其发布到控制台。
def timer_callback(self):
msg = String()
msg.data = 'Hello World: %d' % self.i
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1
最后,定义主函数。
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
首先初始化``rclpy``库,然后创建节点,最后"旋转"节点以调用其回调函数。
2.2 添加依赖项
导航到``ros2_ws/src/py_pubsub``目录的上一级,其中已经为您创建了``setup.py``、``setup.cfg``和``package.xml``文件。
用文本编辑器打开``package.xml``文件。
如在:doc:之前的教程 <./Creating-Your-First-ROS2-Package>`中提到的,确保填写``<description>`
, ``<maintainer>``和``<license>``标签:
<description>Examples of minimal publisher/subscriber using rclpy</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
在上述行之后,添加与您的节点导入语句对应的以下依赖项:
<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
这将在代码执行时声明该包需要``rclpy``和``std_msgs``。
确保保存文件.
2.3 添加入口点
打开``setup.py``文件。再次,将``maintainer``、maintainer_email
、``description``和``license``字段与您的``package.xml``相匹配:
maintainer='YourName',
maintainer_email='you@email.com',
description='Examples of minimal publisher/subscriber using rclpy',
license='Apache License 2.0',
将以下行添加到``entry_points``字段的``console_scripts``括号内:
entry_points={
'console_scripts': [
'talker = py_pubsub.publisher_member_function:main',
],
},
不要忘记保存。
2.4 检查 setup.cfg
setup.cfg
文件的内容应该被正确地自动填充,如下所示:
[develop]
script_dir=$base/lib/py_pubsub
[install]
install_scripts=$base/lib/py_pubsub
这仅仅是告诉 setuptools 将你的可执行文件放在 lib
中,因为 ros2 run
会在那里查找它们。
现在您可以构建您的软件包,加载本地设置文件并运行它,但是让我们首先创建订阅者节点,这样您就可以看到整个系统的运行情况。
3 编写订阅者节点
返回到 ros2_ws/src/py_pubsub/py_pubsub
,创建下一个节点。在终端中输入以下代码:
wget https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py
wget https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py
在 Windows 命令行提示符中:
curl -sk https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py -o subscriber_member_function.py
或者在powershell中执行:
curl https://raw.githubusercontent.com/ros2/examples/humble/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py -o subscriber_member_function.py
现在目录中应该有以下文件:
__init__.py publisher_member_function.py subscriber_member_function.py
3.1 检查代码
用文本编辑器打开 subscriber_member_function.py
。
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(
String,
'topic',
self.listener_callback,
10)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
self.get_logger().info('I heard: "%s"' % msg.data)
def main(args=None):
rclpy.init(args=args)
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
订阅者节点的代码几乎与发布者节点相同。构造函数使用与发布者相同的参数创建一个订阅者。回顾一下:doc:`主题教程<../Beginner-CLI-Tools/Understanding-ROS2-Topics/Understanding-ROS2-Topics>`中提到的,发布者和订阅者使用的主题名称和消息类型必须匹配,以便它们能够进行通信。
self.subscription = self.create_subscription(
String,
'topic',
self.listener_callback,
10)
订阅者的构造函数和回调函数不包括任何定时器定义,因为它不需要。一旦接收到消息,它的回调函数就会被调用。
回调函数的定义只是将一条信息和接收到的数据打印到控制台上。请回忆一下,发布者定义了``msg.data = 'Hello World: %d' % self.i``。
def listener_callback(self, msg):
self.get_logger().info('I heard: "%s"' % msg.data)
``main``函数的定义几乎完全相同,只是将创建和运行发布者替换为订阅者。
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
由于该节点与发布者具有相同的依赖关系,因此不需要向``package.xml``中添加任何新内容。``setup.cfg``文件也可以保持不变。
3.2 添加一个入口点
重新打开 setup.py
并在发布者的入口点下方添加订阅者节点的入口点。现在,entry_points
字段应该如下所示:
entry_points={
'console_scripts': [
'talker = py_pubsub.publisher_member_function:main',
'listener = py_pubsub.subscriber_member_function:main',
],
},
确保保存文件,然后您的发布/订阅系统就准备好了。
4 构建和运行
很可能您已经在ROS 2系统中安装了 rclpy
和 std_msgs
包。在构建之前,在工作空间的根目录(ros2_ws
)中运行 rosdep
以检查缺失的依赖关系是一个好的做法:
rosdep install -i --from-path src --rosdistro humble -y
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
仍然在您的工作空间根目录(ros2_ws
)中,构建您的新软件包:
colcon build --packages-select py_pubsub
colcon build --packages-select py_pubsub
colcon build --merge-install --packages-select py_pubsub
打开一个新的终端,导航到 ros2_ws
,并加载设置文件:
source install/setup.bash
. install/setup.bash
call install/setup.bat
现在运行对话节点:
ros2 run py_pubsub talker
终端应该会每0.5秒发布一条信息消息,如下所示:
[INFO] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [minimal_publisher]: Publishing: "Hello World: 4"
...
打开另一个终端,在``ros2_ws``内部再次source设置文件,然后启动监听节点:
ros2 run py_pubsub listener
监听器将从发布者当前的消息计数开始,将消息打印到控制台,就像这样:
[INFO] [minimal_subscriber]: I heard: "Hello World: 10"
[INFO] [minimal_subscriber]: I heard: "Hello World: 11"
[INFO] [minimal_subscriber]: I heard: "Hello World: 12"
[INFO] [minimal_subscriber]: I heard: "Hello World: 13"
[INFO] [minimal_subscriber]: I heard: "Hello World: 14"
在每个终端中输入``Ctrl+C``来停止节点的旋转。