37 #ifndef MAPPER_PCL_CONVERSIONS_H_
38 #define MAPPER_PCL_CONVERSIONS_H_
43 #include <pcl/conversions.h>
45 #include <pcl/PCLHeader.h>
46 #include <std_msgs/Header.h>
48 #include <pcl/PCLPointField.h>
49 #include <sensor_msgs/PointField.h>
51 #include <pcl/PCLPointCloud2.h>
52 #include <sensor_msgs/PointCloud2.h>
54 #include <Eigen/Geometry>
55 #include <Eigen/StdVector>
68 stamp.fromNSec(pcl_stamp * 1000ull);
72 pcl_stamp = stamp.toNSec() / 1000ull;
82 pcl::uint64_t pcl_stamp;
83 toPCL(stamp, pcl_stamp);
89 inline void fromPCL(
const pcl::PCLHeader &pcl_header,
90 std_msgs::Header &header) {
91 fromPCL(pcl_header.stamp, header.stamp);
92 header.seq = pcl_header.seq;
93 header.frame_id = pcl_header.frame_id;
96 inline void toPCL(
const std_msgs::Header &header, pcl::PCLHeader &pcl_header) {
97 toPCL(header.stamp, pcl_header.stamp);
98 pcl_header.seq = header.seq;
99 pcl_header.frame_id = header.frame_id;
102 inline std_msgs::Header
fromPCL(
const pcl::PCLHeader &pcl_header) {
103 std_msgs::Header header;
108 inline pcl::PCLHeader
toPCL(
const std_msgs::Header &header) {
109 pcl::PCLHeader pcl_header;
110 toPCL(header, pcl_header);
116 inline void fromPCL(
const pcl::PCLPointField &pcl_pf,
117 sensor_msgs::PointField &pf) {
118 pf.name = pcl_pf.name;
119 pf.offset = pcl_pf.offset;
120 pf.datatype = pcl_pf.datatype;
121 pf.count = pcl_pf.count;
124 inline void fromPCL(
const std::vector<pcl::PCLPointField> &pcl_pfs,
125 std::vector<sensor_msgs::PointField> &pfs) {
126 pfs.resize(pcl_pfs.size());
127 std::vector<pcl::PCLPointField>::const_iterator it = pcl_pfs.begin();
129 for (; it != pcl_pfs.end(); ++it, ++i) {
134 inline void toPCL(
const sensor_msgs::PointField &pf,
135 pcl::PCLPointField &pcl_pf) {
136 pcl_pf.name = pf.name;
137 pcl_pf.offset = pf.offset;
138 pcl_pf.datatype = pf.datatype;
139 pcl_pf.count = pf.count;
142 inline void toPCL(
const std::vector<sensor_msgs::PointField> &pfs,
143 std::vector<pcl::PCLPointField> &pcl_pfs) {
144 pcl_pfs.resize(pfs.size());
145 std::vector<sensor_msgs::PointField>::const_iterator it = pfs.begin();
147 for (; it != pfs.end(); ++it, ++i) {
148 toPCL(*(it), pcl_pfs[i]);
155 sensor_msgs::PointCloud2 &pc2) {
156 fromPCL(pcl_pc2.header, pc2.header);
157 pc2.height = pcl_pc2.height;
158 pc2.width = pcl_pc2.width;
159 fromPCL(pcl_pc2.fields, pc2.fields);
160 pc2.is_bigendian = pcl_pc2.is_bigendian;
161 pc2.point_step = pcl_pc2.point_step;
162 pc2.row_step = pcl_pc2.row_step;
163 pc2.is_dense = pcl_pc2.is_dense;
166 inline void fromPCL(
const pcl::PCLPointCloud2 &pcl_pc2,
167 sensor_msgs::PointCloud2 &pc2) {
169 pc2.data = pcl_pc2.data;
173 sensor_msgs::PointCloud2 &pc2) {
175 pc2.data.swap(pcl_pc2.data);
179 pcl::PCLPointCloud2 &pcl_pc2) {
180 toPCL(pc2.header, pcl_pc2.header);
181 pcl_pc2.height = pc2.height;
182 pcl_pc2.width = pc2.width;
183 toPCL(pc2.fields, pcl_pc2.fields);
184 pcl_pc2.is_bigendian = pc2.is_bigendian;
185 pcl_pc2.point_step = pc2.point_step;
186 pcl_pc2.row_step = pc2.row_step;
187 pcl_pc2.is_dense = pc2.is_dense;
190 inline void toPCL(
const sensor_msgs::PointCloud2 &pc2,
191 pcl::PCLPointCloud2 &pcl_pc2) {
193 pcl_pc2.data = pc2.data;
197 pcl::PCLPointCloud2 &pcl_pc2) {
199 pcl_pc2.data.swap(pc2.data);
209 const std::string &field_name) {
211 for (
size_t d = 0; d < cloud.fields.size(); ++d) {
212 if (cloud.fields[d].name == field_name) {
213 return (
static_cast<int>(d));
223 for (
size_t i = 0; i < cloud.fields.size() - 1; ++i) {
224 result += cloud.fields[i].name +
" ";
226 result += cloud.fields[cloud.fields.size() - 1].name;
233 template <
typename T>
235 sensor_msgs::PointCloud2 &cloud) {
236 pcl::PCLPointCloud2 pcl_pc2;
237 pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
241 template <
typename T>
243 pcl::PointCloud<T> &pcl_cloud) {
244 pcl::PCLPointCloud2 pcl_pc2;
246 pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
249 template <
typename T>
251 pcl::PointCloud<T> &pcl_cloud) {
252 pcl::PCLPointCloud2 pcl_pc2;
254 pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
259 template <
typename Po
intT>
261 MsgFieldMap &field_map) {
262 std::vector<pcl::PCLPointField> pcl_msg_fields;
264 return createMapping<PointT>(pcl_msg_fields, field_map);
271 struct DefaultMessageCreator<
pcl::PCLPointCloud2> {
273 boost::shared_ptr<pcl::PCLPointCloud2> msg(
new pcl::PCLPointCloud2());
278 namespace message_traits {
280 struct MD5Sum<
pcl::PCLPointCloud2> {
282 return MD5Sum<sensor_msgs::PointCloud2>::value();
284 static const char *
value(
const pcl::PCLPointCloud2 &) {
return value(); }
286 static const uint64_t static_value1 =
287 MD5Sum<sensor_msgs::PointCloud2>::static_value1;
288 static const uint64_t static_value2 =
289 MD5Sum<sensor_msgs::PointCloud2>::static_value2;
293 ROS_STATIC_ASSERT(static_value1 == 0x1158d486dd51d683ULL);
294 ROS_STATIC_ASSERT(static_value2 == 0xce2f1be655c3c181ULL);
298 struct DataType<
pcl::PCLPointCloud2> {
300 return DataType<sensor_msgs::PointCloud2>::value();
302 static const char *
value(
const pcl::PCLPointCloud2 &) {
return value(); }
306 struct Definition<
pcl::PCLPointCloud2> {
308 return Definition<sensor_msgs::PointCloud2>::value();
310 static const char *
value(
const pcl::PCLPointCloud2 &) {
return value(); }
314 struct HasHeader<
pcl::PCLPointCloud2> : TrueType {};
317 namespace serialization {
322 struct Serializer<
pcl::PCLPointCloud2> {
323 template <
typename Stream>
324 inline static void write(Stream &stream,
const pcl::PCLPointCloud2 &m) {
325 std_msgs::Header header;
328 stream.next(m.height);
329 stream.next(m.width);
330 std::vector<sensor_msgs::PointField> pfs;
333 stream.next(m.is_bigendian);
334 stream.next(m.point_step);
335 stream.next(m.row_step);
337 stream.next(m.is_dense);
340 template <
typename Stream>
341 inline static void read(Stream &stream, pcl::PCLPointCloud2 &m) {
342 std_msgs::Header header;
345 stream.next(m.height);
346 stream.next(m.width);
347 std::vector<sensor_msgs::PointField> pfs;
350 stream.next(m.is_bigendian);
351 stream.next(m.point_step);
352 stream.next(m.row_step);
354 stream.next(m.is_dense);
360 std_msgs::Header header;
362 length += serializationLength(header);
365 std::vector<sensor_msgs::PointField> pfs;
367 length += serializationLength(pfs);
372 length += m.data.size() *
sizeof(pcl::uint8_t);
383 struct Serializer<
pcl::PCLPointField> {
384 template <
typename Stream>
385 inline static void write(Stream &stream,
const pcl::PCLPointField &m) {
387 stream.next(m.offset);
388 stream.next(m.datatype);
389 stream.next(m.count);
392 template <
typename Stream>
393 inline static void read(Stream &stream, pcl::PCLPointField &m) {
395 stream.next(m.offset);
396 stream.next(m.datatype);
397 stream.next(m.count);
403 length += serializationLength(m.name);
404 length += serializationLength(m.offset);
405 length += serializationLength(m.datatype);
406 length += serializationLength(m.count);
416 struct Serializer<
pcl::PCLHeader> {
417 template <
typename Stream>
418 inline static void write(Stream &stream,
const pcl::PCLHeader &m) {
419 std_msgs::Header header;
424 template <
typename Stream>
425 inline static void read(Stream &stream, pcl::PCLHeader &m) {
426 std_msgs::Header header;
434 std_msgs::Header header;
436 length += serializationLength(header);
445 #endif // MAPPER_PCL_CONVERSIONS_H_