Point Cloud Library (PCL)  1.15.1-dev
io.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior 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  * $Id$
38  *
39  */
40 
41 #pragma once
42 
43 #include <numeric>
44 #include <string>
45 
46 #include <pcl/point_cloud.h>
47 #include <pcl/PointIndices.h>
48 #include <pcl/pcl_macros.h>
49 #include <pcl/PolygonMesh.h>
50 #include <locale>
51 
52 namespace pcl
53 {
54  /** \brief Get the index of a specified field (i.e., dimension/channel)
55  * \param[in] cloud the point cloud message
56  * \param[in] field_name the string defining the field name
57  * \return the index of the field or a negative integer if no field with the given name exists
58  * \ingroup common
59  */
60  inline int
61  getFieldIndex (const pcl::PCLPointCloud2 &cloud, const std::string &field_name)
62  {
63  // Get the index we need
64  const auto result = std::find_if(cloud.fields.begin (), cloud.fields.end (),
65  [&field_name](const auto field) { return field.name == field_name; });
66  if (result == cloud.fields.end ())
67  return -1;
68  return std::distance(cloud.fields.begin (), result);
69  }
70 
71  /** \brief Get the index of a specified field (i.e., dimension/channel)
72  * \tparam PointT datatype for which fields is being queries
73  * \param[in] field_name the string defining the field name
74  * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains
75  * \return the index of the field or a negative integer if no field with the given name exists
76  * \ingroup common
77  */
78  template <typename PointT> inline int
79  getFieldIndex (const std::string &field_name,
80  std::vector<pcl::PCLPointField> &fields);
81  /** \brief Get the index of a specified field (i.e., dimension/channel)
82  * \tparam PointT datatype for which fields is being queries
83  * \param[in] field_name the string defining the field name
84  * \param[in] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains
85  * \ingroup common
86  */
87  template <typename PointT> inline int
88  getFieldIndex (const std::string &field_name,
89  const std::vector<pcl::PCLPointField> &fields);
90 
91  /** \brief Get the list of available fields (i.e., dimension/channel)
92  * \tparam PointT datatype whose details are requested
93  * \ingroup common
94  */
95  template <typename PointT> inline std::vector<pcl::PCLPointField>
96  getFields ();
97 
98  /** \brief Get the list of available fields (i.e., dimension/channel) from cloud type,
99  * not point type
100  * \tparam CloudT cloud type, PointCloud or PCLPointCloud2
101  * \param cloud input cloud. Unsused for PointCloud, needed for PCLPointCloud2 because the fields are not available statically
102  * \ingroup common
103  */
104  template <typename CloudT> inline std::vector<pcl::PCLPointField>
105  getFields (const CloudT& cloud) ;
106 
107 
108  /** \brief Get the list of all fields available in a given cloud
109  * \param[in] cloud the point cloud message
110  * \ingroup common
111  */
112  template <typename PointT> inline std::string
113  getFieldsList (const pcl::PointCloud<PointT> &cloud);
114 
115  /** \brief Get the available point cloud fields as a space separated string
116  * \param[in] cloud a pointer to the PointCloud message
117  * \ingroup common
118  */
119  inline std::string
121  {
122  if (cloud.fields.empty())
123  {
124  return "";
125  } else
126  {
127  return std::accumulate(std::next (cloud.fields.begin ()), cloud.fields.end (), cloud.fields[0].name,
128  [](const auto& acc, const auto& field) { return acc + " " + field.name; });
129  }
130  }
131 
132  /** \brief Obtains the size of a specific field data type in bytes
133  * \param[in] datatype the field data type (see PCLPointField.h)
134  * \ingroup common
135  */
136  inline int
137  getFieldSize (const int datatype)
138  {
139  switch (datatype)
140  {
142  return sizeof(bool);
143 
146  return (1);
147 
150  return (2);
151 
155  return (4);
156 
160  return (8);
161 
162  default:
163  return (0);
164  }
165  }
166 
167  /** \brief Obtain a vector with the sizes of all valid fields (e.g., not "_")
168  * \param[in] fields the input vector containing the fields
169  * \param[out] field_sizes the resultant field sizes in bytes
170  */
171  PCL_EXPORTS void
172  getFieldsSizes (const std::vector<pcl::PCLPointField> &fields,
173  std::vector<int> &field_sizes);
174 
175  /** \brief Obtains the type of the PCLPointField from a specific size and type
176  * \param[in] size the size in bytes of the data field
177  * \param[in] type a char describing the type of the field ('B' = bool, 'F' = float, 'I' = signed, 'U' = unsigned)
178  * \ingroup common
179  */
180  inline int
181  getFieldType (const int size, char type)
182  {
183  type = std::toupper (type, std::locale::classic ());
184 
185  // extra logic for bool because its size is undefined
186  if (type == 'B') {
187  if (size == sizeof(bool)) {
189  } else {
190  return -1;
191  }
192  }
193 
194  switch (size)
195  {
196  case 1:
197  if (type == 'I')
198  return (pcl::PCLPointField::INT8);
199  if (type == 'U')
200  return (pcl::PCLPointField::UINT8);
201  break;
202 
203  case 2:
204  if (type == 'I')
205  return (pcl::PCLPointField::INT16);
206  if (type == 'U')
208  break;
209 
210  case 4:
211  if (type == 'I')
212  return (pcl::PCLPointField::INT32);
213  if (type == 'U')
215  if (type == 'F')
217  break;
218 
219  case 8:
220  if (type == 'I')
221  return (pcl::PCLPointField::INT64);
222  if (type == 'U')
224  if (type == 'F')
226  break;
227  }
228  return (-1);
229  }
230 
231  /** \brief Obtains the type of the PCLPointField from a specific PCLPointField as a char
232  * \param[in] type the PCLPointField field type
233  * \ingroup common
234  */
235  inline char
236  getFieldType (const int type)
237  {
238  switch (type)
239  {
241  return ('B');
242 
247  return ('I');
248 
253  return ('U');
254 
257  return ('F');
258 
259  default:
260  return ('?');
261  }
262  }
263 
264  /**
265  * \brief Get the value of a point field from raw data pointer and field type.
266  *
267  * \tparam T return type the field will be cast as
268  * \param data data pointer
269  * \param type point field type
270  * \ingroup common
271  *
272  * \return field value
273  */
274  template <typename T> T point_field_as (const std::uint8_t* data, const std::uint8_t type);
275 
276 
278  {
283  };
284 
285  /** \brief \return the right index according to the interpolation type.
286  * \note this is adapted from OpenCV
287  * \param p the index of point to interpolate
288  * \param length the top/bottom row or left/right column index
289  * \param type the requested interpolation
290  * \throws pcl::BadArgumentException if type is unknown
291  */
292  PCL_EXPORTS int
293  interpolatePointIndex (int p, int length, InterpolationType type);
294 
295  /** \brief Concatenate two pcl::PointCloud<PointT>
296  * \param[in] cloud1 the first input point cloud dataset
297  * \param[in] cloud2 the second input point cloud dataset
298  * \param[out] cloud_out the resultant output point cloud dataset
299  * \return true if successful, false otherwise
300  * \ingroup common
301  */
302  template <typename PointT>
303  bool
305  const pcl::PointCloud<PointT> &cloud2,
306  pcl::PointCloud<PointT> &cloud_out)
307  {
308  return pcl::PointCloud<PointT>::concatenate(cloud1, cloud2, cloud_out);
309  }
310 
311  /** \brief Concatenate two pcl::PCLPointCloud2
312  *
313  * \warning This function will concatenate IFF the non-skip fields are in the correct
314  * order and same in number.
315  * \param[in] cloud1 the first input point cloud dataset
316  * \param[in] cloud2 the second input point cloud dataset
317  * \param[out] cloud_out the resultant output point cloud dataset
318  * \return true if successful, false otherwise
319  * \ingroup common
320  */
321  inline bool
323  const pcl::PCLPointCloud2 &cloud2,
324  pcl::PCLPointCloud2 &cloud_out)
325  {
326  return pcl::PCLPointCloud2::concatenate(cloud1, cloud2, cloud_out);
327  }
328 
329  /** \brief Concatenate two pcl::PolygonMesh
330  * \param[in] mesh1 the first input mesh
331  * \param[in] mesh2 the second input mesh
332  * \param[out] mesh_out the resultant output mesh
333  * \return true if successful, false otherwise
334  * \ingroup common
335  */
336  inline bool
338  const pcl::PolygonMesh &mesh2,
339  pcl::PolygonMesh &mesh_out)
340  {
341  return pcl::PolygonMesh::concatenate(mesh1, mesh2, mesh_out);
342  }
343 
344  /** \brief Extract the indices of a given point cloud as a new point cloud
345  * \param[in] cloud_in the input point cloud dataset
346  * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in
347  * \param[out] cloud_out the resultant output point cloud dataset
348  * \note Assumes unique indices.
349  * \ingroup common
350  */
351  PCL_EXPORTS void
353  const Indices &indices,
354  pcl::PCLPointCloud2 &cloud_out);
355 
356  /** \brief Extract the indices of a given point cloud as a new point cloud
357  * \param[in] cloud_in the input point cloud dataset
358  * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in
359  * \param[out] cloud_out the resultant output point cloud dataset
360  * \note Assumes unique indices.
361  * \ingroup common
362  */
363  PCL_EXPORTS void
365  const IndicesAllocator< Eigen::aligned_allocator<index_t> > &indices,
366  pcl::PCLPointCloud2 &cloud_out);
367 
368  /** \brief Copy fields and point cloud data from \a cloud_in to \a cloud_out
369  * \param[in] cloud_in the input point cloud dataset
370  * \param[out] cloud_out the resultant output point cloud dataset
371  * \ingroup common
372  */
373  PCL_EXPORTS void
375  pcl::PCLPointCloud2 &cloud_out);
376 
377  /** \brief Check if two given point types are the same or not. */
378 template <typename Point1T, typename Point2T> constexpr bool
379  isSamePointType() noexcept
380  {
381  return (std::is_same<remove_cvref_t<Point1T>, remove_cvref_t<Point2T>>::value);
382  }
383 
384  /** \brief Extract the indices of a given point cloud as a new point cloud
385  * \param[in] cloud_in the input point cloud dataset
386  * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in
387  * \param[out] cloud_out the resultant output point cloud dataset
388  * \note Assumes unique indices.
389  * \ingroup common
390  */
391  template <typename PointT, typename IndicesVectorAllocator = std::allocator<index_t>> void
392  copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
393  const IndicesAllocator< IndicesVectorAllocator> &indices,
394  pcl::PointCloud<PointT> &cloud_out);
395 
396  /** \brief Extract the indices of a given point cloud as a new point cloud
397  * \param[in] cloud_in the input point cloud dataset
398  * \param[in] indices the PointIndices structure representing the points to be copied from cloud_in
399  * \param[out] cloud_out the resultant output point cloud dataset
400  * \note Assumes unique indices.
401  * \ingroup common
402  */
403  template <typename PointT> void
404  copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
405  const PointIndices &indices,
406  pcl::PointCloud<PointT> &cloud_out);
407 
408  /** \brief Extract the indices of a given point cloud as a new point cloud
409  * \param[in] cloud_in the input point cloud dataset
410  * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in
411  * \param[out] cloud_out the resultant output point cloud dataset
412  * \note Assumes unique indices.
413  * \ingroup common
414  */
415  template <typename PointT> void
416  copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
417  const std::vector<pcl::PointIndices> &indices,
418  pcl::PointCloud<PointT> &cloud_out);
419 
420  /** \brief Copy all the fields from a given point cloud into a new point cloud
421  * \param[in] cloud_in the input point cloud dataset
422  * \param[out] cloud_out the resultant output point cloud dataset
423  * \ingroup common
424  */
425  template <typename PointInT, typename PointOutT> void
426  copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
427  pcl::PointCloud<PointOutT> &cloud_out);
428 
429  /** \brief Extract the indices of a given point cloud as a new point cloud
430  * \param[in] cloud_in the input point cloud dataset
431  * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in
432  * \param[out] cloud_out the resultant output point cloud dataset
433  * \note Assumes unique indices.
434  * \ingroup common
435  */
436  template <typename PointInT, typename PointOutT, typename IndicesVectorAllocator = std::allocator<index_t>> void
437  copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
438  const IndicesAllocator<IndicesVectorAllocator> &indices,
439  pcl::PointCloud<PointOutT> &cloud_out);
440 
441  /** \brief Extract the indices of a given point cloud as a new point cloud
442  * \param[in] cloud_in the input point cloud dataset
443  * \param[in] indices the PointIndices structure representing the points to be copied from cloud_in
444  * \param[out] cloud_out the resultant output point cloud dataset
445  * \note Assumes unique indices.
446  * \ingroup common
447  */
448  template <typename PointInT, typename PointOutT> void
449  copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
450  const PointIndices &indices,
451  pcl::PointCloud<PointOutT> &cloud_out);
452 
453  /** \brief Extract the indices of a given point cloud as a new point cloud
454  * \param[in] cloud_in the input point cloud dataset
455  * \param[in] indices the vector of indices representing the points to be copied from cloud_in
456  * \param[out] cloud_out the resultant output point cloud dataset
457  * \note Assumes unique indices.
458  * \ingroup common
459  */
460  template <typename PointInT, typename PointOutT> void
461  copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
462  const std::vector<pcl::PointIndices> &indices,
463  pcl::PointCloud<PointOutT> &cloud_out);
464 
465  /** \brief Copy a point cloud inside a larger one interpolating borders.
466  * \param[in] cloud_in the input point cloud dataset
467  * \param[out] cloud_out the resultant output point cloud dataset
468  * \param top
469  * \param bottom
470  * \param left
471  * \param right
472  * Position of cloud_in inside cloud_out is given by \a top, \a left, \a bottom \a right.
473  * \param[in] border_type the interpolating method (pcl::BORDER_XXX)
474  * BORDER_REPLICATE: aaaaaa|abcdefgh|hhhhhhh
475  * BORDER_REFLECT: fedcba|abcdefgh|hgfedcb
476  * BORDER_REFLECT_101: gfedcb|abcdefgh|gfedcba
477  * BORDER_WRAP: cdefgh|abcdefgh|abcdefg
478  * BORDER_CONSTANT: iiiiii|abcdefgh|iiiiiii with some specified 'i'
479  * BORDER_TRANSPARENT: mnopqr|abcdefgh|tuvwxyz where m-r and t-z are original values of cloud_out
480  * \param value
481  * \throw pcl::BadArgumentException if any of top, bottom, left or right is negative.
482  * \ingroup common
483  */
484  template <typename PointT> void
485  copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
486  pcl::PointCloud<PointT> &cloud_out,
487  int top, int bottom, int left, int right,
488  pcl::InterpolationType border_type, const PointT& value);
489 
490  /** \brief Concatenate two datasets representing different fields.
491  *
492  * \note If the input datasets have overlapping fields (i.e., both contain
493  * the same fields), then the data in the second cloud (cloud2_in) will
494  * overwrite the data in the first (cloud1_in).
495  *
496  * \param[in] cloud1_in the first input dataset
497  * \param[in] cloud2_in the second input dataset (overwrites the fields of the first dataset for those that are shared)
498  * \param[out] cloud_out the resultant output dataset created by the concatenation of all the fields in the input datasets
499  * \ingroup common
500  */
501  template <typename PointIn1T, typename PointIn2T, typename PointOutT> void
503  const pcl::PointCloud<PointIn2T> &cloud2_in,
504  pcl::PointCloud<PointOutT> &cloud_out);
505 
506  /** \brief Concatenate two datasets representing different fields.
507  *
508  * \note If the input datasets have overlapping fields (i.e., both contain
509  * the same fields), then the data in the second cloud (cloud2_in) will
510  * overwrite the data in the first (cloud1_in).
511  *
512  * \param[in] cloud1_in the first input dataset
513  * \param[in] cloud2_in the second input dataset (overwrites the fields of the first dataset for those that are shared)
514  * \param[out] cloud_out the output dataset created by concatenating all the fields in the input datasets
515  * \ingroup common
516  */
517  PCL_EXPORTS bool
519  const pcl::PCLPointCloud2 &cloud2_in,
520  pcl::PCLPointCloud2 &cloud_out);
521 
522  /** \brief Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format
523  * \param[in] in the point cloud message
524  * \param[out] out the resultant Eigen MatrixXf format containing XYZ0 / point
525  * \ingroup common
526  */
527  PCL_EXPORTS bool
528  getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out);
529 
530  /** \brief Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message
531  * \param[in] in the Eigen MatrixXf format containing XYZ0 / point
532  * \param[out] out the resultant point cloud message
533  * \note the method assumes that the PCLPointCloud2 message already has the fields set up properly !
534  * \ingroup common
535  */
536  PCL_EXPORTS bool
537  getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out);
538 
539  namespace io
540  {
541  /** \brief swap bytes order of a char array of length N
542  * \param bytes char array to swap
543  * \ingroup common
544  */
545  template <std::size_t N> void
546  swapByte (char* bytes);
547 
548  /** \brief specialization of swapByte for dimension 1
549  * \param bytes char array to swap
550  */
551  template <> inline void
552  swapByte<1> (char* bytes) { bytes[0] = bytes[0]; }
553 
554 
555  /** \brief specialization of swapByte for dimension 2
556  * \param bytes char array to swap
557  */
558  template <> inline void
559  swapByte<2> (char* bytes) { std::swap (bytes[0], bytes[1]); }
560 
561  /** \brief specialization of swapByte for dimension 4
562  * \param bytes char array to swap
563  */
564  template <> inline void
565  swapByte<4> (char* bytes)
566  {
567  std::swap (bytes[0], bytes[3]);
568  std::swap (bytes[1], bytes[2]);
569  }
570 
571  /** \brief specialization of swapByte for dimension 8
572  * \param bytes char array to swap
573  */
574  template <> inline void
575  swapByte<8> (char* bytes)
576  {
577  std::swap (bytes[0], bytes[7]);
578  std::swap (bytes[1], bytes[6]);
579  std::swap (bytes[2], bytes[5]);
580  std::swap (bytes[3], bytes[4]);
581  }
582 
583  /** \brief swaps byte of an arbitrary type T casting it to char*
584  * \param value the data you want its bytes swapped
585  */
586  template <typename T> void
587  swapByte (T& value)
588  {
589  pcl::io::swapByte<sizeof(T)> (reinterpret_cast<char*> (&value));
590  }
591  }
592 }
593 
594 #include <pcl/common/impl/io.hpp>
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:174
static bool concatenate(pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2)
Definition: point_cloud.h:232
bool concatenate(const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< PointT > &cloud_out)
Concatenate two pcl::PointCloud<PointT>
Definition: io.h:304
void swapByte(char *bytes)
swap bytes order of a char array of length N
T point_field_as(const std::uint8_t *data, const std::uint8_t type)
Get the value of a point field from raw data pointer and field type.
Definition: io.hpp:144
PCL_EXPORTS bool getPointCloudAsEigen(const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out)
Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format.
PCL_EXPORTS bool getEigenAsPointCloud(Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out)
Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message.
int getFieldSize(const int datatype)
Obtains the size of a specific field data type in bytes.
Definition: io.h:137
std::string getFieldsList(const pcl::PointCloud< PointT > &)
Get the list of all fields available in a given cloud.
Definition: io.hpp:119
int getFieldType(const int size, char type)
Obtains the type of the PCLPointField from a specific size and type.
Definition: io.h:181
void concatenateFields(const pcl::PointCloud< PointIn1T > &cloud1_in, const pcl::PointCloud< PointIn2T > &cloud2_in, pcl::PointCloud< PointOutT > &cloud_out)
Concatenate two datasets representing different fields.
Definition: io.hpp:369
#define PCL_FALLTHROUGH
Macro to add a no-op or a fallthrough attribute based on compiler feature.
Definition: pcl_macros.h:438
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
Definition: io.hpp:208
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
void swapByte< 1 >(char *bytes)
specialization of swapByte for dimension 1
Definition: io.h:552
void swapByte< 4 >(char *bytes)
specialization of swapByte for dimension 4
Definition: io.h:565
void swapByte< 2 >(char *bytes)
specialization of swapByte for dimension 2
Definition: io.h:559
void swapByte< 8 >(char *bytes)
specialization of swapByte for dimension 8
Definition: io.h:575
int getFieldIndex(const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields)
Definition: io.hpp:52
InterpolationType
Definition: io.h:278
@ BORDER_REFLECT
Definition: io.h:280
@ BORDER_REFLECT_101
Definition: io.h:281
@ BORDER_TRANSPARENT
Definition: io.h:281
@ BORDER_DEFAULT
Definition: io.h:282
@ BORDER_CONSTANT
Definition: io.h:279
@ BORDER_WRAP
Definition: io.h:280
@ BORDER_REPLICATE
Definition: io.h:279
PCL_EXPORTS int interpolatePointIndex(int p, int length, InterpolationType type)
constexpr bool isSamePointType() noexcept
Check if two given point types are the same or not.
Definition: io.h:379
std::vector< index_t, Allocator > IndicesAllocator
Type used for indices in PCL.
Definition: types.h:128
std::remove_cv_t< std::remove_reference_t< T > > remove_cvref_t
Definition: type_traits.h:298
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
PCL_EXPORTS void getFieldsSizes(const std::vector< pcl::PCLPointField > &fields, std::vector< int > &field_sizes)
Obtain a vector with the sizes of all valid fields (e.g., not "_")
void getFields(const pcl::PointCloud< PointT > &, std::vector< pcl::PCLPointField > &fields)
Definition: io.hpp:83
Defines all the PCL and non-PCL macros used.
#define PCL_EXPORTS
Definition: pcl_macros.h:324
std::vector<::pcl::PCLPointField > fields
static bool concatenate(pcl::PCLPointCloud2 &cloud1, const pcl::PCLPointCloud2 &cloud2)
Inplace concatenate two pcl::PCLPointCloud2.
A point structure representing Euclidean xyz coordinates, and the RGB color.
static bool concatenate(pcl::PolygonMesh &mesh1, const pcl::PolygonMesh &mesh2)
Inplace concatenate two pcl::PolygonMesh.
Definition: PolygonMesh.h:30