目标:从您自己的 Python 节点记录数据到一个包。
教程级别:高级
时间:20 分钟
目录
背景
先决条件
任务
1. 创建一个包
2. 编写 Python 节点
3. 建立并运行
4. 从节点记录合成数据
5. 从可执行文件记录合成数据
摘要
背景
rosbag2
不仅提供 ros2 bag
命令行工具。它还提供了一个 Python API,用于从您自己的源代码中读取和写入 bag。这使您可以订阅一个主题,并在对该数据执行任何其他处理的同时,将接收到的数据保存到 bag 中。例如,您可以这样做,以保存来自一个主题的数据和处理该数据的结果,而无需通过一个主题发送处理后的数据来记录它。由于任何数据都可以记录在 bag 中,因此也可以保存由其他来源生成的数据,而不是主题,例如用于训练集的合成数据。这很有用,例如,可以快速生成一个包含大量样本的 bag,这些样本分布在较长的回放时间内。
先决条件
您应该在常规的 ROS 2 设置中安装 rosbag2
软件包。
如果您已经从 Linux 上的 Debian 软件包安装,它可能会默认安装。如果没有,您可以使用此命令安装它。
sudo apt install ros-jazzy-rosbag2
本教程讨论了如何使用 ROS 2 包,包括从终端使用。您应该已经完成了基本的 ROS 2 包教程。
任务
1. 创建一个包
打开一个新的终端并且初始化您的 ROS 2 安装,这样 ros2
命令就会生效。
按照这些指示创建一个名为 ros2_ws
的新工作区。
导航到 ros2_ws/src
目录并创建一个新包:
ros2 pkg create --build-type ament_python --license Apache-2.0 bag_recorder_nodes_py --dependencies rclpy rosbag2_py example_interfaces std_msgs
您的终端将返回一条消息,验证您的包 bag_recorder_nodes_py
及其所有必要的文件和文件夹的创建。 --dependencies
参数将自动添加必要的依赖行到 package.xml
。在这种情况下,该包将使用 rosbag2_py
包以及 rclpy
包。消息定义还需要依赖 example_interfaces
包。
1.1 更新 package.xml
和 setup.py
因为您在创建包时使用了 --dependencies
选项,您无需手动将依赖项添加到 package.xml
中。但是,一如既往,请确保将描述、维护者电子邮件和姓名以及许可信息添加到 package.xml
中。
<description>Python bag writing tutorial</description>
<maintainer email="cxy@126.com">cxy</maintainer>
<license>Apache-2.0</license>
还请确保将此信息添加到 setup.py
文件中。
maintainer='cxy',
maintainer_email='cxy@126.com',
description='Python bag writing tutorial',
license='Apache-2.0',
2. 编写 Python 节点
在 ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py
目录中,创建一个名为 simple_bag_recorder.py
的新文件,并将以下代码粘贴到其中。
import rclpy # 导入 rclpy 库
from rclpy.node import Node # 从 rclpy.node 模块中导入 Node 类
from rclpy.serialization import serialize_message # 从 rclpy.serialization 模块中导入 serialize_message 函数
from std_msgs.msg import String # 从 std_msgs.msg 模块中导入 String 消息类型
import rosbag2_py # 导入 rosbag2_py 库
class SimpleBagRecorder(Node): # 定义 SimpleBagRecorder 类,继承自 Node
def __init__(self): # 初始化方法
super().__init__('simple_bag_recorder') # 调用父类的初始化方法,节点名称为 'simple_bag_recorder'
self.writer = rosbag2_py.SequentialWriter() # 创建一个 SequentialWriter 对象
storage_options = rosbag2_py._storage.StorageOptions(
uri='my_bag', # 设置存储选项的 URI 为 'my_bag'
storage_id='mcap') # 设置存储 ID 为 'mcap'
converter_options = rosbag2_py._storage.ConverterOptions('', '') # 创建转换选项对象
self.writer.open(storage_options, converter_options) # 打开 writer
topic_info = rosbag2_py._storage.TopicMetadata(
id=0, # 主题 ID 为 0
name='chatter', # 主题名称为 'chatter'
type='std_msgs/msg/String', # 主题类型为 'std_msgs/msg/String'
serialization_format='cdr') # 序列化格式为 'cdr'
self.writer.create_topic(topic_info) # 创建主题
self.subscription = self.create_subscription(
String, # 订阅的消息类型为 String
'chatter', # 订阅的主题名称为 'chatter'
self.topic_callback, # 回调函数为 self.topic_callback
10) # 队列大小为 10
self.subscription # 保持订阅对象的引用
def topic_callback(self, msg): # 定义回调函数
self.writer.write(
'chatter', # 写入的主题名称为 'chatter'
serialize_message(msg), # 序列化消息
self.get_clock().now().nanoseconds) # 获取当前时间戳并转换为纳秒
def main(args=None): # 定义主函数
rclpy.init(args=args) # 初始化 rclpy
sbr = SimpleBagRecorder() # 创建 SimpleBagRecorder 对象
rclpy.spin(sbr) # 让节点保持运行
rclpy.shutdown() # 关闭 rclpy
if __name__ == '__main__': # 如果当前模块是主模块
main() # 调用主函数
检查代码 2.1
顶部的 import
语句是包依赖项。请注意导入 rosbag2_py
包以使用 bag 文件所需的函数和结构。
在类构造函数中,我们首先创建将用于写入包的写入器对象。我们正在创建一个 SequentialWriter
,它按接收顺序将消息写入包中。rosbag2 中可能有其他具有不同行为的写入器。
self.writer = rosbag2_py.SequentialWriter()
现在我们有了一个 writer 对象,我们可以使用它打开 bag。我们指定要创建的 bag 的 URI 和格式 ( mcap
),将其他选项保留为默认值。使用默认的转换选项,这些选项不会执行任何转换,并以接收到的序列化格式存储消息。
storage_options = rosbag2_py._storage.StorageOptions(
uri='my_bag',
storage_id='mcap')
converter_options = rosbag2_py._storage.ConverterOptions('', '')
self.writer.open(storage_options, converter_options)
接下来,我们需要告诉writer我们希望存储的主题。这是通过创建一个 TopicMetadata
对象并将其注册到 writer 来完成的。该对象指定了主题名称、主题数据类型和使用的序列化格式。
topic_info = rosbag2_py._storage.TopicMetadata(
id=0,
name='chatter',
type='std_msgs/msg/String',
serialization_format='cdr')
self.writer.create_topic(topic_info)
现在 writer 已经设置好记录我们传递给它的数据,我们创建一个订阅并为其指定一个回调。我们将在回调中将数据写入包中。
self.subscription = self.create_subscription(
String,
'chatter',
self.topic_callback,
10)
self.subscription
回调函数以未序列化的形式接收消息(这是 rclpy
API 的标准),并将消息传递给写入器,指定数据的主题和记录消息的时间戳。然而,写入器需要序列化的消息来存储在包中。这意味着我们需要在将数据传递给写入器之前对其进行序列化。出于这个原因,我们调用 serialize_message()
并将其结果传递给写入器,而不是直接传递消息。
def topic_callback(self, msg):
self.writer.write(
'chatter',
serialize_message(msg),
self.get_clock().now().nanoseconds)
文件以 main
函数结束,该函数用于创建节点实例并开始处理 ROS。
def main(args=None):
rclpy.init(args=args)
sbr = SimpleBagRecorder()
rclpy.spin(sbr)
rclpy.shutdown()
2.2 添加入口点
打开 setup.py
文件在 bag_recorder_nodes_py
包中,并为您的节点添加一个入口点。
entry_points={
'console_scripts': [
'simple_bag_recorder = bag_recorder_nodes_py.simple_bag_recorder:main',
],
},
3. 构建并运行
导航回到工作区的根目录, ros2_ws
,并构建您的新包。
colcon build --packages-select bag_recorder_nodes_py
打开一个新的终端,导航到 ros2_ws
,并加载设置文件。
source install/setup.bash
现在运行节点:
ros2 run bag_recorder_nodes_py simple_bag_recorder
打开第二个终端并运行 talker
示例节点。
ros2 run demo_nodes_cpp talker
这将开始在 chatter
主题上发布数据。当包写入节点接收到这些数据时,它将写入 my_bag
包。如果 my_bag
目录已经存在,则必须先删除它,然后再运行 simple_bag_recorder
节点。这是因为 rosbag2
默认情况下不会覆盖现有的包,因此目标目录不能存在。
终止两个节点。然后,在一个终端启动 listener
示例节点。
ros2 run demo_nodes_cpp listener
在另一个终端中,使用 ros2 bag
播放由您的节点记录的包。
ros2 bag play my_bag
您将看到来自bag 的消息被 listener
节点接收。
如果您希望再次运行 bag-writing 节点,您首先需要删除 my_bag
目录。
4 从节点记录合成数据
任何数据都可以记录到一个包中,而不仅仅是通过主题接收到的数据。将数据写入包中的一个常见用例是生成和存储合成数据。在本节中,您将学习如何编写一个生成一些数据并将其存储在包中的节点。我们将演示两种方法来实现这一点。第一种方法使用带有计时器的节点;如果您的数据生成是节点外部的,例如直接从硬件(例如相机)读取数据,这是您将使用的方法。第二种方法不使用节点;当您不需要使用 ROS 基础设施的任何功能时,可以使用这种方法。
4.1 编写一个 Python 节点
在 ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py
目录中,创建一个名为 data_generator_node.py
的新文件,并将以下代码粘贴到其中。
import rclpy # 导入 rclpy 库
from rclpy.node import Node # 从 rclpy.node 模块中导入 Node 类
from rclpy.serialization import serialize_message # 从 rclpy.serialization 模块中导入 serialize_message 函数
from example_interfaces.msg import Int32 # 从 example_interfaces.msg 模块中导入 Int32 消息类型
import rosbag2_py # 导入 rosbag2_py 库
class DataGeneratorNode(Node): # 定义 DataGeneratorNode 类,继承自 Node
def __init__(self): # 初始化方法
super().__init__('data_generator_node') # 调用父类的初始化方法,节点名称为 'data_generator_node'
self.data = Int32() # 创建一个 Int32 消息对象
self.data.data = 0 # 初始化消息数据为 0
self.writer = rosbag2_py.SequentialWriter() # 创建一个 SequentialWriter 对象
storage_options = rosbag2_py._storage.StorageOptions(
uri='timed_synthetic_bag', # 设置存储选项的 URI 为 'timed_synthetic_bag'
storage_id='mcap') # 设置存储 ID 为 'mcap'
converter_options = rosbag2_py._storage.ConverterOptions('', '') # 创建转换选项对象
self.writer.open(storage_options, converter_options) # 打开 writer
topic_info = rosbag2_py._storage.TopicMetadata(
id=0, # 主题 ID 为 0
name='synthetic', # 主题名称为 'synthetic'
type='example_interfaces/msg/Int32', # 主题类型为 'example_interfaces/msg/Int32'
serialization_format='cdr') # 序列化格式为 'cdr'
self.writer.create_topic(topic_info) # 创建主题
self.timer = self.create_timer(1, self.timer_callback) # 创建一个定时器,每秒调用一次 timer_callback
def timer_callback(self): # 定义定时器回调函数
self.writer.write(
'synthetic', # 写入的主题名称为 'synthetic'
serialize_message(self.data), # 序列化消息
self.get_clock().now().nanoseconds) # 获取当前时间戳并转换为纳秒
self.data.data += 1 # 增加消息数据
def main(args=None): # 定义主函数
rclpy.init(args=args) # 初始化 rclpy
dgn = DataGeneratorNode() # 创建 DataGeneratorNode 对象
rclpy.spin(dgn) # 让节点保持运行
rclpy.shutdown() # 关闭 rclpy
if __name__ == '__main__': # 如果当前模块是主模块
main() # 调用主函数
4.2 检查代码
这段代码的大部分与第一个示例相同。这里描述了重要的区别。
首先,包的名称被更改。
storage_options = rosbag2_py._storage.StorageOptions(
uri='timed_synthetic_bag',
storage_id='mcap')
主题的名称也已更改,存储的数据类型也是如此。
topic_info = rosbag2_py._storage.TopicMetadata(
id=0,
name='synthetic',
type='example_interfaces/msg/Int32',
serialization_format='cdr')
self.writer.create_topic(topic_info)
与其订阅一个主题,这个节点有一个计时器。计时器以一秒的周期触发,并在触发时调用给定的成员函数。
self.timer = self.create_timer(1, self.timer_callback)
在定时器回调中,我们生成(或以其他方式获取,例如从连接到某些硬件的串行端口读取)我们希望存储在包中的数据。与前面的示例一样,数据尚未序列化,因此我们必须在将其传递给写入器之前对其进行序列化。
self.writer.write(
'synthetic',
serialize_message(self.data),
self.get_clock().now().nanoseconds)
4.3 添加可执行文件
打开 setup.py
文件在 bag_recorder_nodes_py
包中,并为您的节点添加一个入口点。
entry_points={
'console_scripts': [
'simple_bag_recorder = bag_recorder_nodes_py.simple_bag_recorder:main',
'data_generator_node = bag_recorder_nodes_py.data_generator_node:main',
],
},
4.4 构建和运行
导航回到工作区的根目录, ros2_ws
,并构建你的包。
colcon build --packages-select bag_recorder_nodes_py
打开一个新的终端,导航到 ros2_ws
,并加载设置文件。
source install/setup.bash
如果 timed_synthetic_bag
目录已经存在,则必须先删除它,然后才能运行节点。
现在运行节点:
ros2 run bag_recorder_nodes_py data_generator_node
等待大约 30 秒,然后使用 ctrl-c 终止节点。接下来,播放创建的包。
ros2 bag play timed_synthetic_bag
打开第二个终端并回显 /synthetic
主题。
ros2 topic echo /synthetic
您将看到生成并存储在包中的数据以每秒一条消息的速度打印到控制台。
5. 从可执行文件记录合成数据
现在您可以创建一个存储来自非主题源数据的包,您将学习如何从非节点可执行文件生成和记录合成数据。这种方法的优点是代码更简单,并且可以快速创建大量数据。
5.1 编写一个 Python 可执行文件
在 ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py
目录中,创建一个名为 data_generator_executable.py
的新文件,并将以下代码粘贴到其中。
from rclpy.clock import Clock # 从 rclpy.clock 模块中导入 Clock 类
from rclpy.duration import Duration # 从 rclpy.duration 模块中导入 Duration 类
from rclpy.serialization import serialize_message # 从 rclpy.serialization 模块中导入 serialize_message 函数
from example_interfaces.msg import Int32 # 从 example_interfaces.msg 模块中导入 Int32 消息类型
import rosbag2_py # 导入 rosbag2_py 库
def main(args=None): # 定义主函数
writer = rosbag2_py.SequentialWriter() # 创建一个 SequentialWriter 对象
storage_options = rosbag2_py._storage.StorageOptions(
uri='big_synthetic_bag', # 设置存储选项的 URI 为 'big_synthetic_bag'
storage_id='mcap') # 设置存储 ID 为 'mcap'
converter_options = rosbag2_py._storage.ConverterOptions('', '') # 创建转换选项对象
writer.open(storage_options, converter_options) # 打开 writer
topic_info = rosbag2_py._storage.TopicMetadata(
id=0, # 主题 ID 为 0
name='synthetic', # 主题名称为 'synthetic'
type='example_interfaces/msg/Int32', # 主题类型为 'example_interfaces/msg/Int32'
serialization_format='cdr') # 序列化格式为 'cdr'
writer.create_topic(topic_info) # 创建主题
time_stamp = Clock().now() # 获取当前时间戳
for ii in range(0, 100): # 循环 100 次 0-99
data = Int32() # 创建一个 Int32 消息对象
data.data = ii # 设置消息数据为当前循环变量 ii
writer.write(
'synthetic', # 写入的主题名称为 'synthetic'
serialize_message(data), # 序列化消息
time_stamp.nanoseconds) # 写入当前时间戳的纳秒值
time_stamp += Duration(seconds=1) # 将时间戳增加 1 秒
if __name__ == '__main__': # 如果当前模块是主模块
main() # 调用主函数
5.2 检查代码
对比这个样本和之前的样本会发现它们并没有太大区别。唯一显著的区别是使用了 for 循环来驱动数据生成,而不是计时器。
请注意,我们现在生成数据的时间戳,而不是依赖当前系统时间来获取每个样本的时间。时间戳可以是您需要的任何值。数据将按照这些时间戳给出的速率回放,因此这是控制样本默认回放速度的有用方法。还请注意,虽然每个样本之间的间隔是整整一秒钟,但这个可执行文件不需要在每个样本之间等待一秒钟。这使我们能够在比回放所需时间短得多的时间内生成覆盖较长时间跨度的大量数据。
time_stamp = Clock().now()
for ii in range(0, 100):
data = Int32()
data.data = ii
writer.write(
'synthetic',
serialize_message(data),
time_stamp.nanoseconds)
time_stamp += Duration(seconds=1)
5.3 添加可执行文件
打开 setup.py
文件在 bag_recorder_nodes_py
包中,并为您的节点添加一个入口点。
entry_points={
'console_scripts': [
'simple_bag_recorder = bag_recorder_nodes_py.simple_bag_recorder:main',
'data_generator_node = bag_recorder_nodes_py.data_generator_node:main',
'data_generator_executable = bag_recorder_nodes_py.data_generator_executable:main',
],
},
5.4 构建和运行
导航回到工作区的根目录, ros2_ws
,并构建你的包。
colcon build --packages-select bag_recorder_nodes_py
打开终端,导航到 ros2_ws
,并加载设置文件。
source install/setup.bash
如果 big_synthetic_bag
目录已经存在,则必须先删除它,然后再运行可执行文件。
现在运行可执行文件:
ros2 run bag_recorder_nodes_py data_generator_executable
请注意,可执行文件运行并完成得非常快。
现在播放创建的包。
ros2 bag play big_synthetic_bag
打开第二个终端并回显 /synthetic
主题。
ros2 topic echo /synthetic
您将看到生成并存储在包中的数据以每秒一条消息的速度打印到控制台。尽管包生成得很快,但仍然按照时间戳指示的速度回放。
摘要
您创建了一个节点,将其接收到的主题数据记录到一个包中。您测试了使用该节点记录包,并通过回放包验证了数据已被记录。此方法可用于记录包含比通过主题接收到的数据更多的包,例如包含处理接收到的数据所得的结果。然后,您继续创建一个节点和一个可执行文件,以生成合成数据并将其存储在一个包中。后者的方法尤其适用于生成可用作训练集的合成数据。