您正在阅读的是开发版本的文档。有关最新发布的版本,请访问 Jazzy.
读取袋文件(C++)
目标 无需使用 CLI 即可从数据包中读取数据。
辅导水平: 高级
时间 10 分钟
背景介绍
rosbag2
不只是提供 玫瑰2 背包
命令行工具。它还提供了一个 C++ 应用程序接口,用于从自己的源代码中读取和写入数据包。这样,您就可以读取软件包中的内容,而无需播放软件包,这有时非常有用。
先决条件
您应该有 rosbag2
作为 ROS 2 常规设置的一部分安装的软件包。
如果需要安装 ROS 2,请参见 安装说明.
您应该已经完成了 ROS 2 工具包基础教程我们将使用 子集
你在那里创造的袋子。
任务
1 创建一个软件包
打开一个新终端,然后 为您的 ROS 2 安装提供源代码 以便 玫瑰2
命令即可运行。
在新的或现有的 工作区,导航至 来源
目录,并创建一个新软件包:
ros2 pkg create --build-type ament_cmake --license Apache-2.0 bag_reading_cpp --dependencies rclcpp rosbag2_transport turtlesim
您的终端将返回一条信息,验证是否创建了软件包 bag_reading_cpp
及其所有必要的文件和文件夹。文件 --依赖
参数会自动在 package.xml
和 CMakeLists.txt
.在这种情况下,软件包将使用 罗兹包2_运输
软件包以及 rclcpp
软件包。对 海龟
软件包也是处理自定义 turtlesim 消息所必需的。
1.1 更新 package.xml
因为您使用了 --依赖
选项,就不必在创建软件包时手动将依赖关系添加到 package.xml
或 CMakeLists.txt
.不过,请务必一如既往地将说明、维护者电子邮件和姓名以及许可证信息添加到 package.xml
.
<描述>;C++ 背包 阅读 教程</description>;
维护者 电子邮件="[email protected]";>;您的 名称维护人员</maintainer>;
许可证Apache-2.0</license>;
2 编写 C++ 阅读器
在包裹的 来源
目录下,新建一个名为 simple_bag_reader.cpp
并粘贴以下代码。
#include 时间顺序<chrono>;
#include 功能强大;
#include iostream>;
#include <内存>;
#include <字符串>;
#include "rclcpp/rclcpp.hpp";
#include "rclcpp/serialization.hpp";
#include "rosbag2_transport/reader_writer_factory.hpp";
#include "turtlesim/msg/pose.hpp";
使用 命名空间 标准::计时器;
类 播放节点 : 公 rclcpp::节点
{
公:
播放节点(缢 标准::字符串 及样品; 袋子文件名)
: 节点("playback_node";)
{
出版商_ = 此->;创建出版商<;海龟::信息::姿势>;("/turtle1/pose";, 10);
定时器 = 此->;创建隔离墙计时器(100毫秒,
[此](){返回 此->;定时器回调();}
);
rosbag2_存储::存储选项 存储选项;
存储选项.uri = 袋子文件名;
读者_ = 罗兹包2_运输::读写器工厂::make_reader(存储选项);
读者_->;开(存储选项);
}
私人:
空白 定时器回调()
{
虽然 (读者_->;has_next()) {
rosbag2_存储::序列化消息包共享 Ptr 信息 = 读者_->;read_next();
如果 (信息->;topic_name != "/turtle1/pose";) {
继续;
}
rclcpp::序列化信息 序列化的 msg(*信息->;序列化数据);
海龟::信息::姿势::SharedPtr ros_msg = 标准::共享<;海龟::信息::姿势>;();
序列化_.反序列化消息(及样品;序列化的 msg, ros_msg.获取());
出版商_->;发布(*ros_msg);
标准::cout <<; '(' <<; ros_msg->;x <<; ","; <<; ros_msg->;y <<; ")\n";;
断裂;
}
}
rclcpp::定时器基数::SharedPtr 定时器;
rclcpp::出版商<;海龟::信息::姿势>::SharedPtr 出版商_;
rclcpp::序列化<;海龟::信息::姿势>; 序列化_;
标准::唯一参数<;rosbag2_cpp::读者>; 读者_;
};
int 主要(int 参数, 烧焦 ** 参数)
{
如果 (参数 != 2) {
标准::cerr <<; "使用方法:"; <<; 参数[0] <<; "<bag>"; <<; 标准::endl;
返回 1;
}
rclcpp::启动(参数, 参数);
rclcpp::后旋(标准::共享<;播放节点>;(参数[1]));
rclcpp::关闭();
返回 0;
}
2.1 检查代码
"(《世界人权宣言》) #include
顶部的语句是软件包的依赖关系。注意包含了 罗兹包2_运输
包中提供了处理袋文件所需的函数和结构。
下一行将创建一个节点,用于读取袋文件并播放数据。
类 播放节点 : 公 rclcpp::节点
现在,我们可以创建一个以 10 hz 频率运行的定时器回调。我们的目标是重放一条信息到 /turtle1/pose
主题。请注意,构造函数的参数是文件袋的路径。
公:
播放节点(缢 标准::字符串 及样品; 袋子文件名)
: 节点("playback_node";)
{
出版商_ = 此->;创建出版商<;海龟::信息::姿势>;("/turtle1/pose";, 10);
定时器 = 此->;创建隔离墙计时器(100毫秒,
[此](){返回 此->;定时器回调();}
);
我们也会在构造函数中打开袋子。打开 rosbag2_transport::ReaderWriterFactory
是一个可以根据存储选项构建压缩或非压缩读写器的类。
rosbag2_存储::存储选项 存储选项;
存储选项.uri = 袋子文件名;
读者_ = 罗兹包2_运输::读写器工厂::make_reader(存储选项);
读者_->;开(存储选项);
现在,在定时器回调中,我们会循环查看消息袋中的消息,直到读取到所需主题记录的消息。请注意,序列化后的消息除了主题名称外,还有时间戳元数据。
空白 定时器回调()
{
虽然 (读者_->;has_next()) {
rosbag2_存储::序列化消息包共享 Ptr 信息 = 读者_->;read_next();
如果 (信息->;topic_name != "/turtle1/pose";) {
继续;
}
然后,我们构建一个 rclcpp::SerializedMessage
对象。此外,我们还需要创建一个 ROS 2 反序列化消息,用于保存反序列化的结果。然后,我们可以将这两个对象传递给 rclcpp::Serialization::deserialize_message
方法。
rclcpp::序列化信息 序列化的 msg(*信息->;序列化数据);
海龟::信息::姿势::SharedPtr ros_msg = 标准::共享<;海龟::信息::姿势>;();
序列化_.反序列化消息(及样品;序列化的 msg, ros_msg.获取());
最后,我们发布反序列化信息,并将 xy 坐标打印到终端。我们还将跳出循环,以便在下一次定时器回调时发布下一条信息。
出版商_->;发布(*ros_msg);
标准::cout <<; '(' <<; ros_msg->;x <<; ","; <<; ros_msg->;y <<; ")\n";;
断裂;
}
我们还必须声明在整个节点中使用的私有变量。
rclcpp::定时器基数::SharedPtr 定时器;
rclcpp::出版商<;海龟::信息::姿势>::SharedPtr 出版商_;
rclcpp::序列化<;海龟::信息::姿势>; 序列化_;
标准::唯一参数<;rosbag2_cpp::读者>; 读者_;
};
最后,我们创建了主函数,该函数将检查用户是否传入了文件袋路径参数,并旋转我们的节点。
int 主要(int 参数, 烧焦 ** 参数)
{
如果 (参数 != 2) {
标准::cerr <<; "使用方法:"; <<; 参数[0] <<; "<bag>"; <<; 标准::endl;
返回 1;
}
rclcpp::启动(参数, 参数);
rclcpp::后旋(标准::共享<;播放节点>;(参数[1]));
rclcpp::关闭();
返回 0;
}
2.2 添加可执行文件
现在打开 CMakeLists.txt
锉刀
在依赖项块下方,包含 find_package(rosbag2_transport 必填)
添加以下代码
add_executable(simple_bag_reader src/simple_bag_reader.cpp)
ament_target_dependencies(simple_bag_reader rclcpp rosbag2_transport turtlesim)
install(TARGETS
简单包阅读器
目的地 lib/${PROJECT_NAME}
)
3 构建和运行
返回工作区的根目录,构建新软件包。
colcon build --packages-select bag_reading_cpp
colcon build --packages-select bag_reading_cpp
colcon build --merge-install --packages-select bag_reading_cpp
接下来,获取设置文件。
source install/setup.bash
source install/setup.bash
调用 install/setup.bat
现在,运行脚本。确保替换 /path/to/subset
的路径。 子集
包。
ros2 run bag_reading_cpp simple_bag_reader /path/to/subset
你会看到乌龟的 (x, y) 坐标被打印到控制台。
摘要
您创建了一个 C++ 可执行程序,用于从一个袋子中读取数据。然后编译并运行该可执行文件,并在控制台中打印出袋子中的一些信息。