回溯rosbag2
概述

方式1一邊採集數據,一邊生成地圖信息。
方式2是將採集數據和生成地圖信息分割開來了,方式2做到了解耦合,所以更靈活一些。用同一套數據,可能用不同的算法處理,總之,非常靈活。
留存的過程咱們也可以叫做序列化。(轉化為磁盤文件)
留存一般叫錄製(序列化)。
讀取一般叫回放(反序列化)。

留存時也可以將文件進行分卷,也就是每個文件最大能佔多大的大小,如果超過該大小,就新建一個文件繼續留存。(類似於壓縮文件的分卷)
這樣的話,存的數據太大,我們一次性打開太慢,就可以分段打開。


需要依賴於rosbag2_cpp或者rosbag2_py
然後還要依賴於geometry_msgs,這個是因為我們要序列化的數據是這個包下的速度指令。
ros2 pkg create cpp02_rosbag --build-type ament_cmake --dependencies rclcpp rosbag2_cpp geometry_msgs --node-name cpp01_writer
rosbag2的命令工具

一般ROSBAG2的使用有命令行工具和編碼兩種使用方式,命令行工具功能比較齊全,夠用。
查看幫助文檔ros2 bag -h

主要有6個指令。



可以看record的詳細用法。

record是用來將消息序列化的。(錄製)
play是用來反序列化消息的。(回放)
info是用來輸出bag文件的相關信息的。比如有多少條消息,錄製起始時間和終止時間以及持續時間。
reindex是重建bag文件,可以修改bag源數據文件。
list是輸出rosbag2中可用的插件(高階應用)。
convert我們可以用這個給bag文件修改擴展名,也可以把多個bag文件合併成一個文件。

打開小烏龜節點與鍵盤控制小烏龜節點。
我們用鍵盤控制小烏龜,然後把速度指令通過rosbag2給序列化。
然後我們關掉兩個節點,再重啓小烏龜節點,然後這次不通過鍵盤控制,而是通過play bag文件讓小烏龜運動。
record指令後面要跟一個話題組成的列表,但是在咱們下面的操作中,只用到了一個話題。


然後再用output,把序列化後的文件寫出到一個磁盤目錄中去。

cd進想保存bag的目錄,然輸入record指令,後面跟話題名稱,然後-o +bag文件名,這裏也可以不重新命名bag文件,這樣會用默認的名字,默認的名稱是年月日命名的。
這樣就已經開始錄製了。


按Ctrl + C進行結束,結束有個提示,説正在將消息寫入bag,需要一段時間。


這個yaml文件是源數據文件。
db3是SQLite數據庫,這個是移動端(比如手機)常用的數據庫。
這個數據庫就存儲了錄製的數據。
rosbag2 C++案例分析及框架搭建


add_executable(demo01_writer src/demo01_writer.cpp)
ament_target_dependencies(
demo01_writer
"rclcpp"
"rosbag2_cpp"
"geometry_msgs"
)
add_executable(demo02_reader src/demo02_reader.cpp)
ament_target_dependencies(
demo02_reader
"rclcpp"
"rosbag2_cpp"
"geometry_msgs"
)
install(TARGETS
demo01_writer
demo02_reader
DESTINATION lib/${PROJECT_NAME})
rosbag2 C++ 錄製數據
/*
需求:录制 turtle_teleop_key 节点发布的速度指令。
步骤:
1.包含头文件;
2.初始化 ROS 客户端;
3.定义节点类;
3-1.创建写出对象指针;
3-2.设置写出的目标文件;
3-3.写出消息。
4.调用 spin 函数,并传入对象指针;
5.释放资源。
*/
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "rosbag2_cpp/writer.hpp"
#include "geometry_msgs/msg/twist.hpp"
using std::placeholders::_1;
// 3.定义节点类;
class SimpleBagRecorder : public rclcpp::Node
{
public:
SimpleBagRecorder()
: Node("simple_bag_recorder")
{
// 3-1.创建写出对象指针;
writer_ = std::make_unique<rosbag2_cpp::Writer>();
// 3-2.设置写出的目标文件;(目录为ws目录)
writer_->open("src/cpp02_rosbag/my_bag");
subscription_ = create_subscription<geometry_msgs::msg::Twist>(
"/turtle1/cmd_vel", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
}
private:
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
{
rclcpp::Time time_stamp = this->now();
// 3-3.写出消息。
RCLCPP_INFO(this->get_logger(),"数据写出... ...");
writer_->write(msg, "/turtle1/cmd_vel", "geometry_msgs/msg/Twist", time_stamp);
}
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_;
std::unique_ptr<rosbag2_cpp::Writer> writer_;
};
int main(int argc, char * argv[])
{
// 2.初始化 ROS 客户端;
rclcpp::init(argc, argv);
// 4.调用 spin 函数,并传入对象指针;
rclcpp::spin(std::make_shared<SimpleBagRecorder>());
// 5.释放资源。
rclcpp::shutdown();
return 0;
}

這是一個相對目錄,目錄位置是工作空間目錄。

寫數據之前,要先創建一個訂閲方,訂閲方要建立一個回調函數。

回調函數入口參數,消息類型用write函數的入口參數。

這裏要用斜槓代替冒號,因為入口是string類型。



創建烏龜節點。

啓動writer節點

運行小烏龜
運行一會兒後,關掉所有節點。

成功生成了文件
驗證錄製文件是否成功。
在驗證前,先創建一個烏龜節點,不用創建控制節點。
ros2 bag play src/cpp02_rosbag/my_bag

可以看到烏龜正常走了。回放成功!

如果已經生成了一遍my_bag,再想生成新的會顯示不能覆蓋。
解決方案,可以把my_bag設置為動態的,加個時間戳或者直接按功能命名。
rosbag2 C++ 讀取數據
/*
需求:读取 bag 文件数据。
步骤:
1.包含头文件;
2.初始化 ROS 客户端;
3.定义节点类;
3-1.创建读取对象指针;
3-2.设置读取的目标文件;
3-3.读消息;
3-4.关闭文件。
4.调用 spin 函数,并传入对象指针;
5.释放资源。
*/
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "rosbag2_cpp/reader.hpp"
#include "geometry_msgs/msg/twist.hpp"
// 3.定义节点类;
class SimpleBagPlayer: public rclcpp::Node {
public:
SimpleBagPlayer():Node("simple_bag_player"){
// 3-1.创建读取对象指针;
reader_ = std::make_unique<rosbag2_cpp::Reader>();
// 3-2.设置读取的目标文件;
reader_->open("src/cpp02_rosbag/my_bag");
// 3-3.读消息;
while (reader_->has_next())
{
auto twist = reader_->read_next<geometry_msgs::msg::Twist>();
RCLCPP_INFO(this->get_logger(),"线速度:%.2f, 角速度: %.2f",twist.linear.x, twist.angular.z);
}
// 3-4.关闭文件。
reader_->close();
}
private:
std::unique_ptr<rosbag2_cpp::Reader> reader_;
};
int main(int argc, char const *argv[]){
// 2.初始化 ROS 客户端;
rclcpp::init(argc,argv);
// 4.调用 spin 函数,并传入对象指针;
rclcpp::spin(std::make_shared<SimpleBagPlayer>());
// 5.释放资源。
rclcpp::shutdown();
return 0;
}


編譯

這顯示能讀出來幾條信息。能讀出來8條。

正好8條