参考链接:
ROS学习:制作自己的TUM数据集
配置环境
1.安装ROS
参考我的博客
https://blog.csdn.net/qin_liang/article/details/127035615
2.查看rosbag中的topic
rosbag info xxx.bag
3.创建catkin_ws/src文件夹
在src下运行
catkin_create_pkg rosbag2tum roscpp std_msgs sensor_msgs cv_bridge
4.进入生成的rosbag2tum里面的src
在src文件夹下创建bagToTUM.cpp文件:
(修改自己对应的rosbag包里面的节点)
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <ros/ros.h>
#include <iostream>
#include <chrono>
#include <string>
using namespace std;
//设置一些保存路径
string Path = "/home/ql/pan1/Dataset/test/seq3/";
string pathRGB = Path + "rgb.txt";
string pathDepth = Path + "depth.txt";
string dataRGB = Path + "rgb/";
string dataDepth = Path + "depth/";
//设置图像topic名称
string depth_topic = "/zed2i/zed_node/depth/depth_registered";
string rgb_topic = "/zed2i/zed_node/left_raw/image_raw_color";
//保存图像路径至txt文件下
void savePath(string &path, string &type,double time){
ofstream of;
of.open(path, std::ios_base::app);
if(of.fail()){
ROS_INFO("Fail to opencv file!!");
}else{
of<<endl;
of<<std::fixed<< time <<" "<< type <<time<<".png";
of.close();
}
}
//RGB图像回调函数
void GrabRGB(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImageConstPtr cv_ptr;
try
{
//保存图像及路径
cv_ptr = cv_bridge::toCvShare(msg);
//颜色通道转换
cv::Mat bgrImage;
// cvtColor(cv_ptr->image, bgrImage, CV_BGR2RGB);
//cv::imshow("RGB", bgrImage);
double time = cv_ptr->header.stamp.toSec();
string type = "rgb/";
savePath(pathRGB, type, time);
std::ostringstream osf;
osf<< dataRGB <<std::fixed <<time << ".png";//图像以时间戳命名
// cv::imwrite(osf.str(), bgrImage);
cv::imwrite(osf.str(), cv_ptr->image);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
//cv::waitKey(2);
}
//深度图像回调函数
void GrabDepth(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImageConstPtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvShare(msg);
//imshow("Depth", cv_ptr->image);
double time = cv_ptr->header.stamp.toSec();
string type = "depth/";
savePath(pathDepth, type, time);
std::ostringstream osf;
osf<< dataDepth <<std::fixed <<time << ".png";
cv::imwrite(osf.str(), cv_ptr->image);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
//cv::waitKey(2);
}
//节点主函数
int main(int argc,char **argv)
{
ros::init(argc,argv,"bagToTUM");
ros::start();
ofstream of;
of.open(pathRGB, std::ios_base::app);
if(of.fail()){
ROS_INFO("Fail to opencv file!!");
}else{
of<<"#------------start a new dataset-----------------";
of.close();
}
of.open(pathDepth, std::ios_base::app);
if(of.fail()){
ROS_INFO("Fail to opencv file!!");
}else{
of<<"#------------start a new dataset-----------------";
of.close();
}
//订阅图像话题
ROS_INFO("bagToTUM is ready.");
ros::NodeHandle nodeHandler;
ros::Subscriber subRGB = nodeHandler.subscribe(rgb_topic, 5, &GrabRGB);
ros::Subscriber subDepth = nodeHandler.subscribe(depth_topic, 5, &GrabDepth);
ros::spin();
return 0;
}
5.配置rosbag2tum文件夹下的CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(rosbag2tum)
find_package(catkin REQUIRED COMPONENTS
cv_bridge
roscpp
sensor_msgs
std_msgs
)
find_package(OpenCV 3.0 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 2.4.3 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
endif()
endif()
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES rosbag2tum
CATKIN_DEPENDS cv_bridge roscpp sensor_msgs std_msgs
# DEPENDS system_lib
)
include_directories(
# include
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_executable(bag2tum src/bagToTUM.cpp)
target_link_libraries(bag2tum ${catkin_LIBRARIES} ${OpenCV_LIBS})
5.在catkin_ws文件夹下运行
catkin_make
转化
运行之前先在输出的文件夹的位置创建好depth rgb文件夹
1.打开终端运行
roscore
2.在类似这样的文件夹/home/ql/pan1/catkin_ws/devel/lib/rosbag2tum下运行
./rosbag2tum
这个文件夹下必须有这个可执行文件
3.播放对应的bag包
rosbag play xxx.bag -r 0.5
这样就可以转化出对应的图片了