rosbag点云数据保存为bin,ply,pcd文件 您所在的位置:网站首页 prd文件怎么改成bin rosbag点云数据保存为bin,ply,pcd文件

rosbag点云数据保存为bin,ply,pcd文件

2023-12-19 18:01| 来源: 网络整理| 查看: 265

本文基于ros将rosbag中的点云数据一帧一帧保存成对应的文件,并比对各个文件占用空间大小。 阉割版的如下,能用,但是少了一些功能,旨在记录保存下来的各种点云文件。 废话不说,直接上代码:

#include #include #include #include #include #include #include #include #include #include #include #include #include #include std::string FrontPcd_path; void FrontPoint_callback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) { ros::Time time = cloud_msg->header.stamp; pcl::PointCloud tmp; pcl::fromROSMsg(*cloud_msg, tmp); double tt = time.toSec(); //save to pcd file pcl::io::savePCDFileBinary(FrontPcd_path + std::to_string(tt) + ".pcd", tmp); pcl::io::savePCDFileASCII(FrontPcd_path + std::to_string(tt) + ".pcd", tmp); pcl::io::savePLYFile(FrontPcd_path + std::to_string(tt) + ".ply", tmp); //save to bin file std::ofstream out; std::string save_filename = FrontPcd_path + std::to_string(tt) + ".bin"; out.open(save_filename, std::ios::out | std::ios::binary); std::cout ros::init(argc, argv, "read_rosbag"); ROS_INFO("Start Read Rosbag and save it as pcd wiht txt"); ros::NodeHandle nh; std::string front_lidar_topic; nh.param("front_lidar_topic", front_lidar_topic, std::string("/tof_cloud")); nh.param("FrontPcd_path", FrontPcd_path, std::string("/home/sc/catkin_ws/src/read_rosbag/FrontLidar/")); ros::Subscriber sub_cloud1 = nh.subscribe(front_lidar_topic, 100, FrontPoint_callback); ros::MultiThreadedSpinner spinner(1); spinner.spin(); return 0; }

CMakeLists.txt如下:

cmake_minimum_required(VERSION 3.0.2) project(read_rosbag) # add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS nav_msgs pcl_conversions pcl_ros roscpp sensor_msgs std_msgs ) catkin_package( INCLUDE_DIRS include # LIBRARIES read_rosbag CATKIN_DEPENDS nav_msgs pcl_conversions pcl_ros roscpp sensor_msgs std_msgs DEPENDS system_lib ) include_directories( # include ${catkin_INCLUDE_DIRS} ) add_executable(${PROJECT_NAME} src/read_rosbag.cpp) target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} )

就一个很简单的ros功能包,自己写的,有了代码其实其他的可以自己补全。 保存下来的点云数据分别为pcd(Binary压缩),pcd(ASCII压缩),ply,bin四种。占用内存大小由小到大如下:bin < pcd(Binary压缩) < pcd(ASCII压缩) < ply;在这里插入图片描述在这里插入图片描述 如上四个文件大小分别为188.2kb < 255kb < 685.3kb < 685.8kb,每个点云数据都不大,毕竟是tof数据嘛!



【本文地址】

公司简介

联系我们

今日新闻

    推荐新闻

    专题文章
      CopyRight 2018-2019 实验室设备网 版权所有