pcl_conversions.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Open Source Robotics Foundation, Inc.
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation, Inc. nor
19  * the names of its contributors may be used to endorse or promote
20  * products derived from this software without specific prior
21  * written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
37 #ifndef PCL_CONVERSIONS_H__
38 #define PCL_CONVERSIONS_H__
39 
40 #include <vector>
41 
42 #include <ros/ros.h>
43 
44 #include <pcl/conversions.h>
45 
46 #include <pcl/PCLHeader.h>
47 #include <std_msgs/Header.h>
48 
49 #include <pcl/PCLImage.h>
50 #include <sensor_msgs/Image.h>
51 
52 #include <pcl/PCLPointField.h>
53 #include <sensor_msgs/PointField.h>
54 
55 #include <pcl/PCLPointCloud2.h>
56 #include <sensor_msgs/PointCloud2.h>
57 
58 #include <pcl/PointIndices.h>
59 #include <pcl_msgs/PointIndices.h>
60 
61 #include <pcl/ModelCoefficients.h>
62 #include <pcl_msgs/ModelCoefficients.h>
63 
64 #include <pcl/Vertices.h>
65 #include <pcl_msgs/Vertices.h>
66 
67 #include <pcl/PolygonMesh.h>
68 #include <pcl_msgs/PolygonMesh.h>
69 
70 #include <pcl/io/pcd_io.h>
71 
72 #include <Eigen/StdVector>
73 #include <Eigen/Geometry>
74 
75 namespace pcl_conversions {
76 
79  inline
80  void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
81  {
82  stamp.fromNSec(pcl_stamp * 1000ull); // Convert from us to ns
83  }
84 
85  inline
86  void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
87  {
88  pcl_stamp = stamp.toNSec() / 1000ull; // Convert from ns to us
89  }
90 
91  inline
92  ros::Time fromPCL(const std::uint64_t &pcl_stamp)
93  {
94  ros::Time stamp;
95  fromPCL(pcl_stamp, stamp);
96  return stamp;
97  }
98 
99  inline
100  std::uint64_t toPCL(const ros::Time &stamp)
101  {
102  std::uint64_t pcl_stamp;
103  toPCL(stamp, pcl_stamp);
104  return pcl_stamp;
105  }
106 
109  inline
110  void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
111  {
112  fromPCL(pcl_header.stamp, header.stamp);
113  header.seq = pcl_header.seq;
114  header.frame_id = pcl_header.frame_id;
115  }
116 
117  inline
118  void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
119  {
120  toPCL(header.stamp, pcl_header.stamp);
121  pcl_header.seq = header.seq;
122  pcl_header.frame_id = header.frame_id;
123  }
124 
125  inline
126  std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
127  {
128  std_msgs::Header header;
129  fromPCL(pcl_header, header);
130  return header;
131  }
132 
133  inline
134  pcl::PCLHeader toPCL(const std_msgs::Header &header)
135  {
136  pcl::PCLHeader pcl_header;
137  toPCL(header, pcl_header);
138  return pcl_header;
139  }
140 
143  inline
144  void copyPCLImageMetaData(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
145  {
146  fromPCL(pcl_image.header, image.header);
147  image.height = pcl_image.height;
148  image.width = pcl_image.width;
149  image.encoding = pcl_image.encoding;
150  image.is_bigendian = pcl_image.is_bigendian;
151  image.step = pcl_image.step;
152  }
153 
154  inline
155  void fromPCL(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
156  {
157  copyPCLImageMetaData(pcl_image, image);
158  image.data = pcl_image.data;
159  }
160 
161  inline
162  void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
163  {
164  copyPCLImageMetaData(pcl_image, image);
165  image.data.swap(pcl_image.data);
166  }
167 
168  inline
169  void copyImageMetaData(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
170  {
171  toPCL(image.header, pcl_image.header);
172  pcl_image.height = image.height;
173  pcl_image.width = image.width;
174  pcl_image.encoding = image.encoding;
175  pcl_image.is_bigendian = image.is_bigendian;
176  pcl_image.step = image.step;
177  }
178 
179  inline
180  void toPCL(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
181  {
182  copyImageMetaData(image, pcl_image);
183  pcl_image.data = image.data;
184  }
185 
186  inline
187  void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
188  {
189  copyImageMetaData(image, pcl_image);
190  pcl_image.data.swap(image.data);
191  }
192 
195  inline
196  void fromPCL(const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf)
197  {
198  pf.name = pcl_pf.name;
199  pf.offset = pcl_pf.offset;
200  pf.datatype = pcl_pf.datatype;
201  pf.count = pcl_pf.count;
202  }
203 
204  inline
205  void fromPCL(const std::vector<pcl::PCLPointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
206  {
207  pfs.resize(pcl_pfs.size());
208  std::vector<pcl::PCLPointField>::const_iterator it = pcl_pfs.begin();
209  int i = 0;
210  for(; it != pcl_pfs.end(); ++it, ++i) {
211  fromPCL(*(it), pfs[i]);
212  }
213  std::sort(pfs.begin(), pfs.end(), [](const auto& field_a, const auto& field_b)
214  {
215  return field_a.offset < field_b.offset;
216  });
217  }
218 
219  inline
220  void toPCL(const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf)
221  {
222  pcl_pf.name = pf.name;
223  pcl_pf.offset = pf.offset;
224  pcl_pf.datatype = pf.datatype;
225  pcl_pf.count = pf.count;
226  }
227 
228  inline
229  void toPCL(const std::vector<sensor_msgs::PointField> &pfs, std::vector<pcl::PCLPointField> &pcl_pfs)
230  {
231  pcl_pfs.resize(pfs.size());
232  std::vector<sensor_msgs::PointField>::const_iterator it = pfs.begin();
233  int i = 0;
234  for(; it != pfs.end(); ++it, ++i) {
235  toPCL(*(it), pcl_pfs[i]);
236  }
237  }
238 
241  inline
242  void copyPCLPointCloud2MetaData(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
243  {
244  fromPCL(pcl_pc2.header, pc2.header);
245  pc2.height = pcl_pc2.height;
246  pc2.width = pcl_pc2.width;
247  fromPCL(pcl_pc2.fields, pc2.fields);
248  pc2.is_bigendian = pcl_pc2.is_bigendian;
249  pc2.point_step = pcl_pc2.point_step;
250  pc2.row_step = pcl_pc2.row_step;
251  pc2.is_dense = pcl_pc2.is_dense;
252  }
253 
254  inline
255  void fromPCL(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
256  {
257  copyPCLPointCloud2MetaData(pcl_pc2, pc2);
258  pc2.data = pcl_pc2.data;
259  }
260 
261  inline
262  void moveFromPCL(pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
263  {
264  copyPCLPointCloud2MetaData(pcl_pc2, pc2);
265  pc2.data.swap(pcl_pc2.data);
266  }
267 
268  inline
269  void copyPointCloud2MetaData(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
270  {
271  toPCL(pc2.header, pcl_pc2.header);
272  pcl_pc2.height = pc2.height;
273  pcl_pc2.width = pc2.width;
274  toPCL(pc2.fields, pcl_pc2.fields);
275  pcl_pc2.is_bigendian = pc2.is_bigendian;
276  pcl_pc2.point_step = pc2.point_step;
277  pcl_pc2.row_step = pc2.row_step;
278  pcl_pc2.is_dense = pc2.is_dense;
279  }
280 
281  inline
282  void toPCL(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
283  {
284  copyPointCloud2MetaData(pc2, pcl_pc2);
285  pcl_pc2.data = pc2.data;
286  }
287 
288  inline
289  void moveToPCL(sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
290  {
291  copyPointCloud2MetaData(pc2, pcl_pc2);
292  pcl_pc2.data.swap(pc2.data);
293  }
294 
297  inline
298  void fromPCL(const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
299  {
300  fromPCL(pcl_pi.header, pi.header);
301  pi.indices = pcl_pi.indices;
302  }
303 
304  inline
305  void moveFromPCL(pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
306  {
307  fromPCL(pcl_pi.header, pi.header);
308  pi.indices.swap(pcl_pi.indices);
309  }
310 
311  inline
312  void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
313  {
314  toPCL(pi.header, pcl_pi.header);
315  pcl_pi.indices = pi.indices;
316  }
317 
318  inline
319  void moveToPCL(pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
320  {
321  toPCL(pi.header, pcl_pi.header);
322  pcl_pi.indices.swap(pi.indices);
323  }
324 
327  inline
328  void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
329  {
330  fromPCL(pcl_mc.header, mc.header);
331  mc.values = pcl_mc.values;
332  }
333 
334  inline
335  void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
336  {
337  fromPCL(pcl_mc.header, mc.header);
338  mc.values.swap(pcl_mc.values);
339  }
340 
341  inline
342  void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
343  {
344  toPCL(mc.header, pcl_mc.header);
345  pcl_mc.values = mc.values;
346  }
347 
348  inline
349  void moveToPCL(pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
350  {
351  toPCL(mc.header, pcl_mc.header);
352  pcl_mc.values.swap(mc.values);
353  }
354 
357  namespace internal
358  {
359  template <class T>
360  inline void move(std::vector<T> &a, std::vector<T> &b)
361  {
362  b.swap(a);
363  }
364 
365  template <class T1, class T2>
366  inline void move(std::vector<T1> &a, std::vector<T2> &b)
367  {
368  b.assign(a.cbegin(), a.cend());
369  }
370  }
371 
372  inline
373  void fromPCL(const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
374  {
375  vert.vertices.assign(pcl_vert.vertices.cbegin(), pcl_vert.vertices.cend());
376  }
377 
378  inline
379  void fromPCL(const std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
380  {
381  verts.resize(pcl_verts.size());
382  std::vector<pcl::Vertices>::const_iterator it = pcl_verts.begin();
383  std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
384  for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
385  fromPCL(*(it), *(jt));
386  }
387  }
388 
389  inline
390  void moveFromPCL(pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
391  {
392  internal::move(pcl_vert.vertices, vert.vertices);
393  }
394 
395  inline
396  void fromPCL(std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
397  {
398  verts.resize(pcl_verts.size());
399  std::vector<pcl::Vertices>::iterator it = pcl_verts.begin();
400  std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
401  for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
402  moveFromPCL(*(it), *(jt));
403  }
404  }
405 
406  inline
407  void toPCL(const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
408  {
409  pcl_vert.vertices.assign(vert.vertices.cbegin(), vert.vertices.cend());
410  }
411 
412  inline
413  void toPCL(const std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
414  {
415  pcl_verts.resize(verts.size());
416  std::vector<pcl_msgs::Vertices>::const_iterator it = verts.begin();
417  std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
418  for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
419  toPCL(*(it), *(jt));
420  }
421  }
422 
423  inline
424  void moveToPCL(pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
425  {
426  internal::move(vert.vertices, pcl_vert.vertices);
427  }
428 
429  inline
430  void moveToPCL(std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
431  {
432  pcl_verts.resize(verts.size());
433  std::vector<pcl_msgs::Vertices>::iterator it = verts.begin();
434  std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
435  for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
436  moveToPCL(*(it), *(jt));
437  }
438  }
439 
442  inline
443  void fromPCL(const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
444  {
445  fromPCL(pcl_mesh.header, mesh.header);
446  fromPCL(pcl_mesh.cloud, mesh.cloud);
447  fromPCL(pcl_mesh.polygons, mesh.polygons);
448  }
449 
450  inline
451  void moveFromPCL(pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
452  {
453  fromPCL(pcl_mesh.header, mesh.header);
454  moveFromPCL(pcl_mesh.cloud, mesh.cloud);
455  }
456 
457  inline
458  void toPCL(const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
459  {
460  toPCL(mesh.header, pcl_mesh.header);
461  toPCL(mesh.cloud, pcl_mesh.cloud);
462  toPCL(mesh.polygons, pcl_mesh.polygons);
463  }
464 
465  inline
466  void moveToPCL(pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
467  {
468  toPCL(mesh.header, pcl_mesh.header);
469  moveToPCL(mesh.cloud, pcl_mesh.cloud);
470  moveToPCL(mesh.polygons, pcl_mesh.polygons);
471  }
472 
473 } // namespace pcl_conversions
474 
475 namespace pcl {
476 
479  inline int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
480  {
481  // Get the index we need
482  for (size_t d = 0; d < cloud.fields.size(); ++d) {
483  if (cloud.fields[d].name == field_name) {
484  return (static_cast<int>(d));
485  }
486  }
487  return (-1);
488  }
489 
492  inline std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
493  {
494  std::string result;
495  for (size_t i = 0; i < cloud.fields.size () - 1; ++i) {
496  result += cloud.fields[i].name + " ";
497  }
498  result += cloud.fields[cloud.fields.size () - 1].name;
499  return (result);
500  }
501 
504  inline
505  void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
506  {
507  pcl::PCLPointCloud2 pcl_cloud;
508  pcl_conversions::toPCL(cloud, pcl_cloud);
509  pcl::PCLImage pcl_image;
510  pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
511  pcl_conversions::moveFromPCL(pcl_image, image);
512  }
513 
514  inline
515  void moveToROSMsg(sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
516  {
517  pcl::PCLPointCloud2 pcl_cloud;
518  pcl_conversions::moveToPCL(cloud, pcl_cloud);
519  pcl::PCLImage pcl_image;
520  pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
521  pcl_conversions::moveFromPCL(pcl_image, image);
522  }
523 
524  template<typename T> void
525  toROSMsg (const pcl::PointCloud<T> &cloud, sensor_msgs::Image& msg)
526  {
527  // Ease the user's burden on specifying width/height for unorganized datasets
528  if (cloud.width == 0 && cloud.height == 0)
529  {
530  throw std::runtime_error("Needs to be a dense like cloud!!");
531  }
532  else
533  {
534  if (cloud.points.size () != cloud.width * cloud.height)
535  throw std::runtime_error("The width and height do not match the cloud size!");
536  msg.height = cloud.height;
537  msg.width = cloud.width;
538  }
539 
540  // sensor_msgs::image_encodings::BGR8;
541  msg.encoding = "bgr8";
542  msg.step = msg.width * sizeof (std::uint8_t) * 3;
543  msg.data.resize (msg.step * msg.height);
544  for (size_t y = 0; y < cloud.height; y++)
545  {
546  for (size_t x = 0; x < cloud.width; x++)
547  {
548  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
549  memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(std::uint8_t));
550  }
551  }
552  }
553 
556  template<typename T>
557  void toROSMsg(const pcl::PointCloud<T> &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
558  {
559  pcl::PCLPointCloud2 pcl_pc2;
560 #if PCL_VERSION_COMPARE(>=, 1, 14, 1)
561  // if PCL version is recent enough, request that all padding be removed to make the msg as small as possible
562  pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2, false);
563 #else
564  pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
565 #endif
566  pcl_conversions::moveFromPCL(pcl_pc2, cloud);
567  }
568 
569  template<typename T>
570  void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
571  {
572  pcl::PCLPointCloud2 pcl_pc2;
573 #if PCL_VERSION_COMPARE(>=, 1, 13, 1)
574  pcl_conversions::copyPointCloud2MetaData(cloud, pcl_pc2); // Like pcl_conversions::toPCL, but does not copy the binary data
575  pcl::MsgFieldMap field_map;
576  pcl::createMapping<T> (pcl_pc2.fields, field_map);
577  pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud, field_map, &cloud.data[0]);
578 #else
579  pcl_conversions::toPCL(cloud, pcl_pc2);
580  pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
581 #endif
582  }
583 
584  template<typename T>
585  void moveFromROSMsg(sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
586  {
587  pcl::PCLPointCloud2 pcl_pc2;
588  pcl_conversions::moveToPCL(cloud, pcl_pc2);
589  pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
590  }
591 
594  template<typename PointT>
595  void createMapping(const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
596  {
597  std::vector<pcl::PCLPointField> pcl_msg_fields;
598  pcl_conversions::toPCL(msg_fields, pcl_msg_fields);
599  return createMapping<PointT>(pcl_msg_fields, field_map);
600  }
601 
602  namespace io {
603 
606  inline int
607  savePCDFile(const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
608  const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
609  const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
610  const bool binary_mode = false)
611  {
612  pcl::PCLPointCloud2 pcl_cloud;
613  pcl_conversions::toPCL(cloud, pcl_cloud);
614  return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode);
615  }
616 
617  inline int
618  destructiveSavePCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
619  const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
620  const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
621  const bool binary_mode = false)
622  {
623  pcl::PCLPointCloud2 pcl_cloud;
624  pcl_conversions::moveToPCL(cloud, pcl_cloud);
625  return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode);
626  }
627 
630  inline int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
631  {
632  pcl::PCLPointCloud2 pcl_cloud;
633  int ret = pcl::io::loadPCDFile(file_name, pcl_cloud);
634  pcl_conversions::moveFromPCL(pcl_cloud, cloud);
635  return ret;
636  }
637 
638  } // namespace io
639 
642  inline
643  bool concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1,
644  const sensor_msgs::PointCloud2 &cloud2,
645  sensor_msgs::PointCloud2 &cloud_out)
646  {
647  //if one input cloud has no points, but the other input does, just return the cloud with points
648  if (cloud1.width * cloud1.height == 0 && cloud2.width * cloud2.height > 0)
649  {
650  cloud_out = cloud2;
651  return (true);
652  }
653  else if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0)
654  {
655  cloud_out = cloud1;
656  return (true);
657  }
658 
659  bool strip = false;
660  for (size_t i = 0; i < cloud1.fields.size (); ++i)
661  if (cloud1.fields[i].name == "_")
662  strip = true;
663 
664  for (size_t i = 0; i < cloud2.fields.size (); ++i)
665  if (cloud2.fields[i].name == "_")
666  strip = true;
667 
668  if (!strip && cloud1.fields.size () != cloud2.fields.size ())
669  {
670  PCL_ERROR ("[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ());
671  return (false);
672  }
673 
674  // Copy cloud1 into cloud_out
675  cloud_out = cloud1;
676  size_t nrpts = cloud_out.data.size ();
677  // Height = 1 => no more organized
678  cloud_out.width = cloud1.width * cloud1.height + cloud2.width * cloud2.height;
679  cloud_out.height = 1;
680  if (!cloud1.is_dense || !cloud2.is_dense)
681  cloud_out.is_dense = false;
682  else
683  cloud_out.is_dense = true;
684 
685  // We need to strip the extra padding fields
686  if (strip)
687  {
688  // Get the field sizes for the second cloud
689  std::vector<sensor_msgs::PointField> fields2;
690  std::vector<int> fields2_sizes;
691  for (size_t j = 0; j < cloud2.fields.size (); ++j)
692  {
693  if (cloud2.fields[j].name == "_")
694  continue;
695 
696  fields2_sizes.push_back (cloud2.fields[j].count *
697  pcl::getFieldSize (cloud2.fields[j].datatype));
698  fields2.push_back (cloud2.fields[j]);
699  }
700 
701  cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step);
702 
703  // Copy the second cloud
704  for (size_t cp = 0; cp < cloud2.width * cloud2.height; ++cp)
705  {
706  int i = 0;
707  for (size_t j = 0; j < fields2.size (); ++j)
708  {
709  if (cloud1.fields[i].name == "_")
710  {
711  ++i;
712  continue;
713  }
714 
715  // We're fine with the special RGB vs RGBA use case
716  if ((cloud1.fields[i].name == "rgb" && fields2[j].name == "rgba") ||
717  (cloud1.fields[i].name == "rgba" && fields2[j].name == "rgb") ||
718  (cloud1.fields[i].name == fields2[j].name))
719  {
720  memcpy (reinterpret_cast<char*> (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]),
721  reinterpret_cast<const char*> (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]),
722  fields2_sizes[j]);
723  ++i; // increment the field size i
724  }
725  }
726  }
727  }
728  else
729  {
730  for (size_t i = 0; i < cloud1.fields.size (); ++i)
731  {
732  // We're fine with the special RGB vs RGBA use case
733  if ((cloud1.fields[i].name == "rgb" && cloud2.fields[i].name == "rgba") ||
734  (cloud1.fields[i].name == "rgba" && cloud2.fields[i].name == "rgb"))
735  continue;
736  // Otherwise we need to make sure the names are the same
737  if (cloud1.fields[i].name != cloud2.fields[i].name)
738  {
739  PCL_ERROR ("[pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s\n", i, cloud1.fields[i].name.c_str (), cloud2.fields[i].name.c_str ());
740  return (false);
741  }
742  }
743  cloud_out.data.resize (nrpts + cloud2.data.size ());
744  memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ());
745  }
746  return (true);
747  }
748 
749 } // namespace pcl
750 
751 namespace ros
752 {
753  template<>
754  struct DefaultMessageCreator<pcl::PCLPointCloud2>
755  {
757  {
758  boost::shared_ptr<pcl::PCLPointCloud2> msg(new pcl::PCLPointCloud2());
759  return msg;
760  }
761  };
762 
763  namespace message_traits
764  {
765  template<>
766  struct MD5Sum<pcl::PCLPointCloud2>
767  {
768  static const char* value() { return MD5Sum<sensor_msgs::PointCloud2>::value(); }
769  static const char* value(const pcl::PCLPointCloud2&) { return value(); }
770 
771  static const uint64_t static_value1 = MD5Sum<sensor_msgs::PointCloud2>::static_value1;
772  static const uint64_t static_value2 = MD5Sum<sensor_msgs::PointCloud2>::static_value2;
773 
774  // If the definition of sensor_msgs/PointCloud2 changes, we'll get a compile error here.
775  ROS_STATIC_ASSERT(static_value1 == 0x1158d486dd51d683ULL);
776  ROS_STATIC_ASSERT(static_value2 == 0xce2f1be655c3c181ULL);
777  };
778 
779  template<>
780  struct DataType<pcl::PCLPointCloud2>
781  {
782  static const char* value() { return DataType<sensor_msgs::PointCloud2>::value(); }
783  static const char* value(const pcl::PCLPointCloud2&) { return value(); }
784  };
785 
786  template<>
787  struct Definition<pcl::PCLPointCloud2>
788  {
789  static const char* value() { return Definition<sensor_msgs::PointCloud2>::value(); }
790  static const char* value(const pcl::PCLPointCloud2&) { return value(); }
791  };
792 
793  template<> struct HasHeader<pcl::PCLPointCloud2> : TrueType {};
794  } // namespace ros::message_traits
795 
796  namespace serialization
797  {
798  /*
799  * Provide a custom serialization for pcl::PCLPointCloud2
800  */
801  template<>
802  struct Serializer<pcl::PCLPointCloud2>
803  {
804  template<typename Stream>
805  inline static void write(Stream& stream, const pcl::PCLPointCloud2& m)
806  {
807  std_msgs::Header header;
808  pcl_conversions::fromPCL(m.header, header);
809  stream.next(header);
810  stream.next(m.height);
811  stream.next(m.width);
812  std::vector<sensor_msgs::PointField> pfs;
813  pcl_conversions::fromPCL(m.fields, pfs);
814  stream.next(pfs);
815  stream.next(m.is_bigendian);
816  stream.next(m.point_step);
817  stream.next(m.row_step);
818  stream.next(m.data);
819  stream.next(m.is_dense);
820  }
821 
822  template<typename Stream>
823  inline static void read(Stream& stream, pcl::PCLPointCloud2& m)
824  {
825  std_msgs::Header header;
826  stream.next(header);
827  pcl_conversions::toPCL(header, m.header);
828  stream.next(m.height);
829  stream.next(m.width);
830  std::vector<sensor_msgs::PointField> pfs;
831  stream.next(pfs);
832  pcl_conversions::toPCL(pfs, m.fields);
833  stream.next(m.is_bigendian);
834  stream.next(m.point_step);
835  stream.next(m.row_step);
836  stream.next(m.data);
837  stream.next(m.is_dense);
838  }
839 
840  inline static uint32_t serializedLength(const pcl::PCLPointCloud2& m)
841  {
842  uint32_t length = 0;
843 
844  std_msgs::Header header;
845  pcl_conversions::fromPCL(m.header, header);
846  length += serializationLength(header);
847  length += 4; // height
848  length += 4; // width
849  std::vector<sensor_msgs::PointField> pfs;
850  pcl_conversions::fromPCL(m.fields, pfs);
851  length += serializationLength(pfs); // fields
852  length += 1; // is_bigendian
853  length += 4; // point_step
854  length += 4; // row_step
855  length += 4; // data's size
856  length += m.data.size() * sizeof(std::uint8_t);
857  length += 1; // is_dense
858 
859  return length;
860  }
861  };
862 
863  /*
864  * Provide a custom serialization for pcl::PCLPointField
865  */
866  template<>
867  struct Serializer<pcl::PCLPointField>
868  {
869  template<typename Stream>
870  inline static void write(Stream& stream, const pcl::PCLPointField& m)
871  {
872  stream.next(m.name);
873  stream.next(m.offset);
874  stream.next(m.datatype);
875  stream.next(m.count);
876  }
877 
878  template<typename Stream>
879  inline static void read(Stream& stream, pcl::PCLPointField& m)
880  {
881  stream.next(m.name);
882  stream.next(m.offset);
883  stream.next(m.datatype);
884  stream.next(m.count);
885  }
886 
887  inline static uint32_t serializedLength(const pcl::PCLPointField& m)
888  {
889  uint32_t length = 0;
890 
891  length += serializationLength(m.name);
892  length += serializationLength(m.offset);
893  length += serializationLength(m.datatype);
894  length += serializationLength(m.count);
895 
896  return length;
897  }
898  };
899 
900  /*
901  * Provide a custom serialization for pcl::PCLHeader
902  */
903  template<>
904  struct Serializer<pcl::PCLHeader>
905  {
906  template<typename Stream>
907  inline static void write(Stream& stream, const pcl::PCLHeader& m)
908  {
909  std_msgs::Header header;
911  stream.next(header);
912  }
913 
914  template<typename Stream>
915  inline static void read(Stream& stream, pcl::PCLHeader& m)
916  {
917  std_msgs::Header header;
918  stream.next(header);
920  }
921 
922  inline static uint32_t serializedLength(const pcl::PCLHeader& m)
923  {
924  uint32_t length = 0;
925 
926  std_msgs::Header header;
928  length += serializationLength(header);
929 
930  return length;
931  }
932  };
933  } // namespace ros::serialization
934 
935 } // namespace ros
936 
937 
938 #endif /* PCL_CONVERSIONS_H__ */
pcl::createMapping
void createMapping(const std::vector< sensor_msgs::PointField > &msg_fields, MsgFieldMap &field_map)
Definition: pcl_conversions.h:595
ros::message_traits::TrueType
pcl
Definition: pcl_conversions.h:475
pcl::moveFromROSMsg
void moveFromROSMsg(sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
Definition: pcl_conversions.h:585
boost::shared_ptr
pcl::getFieldsList
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
Definition: pcl_conversions.h:492
ros::serialization::Serializer< pcl::PCLPointCloud2 >::read
static void read(Stream &stream, pcl::PCLPointCloud2 &m)
Definition: pcl_conversions.h:823
ros::serialization::Serializer< pcl::PCLPointField >::serializedLength
static uint32_t serializedLength(const pcl::PCLPointField &m)
Definition: pcl_conversions.h:887
pcl::moveToROSMsg
void moveToROSMsg(sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
Definition: pcl_conversions.h:515
pcl_conversions
Definition: pcl_conversions.h:75
pcl::io::destructiveSavePCDFile
int destructiveSavePCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary_mode=false)
Definition: pcl_conversions.h:618
ros
ros.h
ros::serialization::Serializer< pcl::PCLPointCloud2 >::write
static void write(Stream &stream, const pcl::PCLPointCloud2 &m)
Definition: pcl_conversions.h:805
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
ros::serialization::Stream
ros::message_traits::DataType
ros::message_traits::Definition< pcl::PCLPointCloud2 >::value
static const char * value()
Definition: pcl_conversions.h:789
ros::message_traits::DataType< pcl::PCLPointCloud2 >::value
static const char * value()
Definition: pcl_conversions.h:782
ros::message_traits::HasHeader
ros::serialization::Serializer< pcl::PCLHeader >::serializedLength
static uint32_t serializedLength(const pcl::PCLHeader &m)
Definition: pcl_conversions.h:922
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
Definition: pcl_conversions.h:162
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
Definition: pcl_conversions.h:570
ros::message_traits::Definition< pcl::PCLPointCloud2 >::value
static const char * value(const pcl::PCLPointCloud2 &)
Definition: pcl_conversions.h:790
ros::serialization::Serializer< pcl::PCLPointField >::write
static void write(Stream &stream, const pcl::PCLPointField &m)
Definition: pcl_conversions.h:870
ros::message_traits::DataType< pcl::PCLPointCloud2 >::value
static const char * value(const pcl::PCLPointCloud2 &)
Definition: pcl_conversions.h:783
ros::DefaultMessageCreator
ros::message_traits::MD5Sum< pcl::PCLPointCloud2 >::value
static const char * value(const pcl::PCLPointCloud2 &)
Definition: pcl_conversions.h:769
ros::message_traits::DataType::value
static const char * value()
pcl_conversions::fromPCL
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
Definition: pcl_conversions.h:80
ros::serialization::Serializer< pcl::PCLPointCloud2 >::serializedLength
static uint32_t serializedLength(const pcl::PCLPointCloud2 &m)
Definition: pcl_conversions.h:840
ros::message_traits::MD5Sum::value
static const char * value()
pcl::concatenatePointCloud
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
Definition: pcl_conversions.h:643
pcl_conversions::moveToPCL
void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
Definition: pcl_conversions.h:187
d
d
ros::DefaultMessageCreator::operator()
boost::shared_ptr< M > operator()()
ros::message_traits::MD5Sum
pcl::io::loadPCDFile
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
Definition: pcl_conversions.h:630
pcl_conversions::copyImageMetaData
void copyImageMetaData(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
Definition: pcl_conversions.h:169
pcl_conversions::toPCL
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
Definition: pcl_conversions.h:86
pcl_conversions::copyPCLImageMetaData
void copyPCLImageMetaData(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
Definition: pcl_conversions.h:144
TimeBase< Time, Duration >::fromNSec
Time & fromNSec(uint64_t t)
ros::Time
ros::serialization::Serializer< pcl::PCLPointField >::read
static void read(Stream &stream, pcl::PCLPointField &m)
Definition: pcl_conversions.h:879
pcl_conversions::copyPCLPointCloud2MetaData
void copyPCLPointCloud2MetaData(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
Definition: pcl_conversions.h:242
pcl::toROSMsg
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
Definition: pcl_conversions.h:505
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
pcl_conversions::copyPointCloud2MetaData
void copyPointCloud2MetaData(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
Definition: pcl_conversions.h:269
ros::message_traits::Definition::value
static const char * value()
ros::serialization::Serializer< pcl::PCLHeader >::write
static void write(Stream &stream, const pcl::PCLHeader &m)
Definition: pcl_conversions.h:907
ROS_STATIC_ASSERT
#define ROS_STATIC_ASSERT(cond)
ros::message_traits::Definition
header
const std::string header
ros::serialization::Serializer< pcl::PCLHeader >::read
static void read(Stream &stream, pcl::PCLHeader &m)
Definition: pcl_conversions.h:915
pcl::io::savePCDFile
int savePCDFile(const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary_mode=false)
Definition: pcl_conversions.h:607
ros::message_traits::MD5Sum< pcl::PCLPointCloud2 >::value
static const char * value()
Definition: pcl_conversions.h:768
ros::serialization::Serializer
pcl::getFieldIndex
int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
Definition: pcl_conversions.h:479
pcl_conversions::internal::move
void move(std::vector< T > &a, std::vector< T > &b)
Definition: pcl_conversions.h:360


pcl_conversions
Author(s): William Woodall
autogenerated on Fri Jul 12 2024 02:54:37