22 #include <sensor_msgs/PointCloud2.h>
23 #include <sensor_msgs/PointField.h>
26 const std::string text_file_name,
27 const std::string binary_blob_file_name)
29 std::ofstream blob_file, text_file;
31 blob_file.open (binary_blob_file_name.c_str(),
32 std::ios::out | std::ios::binary | std::ios::trunc);
33 if ( !blob_file.is_open() ){
36 blob_file.write(
reinterpret_cast<const char*
>(cloud->data.data()),cloud->data.size());
39 text_file.open (text_file_name.c_str(), std::ios::out | std::ios::trunc);
40 if ( !text_file.is_open() ){
44 text_file << cloud->header.seq << std::endl;
45 text_file << cloud->header.stamp.sec << std::endl;
46 text_file << cloud->header.stamp.nsec << std::endl;
47 text_file << cloud->header.frame_id << std::endl;
50 text_file << cloud->height << std::endl;
51 text_file << cloud->width << std::endl;
52 text_file << +(cloud->is_bigendian) << std::endl;
53 text_file << cloud->point_step << std::endl;
54 text_file << cloud->row_step << std::endl;
55 text_file << +(cloud->is_dense);
58 for (uint i=0; i < cloud->fields.size(); i++)
60 text_file << std::endl;
61 text_file << cloud->fields[i].name << std::endl;
62 text_file << cloud->fields[i].offset << std::endl;
63 text_file << +(cloud->fields[i].datatype) << std::endl;
64 text_file << cloud->fields[i].count;
72 const std::string text_file_name,
73 const std::string binary_blob_file_name)
75 std::ifstream blob_file, text_file;
77 text_file.open (text_file_name.c_str(), std::ios::in);
78 if ( !text_file.is_open() ){
82 text_file >> cloud->header.seq;
83 text_file >> cloud->header.stamp.sec;
84 text_file >> cloud->header.stamp.nsec;
85 text_file >> cloud->header.frame_id;
88 text_file >> cloud->height;
89 text_file >> cloud->width;
91 text_file >> int_buffer;
92 cloud->is_bigendian = int_buffer;
93 text_file >> cloud->point_step;
94 text_file >> cloud->row_step;
96 text_file >> int_buffer;
97 cloud->is_dense = int_buffer;
101 while(text_file.peek() != EOF )
103 cloud->fields.resize(i+1);
105 text_file >> cloud->fields[i].name >> cloud->fields[i].offset \
106 >> int_buffer >> cloud->fields[i].count;
107 cloud->fields[i].datatype =
static_cast<uint8_t
>(int_buffer);
113 size_t point_size = cloud->row_step/cloud->width;
114 size_t cloud_count = cloud->width*cloud->height;
116 blob_file.open (binary_blob_file_name.c_str(), std::ios::in | std::ios::binary);
117 if ( !blob_file.is_open() ){
120 cloud->data.resize(cloud_count*point_size);
121 blob_file.read(
reinterpret_cast<char*
>(cloud->data.data()),cloud_count*point_size);