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


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09