sensor_msg_serialization.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020 Autoware Foundation. All rights reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <fstream>
18 #include <iostream>
19 #include <string>
20 #include <vector>
21 
22 #include <sensor_msgs/PointCloud2.h>
23 #include <sensor_msgs/PointField.h>
24 
25 bool serialize_sensor_msg(const sensor_msgs::PointCloud2::ConstPtr& cloud,
26  const std::string text_file_name,
27  const std::string binary_blob_file_name)
28 {
29  std::ofstream blob_file, text_file;
30 
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() ){
34  return false;
35  }
36  blob_file.write(reinterpret_cast<const char*>(cloud->data.data()),cloud->data.size());
37  blob_file.close();
38 
39  text_file.open (text_file_name.c_str(), std::ios::out | std::ios::trunc);
40  if ( !text_file.is_open() ){
41  return false;
42  }
43  //header
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;
48 
49  //sensor_msg
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);
56 
57  //fields
58  for (uint i=0; i < cloud->fields.size(); i++)
59  {
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;
65  }
66 
67  text_file.close();
68  return true;
69 }
70 
71 bool unserialize_sensor_msg(const sensor_msgs::PointCloud2::Ptr& cloud,
72  const std::string text_file_name,
73  const std::string binary_blob_file_name)
74 {
75  std::ifstream blob_file, text_file;
76 
77  text_file.open (text_file_name.c_str(), std::ios::in);
78  if ( !text_file.is_open() ){
79  return false;
80  }
81  //header
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;
86 
87  //sensor_msg
88  text_file >> cloud->height;
89  text_file >> cloud->width;
90  int int_buffer = 0;
91  text_file >> int_buffer;
92  cloud->is_bigendian = int_buffer;
93  text_file >> cloud->point_step;
94  text_file >> cloud->row_step;
95  int_buffer = 0;
96  text_file >> int_buffer;
97  cloud->is_dense = int_buffer;
98 
99  //fields
100  uint i = 0;
101  while(text_file.peek() != EOF )
102  {
103  cloud->fields.resize(i+1);
104  int int_buffer;
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);
108  i++;
109  }
110 
111  text_file.close();
112 
113  size_t point_size = cloud->row_step/cloud->width; // in Byte
114  size_t cloud_count = cloud->width*cloud->height;
115 
116  blob_file.open (binary_blob_file_name.c_str(), std::ios::in | std::ios::binary);
117  if ( !blob_file.is_open() ){
118  return false;
119  }
120  cloud->data.resize(cloud_count*point_size);
121  blob_file.read(reinterpret_cast<char*>(cloud->data.data()),cloud_count*point_size);
122  blob_file.close();
123  return true;
124 }
serialize_sensor_msg
bool serialize_sensor_msg(const sensor_msgs::PointCloud2::ConstPtr &cloud, const std::string text_file_name, const std::string binary_blob_file_name)
Definition: sensor_msg_serialization.h:25
unserialize_sensor_msg
bool unserialize_sensor_msg(const sensor_msgs::PointCloud2::Ptr &cloud, const std::string text_file_name, const std::string binary_blob_file_name)
Definition: sensor_msg_serialization.h:71


points_preprocessor
Author(s): n-patiphon , aohsato
autogenerated on Wed Mar 2 2022 00:12:07