本文基于ros将rosbag中的点云数据一帧一帧保存成对应的文件,并比对各个文件占用空间大小。
阉割版的如下,能用,但是少了一些功能,旨在记录保存下来的各种点云文件。
废话不说,直接上代码:
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/io/ply_io.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/filters/voxel_grid.h>
#include <nav_msgs/Odometry.h>
#include <fstream>
#include <iostream>
#include <sstream>
#include <string>
#include <iomanip>
std::string FrontPcd_path;
void FrontPoint_callback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
{
ros::Time time = cloud_msg->header.stamp;
pcl::PointCloud<pcl::PointXYZI> 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 << save_filename << " saved" << std::endl;
int cloudSize = tmp.points.size();
for (int i = 0; i < cloudSize; ++i)
{
float point_x = tmp.points[i].x;
float point_y = tmp.points[i].y;
float point_z = tmp.points[i].z;
out.write(reinterpret_cast<const char *>(&point_x), sizeof(float));
out.write(reinterpret_cast<const char *>(&point_y), sizeof(float));
out.write(reinterpret_cast<const char *>(&point_z), sizeof(float));
}
out.close();
}
int main(int argc, char **argv)
{
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数据嘛!