Point Cloud Library (PCL)  1.11.1-dev
point_cloud.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, 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  */
38 
39 #pragma once
40 
41 #ifdef __GNUC__
42 #pragma GCC system_header
43 #endif
44 
45 #include <Eigen/StdVector>
46 #include <Eigen/Geometry>
47 #include <pcl/PCLHeader.h>
48 #include <pcl/exceptions.h>
49 #include <pcl/memory.h>
50 #include <pcl/pcl_macros.h>
51 #include <pcl/type_traits.h>
52 #include <pcl/types.h>
53 #include <pcl/console/print.h> // for PCL_WARN
54 
55 #include <utility>
56 #include <vector>
57 
58 namespace pcl
59 {
60  namespace detail
61  {
62  struct FieldMapping
63  {
64  std::size_t serialized_offset;
65  std::size_t struct_offset;
66  std::size_t size;
67  };
68  } // namespace detail
69 
70  // Forward declarations
71  template <typename PointT> class PointCloud;
72  using MsgFieldMap = std::vector<detail::FieldMapping>;
73 
74  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
75  template <typename PointOutT>
77  {
78  using Pod = typename traits::POD<PointOutT>::type;
79 
80  /** \brief Constructor
81  * \param[in] p1 the input Eigen type
82  * \param[out] p2 the output Point type
83  */
84  NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointOutT &p2)
85  : p1_ (p1),
86  p2_ (reinterpret_cast<Pod&>(p2)),
87  f_idx_ (0) { }
88 
89  /** \brief Operator. Data copy happens here. */
90  template<typename Key> inline void
92  {
93  //boost::fusion::at_key<Key> (p2_) = p1_[f_idx_++];
94  using T = typename pcl::traits::datatype<PointOutT, Key>::type;
95  std::uint8_t* data_ptr = reinterpret_cast<std::uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value;
96  *reinterpret_cast<T*>(data_ptr) = static_cast<T> (p1_[f_idx_++]);
97  }
98 
99  private:
100  const Eigen::VectorXf &p1_;
101  Pod &p2_;
102  int f_idx_;
103  public:
105  };
106 
107  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
108  template <typename PointInT>
110  {
111  using Pod = typename traits::POD<PointInT>::type;
112 
113  /** \brief Constructor
114  * \param[in] p1 the input Point type
115  * \param[out] p2 the output Eigen type
116  */
117  NdCopyPointEigenFunctor (const PointInT &p1, Eigen::VectorXf &p2)
118  : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
119 
120  /** \brief Operator. Data copy happens here. */
121  template<typename Key> inline void
123  {
124  //p2_[f_idx_++] = boost::fusion::at_key<Key> (p1_);
125  using T = typename pcl::traits::datatype<PointInT, Key>::type;
126  const std::uint8_t* data_ptr = reinterpret_cast<const std::uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value;
127  p2_[f_idx_++] = static_cast<float> (*reinterpret_cast<const T*>(data_ptr));
128  }
129 
130  private:
131  const Pod &p1_;
132  Eigen::VectorXf &p2_;
133  int f_idx_;
134  public:
136  };
137 
138  /** \brief PointCloud represents the base class in PCL for storing collections of 3D points.
139  *
140  * The class is templated, which means you need to specify the type of data
141  * that it should contain. For example, to create a point cloud that holds 4
142  * random XYZ data points, use:
143  *
144  * \code
145  * pcl::PointCloud<pcl::PointXYZ> cloud;
146  * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
147  * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
148  * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
149  * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
150  * \endcode
151  *
152  * The PointCloud class contains the following elements:
153  * - \b width - specifies the width of the point cloud dataset in the number of points. WIDTH has two meanings:
154  * - it can specify the total number of points in the cloud (equal with POINTS see below) for unorganized datasets;
155  * - it can specify the width (total number of points in a row) of an organized point cloud dataset.
156  * \a Mandatory.
157  * - \b height - specifies the height of the point cloud dataset in the number of points. HEIGHT has two meanings:
158  * - it can specify the height (total number of rows) of an organized point cloud dataset;
159  * - it is set to 1 for unorganized datasets (thus used to check whether a dataset is organized or not).
160  * \a Mandatory.
161  * - \b points - the data array where all points of type <b>PointT</b> are stored. \a Mandatory.
162  *
163  * - \b is_dense - specifies if all the data in <b>points</b> is finite (true), or whether it might contain Inf/NaN values
164  * (false). \a Mandatory.
165  *
166  * - \b sensor_origin_ - specifies the sensor acquisition pose (origin/translation). \a Optional.
167  * - \b sensor_orientation_ - specifies the sensor acquisition pose (rotation). \a Optional.
168  *
169  * \author Patrick Mihelich, Radu B. Rusu
170  */
171  template <typename PointT>
172  class PCL_EXPORTS PointCloud
173  {
174  public:
175  /** \brief Default constructor. Sets \ref is_dense to true, \ref width
176  * and \ref height to 0, and the \ref sensor_origin_ and \ref
177  * sensor_orientation_ to identity.
178  */
179  PointCloud () = default;
180 
181  /** \brief Copy constructor from point cloud subset
182  * \param[in] pc the cloud to copy into this
183  * \param[in] indices the subset to copy
184  */
186  const Indices &indices) :
187  header (pc.header), points (indices.size ()), width (indices.size ()), height (1), is_dense (pc.is_dense),
188  sensor_origin_ (pc.sensor_origin_), sensor_orientation_ (pc.sensor_orientation_)
189  {
190  // Copy the obvious
191  assert (indices.size () <= pc.size ());
192  for (std::size_t i = 0; i < indices.size (); i++)
193  points[i] = pc[indices[i]];
194  }
195 
196  /** \brief Allocate constructor from point cloud subset
197  * \param[in] width_ the cloud width
198  * \param[in] height_ the cloud height
199  * \param[in] value_ default value
200  */
201  PointCloud (std::uint32_t width_, std::uint32_t height_, const PointT& value_ = PointT ())
202  : points (width_ * height_, value_)
203  , width (width_)
204  , height (height_)
205  {}
206 
207  //TODO: check if copy/move contructors/assignment operators are needed
208 
209  /** \brief Add a point cloud to the current cloud.
210  * \param[in] rhs the cloud to add to the current cloud
211  * \return the new cloud as a concatenation of the current cloud and the new given cloud
212  */
213  inline PointCloud&
214  operator += (const PointCloud& rhs)
215  {
216  concatenate((*this), rhs);
217  return (*this);
218  }
219 
220  /** \brief Add a point cloud to another cloud.
221  * \param[in] rhs the cloud to add to the current cloud
222  * \return the new cloud as a concatenation of the current cloud and the new given cloud
223  */
224  inline PointCloud
225  operator + (const PointCloud& rhs)
226  {
227  return (PointCloud (*this) += rhs);
228  }
229 
230  inline static bool
232  const pcl::PointCloud<PointT> &cloud2)
233  {
234  // Make the resultant point cloud take the newest stamp
235  cloud1.header.stamp = std::max (cloud1.header.stamp, cloud2.header.stamp);
236 
237  // libstdc++ (GCC) on calling reserve allocates new memory, copies and deallocates old vector
238  // This causes a drastic performance hit. Prefer not to use reserve with libstdc++ (default on clang)
239  cloud1.insert (cloud1.end (), cloud2.begin (), cloud2.end ());
240 
241  cloud1.width = cloud1.size ();
242  cloud1.height = 1;
243  cloud1.is_dense = cloud1.is_dense && cloud2.is_dense;
244  return true;
245  }
246 
247  inline static bool
249  const pcl::PointCloud<PointT> &cloud2,
250  pcl::PointCloud<PointT> &cloud_out)
251  {
252  cloud_out = cloud1;
253  return concatenate(cloud_out, cloud2);
254  }
255 
256  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
257  * datasets (those that have height != 1).
258  * \param[in] column the column coordinate
259  * \param[in] row the row coordinate
260  */
261  inline const PointT&
262  at (int column, int row) const
263  {
264  if (this->height > 1)
265  return (points.at (row * this->width + column));
266  else
267  throw UnorganizedPointCloudException ("Can't use 2D indexing with an unorganized point cloud");
268  }
269 
270  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
271  * datasets (those that have height != 1).
272  * \param[in] column the column coordinate
273  * \param[in] row the row coordinate
274  */
275  inline PointT&
276  at (int column, int row)
277  {
278  if (this->height > 1)
279  return (points.at (row * this->width + column));
280  else
281  throw UnorganizedPointCloudException ("Can't use 2D indexing with an unorganized point cloud");
282  }
283 
284  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
285  * datasets (those that have height != 1).
286  * \param[in] column the column coordinate
287  * \param[in] row the row coordinate
288  */
289  inline const PointT&
290  operator () (std::size_t column, std::size_t row) const
291  {
292  return (points[row * this->width + column]);
293  }
294 
295  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
296  * datasets (those that have height != 1).
297  * \param[in] column the column coordinate
298  * \param[in] row the row coordinate
299  */
300  inline PointT&
301  operator () (std::size_t column, std::size_t row)
302  {
303  return (points[row * this->width + column]);
304  }
305 
306  /** \brief Return whether a dataset is organized (e.g., arranged in a structured grid).
307  * \note The height value must be different than 1 for a dataset to be organized.
308  */
309  inline bool
310  isOrganized () const
311  {
312  return (height > 1);
313  }
314 
315  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
316  * \note This method is for advanced users only! Use with care!
317  *
318  * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL
319  * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure,
320  * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
321  *
322  * \param[in] dim the number of dimensions to consider for each point
323  * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns)
324  * \param[in] offset the number of dimensions to skip from the beginning of each point
325  * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point)
326  * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
327  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
328  */
329  inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
330  getMatrixXfMap (int dim, int stride, int offset)
331  {
332  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
333  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, size (), dim, Eigen::OuterStride<> (stride)));
334  else
335  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, dim, size (), Eigen::OuterStride<> (stride)));
336  }
337 
338  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
339  * \note This method is for advanced users only! Use with care!
340  *
341  * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL
342  * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure,
343  * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
344  *
345  * \param[in] dim the number of dimensions to consider for each point
346  * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns)
347  * \param[in] offset the number of dimensions to skip from the beginning of each point
348  * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point)
349  * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
350  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
351  */
352  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
353  getMatrixXfMap (int dim, int stride, int offset) const
354  {
355  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
356  return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(const_cast<PointT*>(&points[0]))+offset, size (), dim, Eigen::OuterStride<> (stride)));
357  else
358  return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(const_cast<PointT*>(&points[0]))+offset, dim, size (), Eigen::OuterStride<> (stride)));
359  }
360 
361  /**
362  * \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
363  * \note This method is for advanced users only! Use with care!
364  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
365  * \overload Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud::getMatrixXfMap ()
366  */
367  inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
369  {
370  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
371  }
372 
373  /**
374  * \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
375  * \note This method is for advanced users only! Use with care!
376  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
377  * \overload const Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud::getMatrixXfMap () const
378  */
379  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
380  getMatrixXfMap () const
381  {
382  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
383  }
384 
385  /** \brief The point cloud header. It contains information about the acquisition time. */
387 
388  /** \brief The point data. */
389  std::vector<PointT, Eigen::aligned_allocator<PointT> > points;
390 
391  /** \brief The point cloud width (if organized as an image-structure). */
392  std::uint32_t width = 0;
393  /** \brief The point cloud height (if organized as an image-structure). */
394  std::uint32_t height = 0;
395 
396  /** \brief True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields). */
397  bool is_dense = true;
398 
399  /** \brief Sensor acquisition pose (origin/translation). */
400  Eigen::Vector4f sensor_origin_ = Eigen::Vector4f::Zero ();
401  /** \brief Sensor acquisition pose (rotation). */
402  Eigen::Quaternionf sensor_orientation_ = Eigen::Quaternionf::Identity ();
403 
404  using PointType = PointT; // Make the template class available from the outside
405  using VectorType = std::vector<PointT, Eigen::aligned_allocator<PointT> >;
406  using CloudVectorType = std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > >;
407  using Ptr = shared_ptr<PointCloud<PointT> >;
408  using ConstPtr = shared_ptr<const PointCloud<PointT> >;
409 
410  // std container compatibility typedefs according to
411  // http://en.cppreference.com/w/cpp/concept/Container
413  using reference = PointT&;
414  using const_reference = const PointT&;
415  using difference_type = typename VectorType::difference_type;
416  using size_type = typename VectorType::size_type;
417 
418  // iterators
419  using iterator = typename VectorType::iterator;
420  using const_iterator = typename VectorType::const_iterator;
421  using reverse_iterator = typename VectorType::reverse_iterator;
422  using const_reverse_iterator = typename VectorType::const_reverse_iterator;
423  inline iterator begin () noexcept { return (points.begin ()); }
424  inline iterator end () noexcept { return (points.end ()); }
425  inline const_iterator begin () const noexcept { return (points.begin ()); }
426  inline const_iterator end () const noexcept { return (points.end ()); }
427  inline const_iterator cbegin () const noexcept { return (points.cbegin ()); }
428  inline const_iterator cend () const noexcept { return (points.cend ()); }
429  inline reverse_iterator rbegin () noexcept { return (points.rbegin ()); }
430  inline reverse_iterator rend () noexcept { return (points.rend ()); }
431  inline const_reverse_iterator rbegin () const noexcept { return (points.rbegin ()); }
432  inline const_reverse_iterator rend () const noexcept { return (points.rend ()); }
433  inline const_reverse_iterator crbegin () const noexcept { return (points.crbegin ()); }
434  inline const_reverse_iterator crend () const noexcept { return (points.crend ()); }
435 
436  //capacity
437  inline std::size_t size () const { return points.size (); }
438  inline index_t max_size() const noexcept { return static_cast<index_t>(points.max_size()); }
439  inline void reserve (std::size_t n) { points.reserve (n); }
440  inline bool empty () const { return points.empty (); }
441  inline PointT* data() noexcept { return points.data(); }
442  inline const PointT* data() const noexcept { return points.data(); }
443 
444  /**
445  * \brief Resizes the container to contain `count` elements
446  * \details
447  * * If the current size is greater than `count`, the pointcloud is reduced to its
448  * first `count` elements
449  * * If the current size is less than `count`, additional default-inserted points
450  * are appended
451  * \note This potentially breaks the organized structure of the cloud by setting
452  * the height to 1 IFF `width * height != count`!
453  * \param[in] count new size of the point cloud
454  */
455  inline void
456  resize(std::size_t count)
457  {
458  points.resize(count);
459  if (width * height != count) {
460  width = static_cast<std::uint32_t>(count);
461  height = 1;
462  }
463  }
464 
465  /**
466  * \brief Resizes the container to contain `new_width * new_height` elements
467  * \details
468  * * If the current size is greater than the requested size, the pointcloud
469  * is reduced to its first requested elements
470  * * If the current size is less then the requested size, additional
471  * default-inserted points are appended
472  * \param[in] new_width new width of the point cloud
473  * \param[in] new_height new height of the point cloud
474  */
475  inline void
476  resize(uindex_t new_width, uindex_t new_height)
477  {
478  points.resize(new_width * new_height);
479  width = new_width;
480  height = new_height;
481  }
482 
483  /**
484  * \brief Resizes the container to contain count elements
485  * \details
486  * * If the current size is greater than `count`, the pointcloud is reduced to its
487  * first `count` elements
488  * * If the current size is less than `count`, additional copies of `value` are
489  * appended
490  * \note This potentially breaks the organized structure of the cloud by setting
491  * the height to 1 IFF `width * height != count`!
492  * \param[in] count new size of the point cloud
493  * \param[in] value the value to initialize the new points with
494  */
495  inline void
496  resize(index_t count, const PointT& value)
497  {
498  points.resize(count, value);
499  if (width * height != count) {
500  width = count;
501  height = 1;
502  }
503  }
504 
505  /**
506  * \brief Resizes the container to contain count elements
507  * \details
508  * * If the current size is greater then the requested size, the pointcloud
509  * is reduced to its first requested elements
510  * * If the current size is less then the requested size, additional
511  * default-inserted points are appended
512  * \param[in] new_width new width of the point cloud
513  * \param[in] new_height new height of the point cloud
514  * \param[in] value the value to initialize the new points with
515  */
516  inline void
517  resize(index_t new_width, index_t new_height, const PointT& value)
518  {
519  points.resize(new_width * new_height, value);
520  width = new_width;
521  height = new_height;
522  }
523 
524  //element access
525  inline const PointT& operator[] (std::size_t n) const { return (points[n]); }
526  inline PointT& operator[] (std::size_t n) { return (points[n]); }
527  inline const PointT& at (std::size_t n) const { return (points.at (n)); }
528  inline PointT& at (std::size_t n) { return (points.at (n)); }
529  inline const PointT& front () const { return (points.front ()); }
530  inline PointT& front () { return (points.front ()); }
531  inline const PointT& back () const { return (points.back ()); }
532  inline PointT& back () { return (points.back ()); }
533 
534  /**
535  * \brief Replaces the points with `count` copies of `value`
536  * \note This breaks the organized structure of the cloud by setting the height to
537  * 1!
538  * \param[in] count new size of the point cloud
539  * \param[in] value value each point of the cloud should have
540  */
541  inline void
542  assign(index_t count, const PointT& value)
543  {
544  points.assign(count, value);
545  width = static_cast<std::uint32_t>(size());
546  height = 1;
547  }
548 
549  /**
550  * \brief Replaces the points with `new_width * new_height` copies of `value`
551  * \param[in] new_width new width of the point cloud
552  * \param[in] new_height new height of the point cloud
553  * \param[in] value value each point of the cloud should have
554  */
555  inline void
556  assign(index_t new_width, index_t new_height, const PointT& value)
557  {
558  points.assign(new_width * new_height, value);
559  width = new_width;
560  height = new_height;
561  }
562 
563  /**
564  * \brief Replaces the points with copies of those in the range `[first, last)`
565  * \details The behavior is undefined if either argument is an iterator into
566  * `*this`
567  * \note This breaks the organized structure of the cloud by setting the height to
568  * 1!
569  */
570  template <class InputIterator>
571  inline void
572  assign(InputIterator first, InputIterator last)
573  {
574  points.assign(std::move(first), std::move(last));
575  width = static_cast<std::uint32_t>(size());
576  height = 1;
577  }
578 
579  /**
580  * \brief Replaces the points with copies of those in the range `[first, last)`
581  * \details The behavior is undefined if either argument is an iterator into
582  * `*this`
583  * \note This calculates the height based on size and width provided. This means
584  * the assignment happens even if the size is not perfectly divisible by width
585  * \param[in] first, last the range from which the points are copied
586  * \param[in] new_width new width of the point cloud
587  */
588  template <class InputIterator>
589  inline void
590  assign(InputIterator first, InputIterator last, index_t new_width)
591  {
592  points.assign(std::move(first), std::move(last));
593  width = new_width;
594  height = size() / width;
595  if (width * height != size()) {
596  PCL_WARN("Mismatch in assignment. Requested width (%zu) doesn't divide "
597  "provided size (%zu) cleanly. Setting height to 1\n",
598  static_cast<std::size_t>(width),
599  static_cast<std::size_t>(size()));
600  width = size();
601  height = 1;
602  }
603  }
604 
605  /**
606  * \brief Replaces the points with the elements from the initializer list `ilist`
607  * \note This breaks the organized structure of the cloud by setting the height to
608  * 1!
609  */
610  void
611  inline assign(std::initializer_list<PointT> ilist)
612  {
613  points.assign(std::move(ilist));
614  width = static_cast<std::uint32_t>(size());
615  height = 1;
616  }
617 
618  /**
619  * \brief Replaces the points with the elements from the initializer list `ilist`
620  * \note This calculates the height based on size and width provided. This means
621  * the assignment happens even if the size is not perfectly divisible by width
622  * \param[in] ilist initializer list from which the points are copied
623  * \param[in] new_width new width of the point cloud
624  */
625  void
626  inline assign(std::initializer_list<PointT> ilist, index_t new_width)
627  {
628  points.assign(std::move(ilist));
629  width = new_width;
630  height = size() / width;
631  if (width * height != size()) {
632  PCL_WARN("Mismatch in assignment. Requested width (%zu) doesn't divide "
633  "provided size (%zu) cleanly. Setting height to 1\n",
634  static_cast<std::size_t>(width),
635  static_cast<std::size_t>(size()));
636  width = size();
637  height = 1;
638  }
639  }
640 
641  /** \brief Insert a new point in the cloud, at the end of the container.
642  * \note This breaks the organized structure of the cloud by setting the height to 1!
643  * \param[in] pt the point to insert
644  */
645  inline void
646  push_back (const PointT& pt)
647  {
648  points.push_back (pt);
649  width = size ();
650  height = 1;
651  }
652 
653  /** \brief Insert a new point in the cloud, at the end of the container.
654  * \note This assumes the user would correct the width and height later on!
655  * \param[in] pt the point to insert
656  */
657  inline void
659  {
660  points.push_back (pt);
661  }
662 
663  /** \brief Emplace a new point in the cloud, at the end of the container.
664  * \note This breaks the organized structure of the cloud by setting the height to 1!
665  * \param[in] args the parameters to forward to the point to construct
666  * \return reference to the emplaced point
667  */
668  template <class... Args> inline reference
669  emplace_back (Args&& ...args)
670  {
671  points.emplace_back (std::forward<Args> (args)...);
672  width = size ();
673  height = 1;
674  return points.back();
675  }
676 
677  /** \brief Emplace a new point in the cloud, at the end of the container.
678  * \note This assumes the user would correct the width and height later on!
679  * \param[in] args the parameters to forward to the point to construct
680  * \return reference to the emplaced point
681  */
682  template <class... Args> inline reference
683  transient_emplace_back (Args&& ...args)
684  {
685  points.emplace_back (std::forward<Args> (args)...);
686  return points.back();
687  }
688 
689  /** \brief Insert a new point in the cloud, given an iterator.
690  * \note This breaks the organized structure of the cloud by setting the height to 1!
691  * \param[in] position where to insert the point
692  * \param[in] pt the point to insert
693  * \return returns the new position iterator
694  */
695  inline iterator
696  insert (iterator position, const PointT& pt)
697  {
698  iterator it = points.insert (std::move(position), pt);
699  width = size ();
700  height = 1;
701  return (it);
702  }
703 
704  /** \brief Insert a new point in the cloud, given an iterator.
705  * \note This assumes the user would correct the width and height later on!
706  * \param[in] position where to insert the point
707  * \param[in] pt the point to insert
708  * \return returns the new position iterator
709  */
710  inline iterator
711  transient_insert (iterator position, const PointT& pt)
712  {
713  iterator it = points.insert (std::move(position), pt);
714  return (it);
715  }
716 
717  /** \brief Insert a new point in the cloud N times, given an iterator.
718  * \note This breaks the organized structure of the cloud by setting the height to 1!
719  * \param[in] position where to insert the point
720  * \param[in] n the number of times to insert the point
721  * \param[in] pt the point to insert
722  */
723  inline void
724  insert (iterator position, std::size_t n, const PointT& pt)
725  {
726  points.insert (std::move(position), n, pt);
727  width = size ();
728  height = 1;
729  }
730 
731  /** \brief Insert a new point in the cloud N times, given an iterator.
732  * \note This assumes the user would correct the width and height later on!
733  * \param[in] position where to insert the point
734  * \param[in] n the number of times to insert the point
735  * \param[in] pt the point to insert
736  */
737  inline void
738  transient_insert (iterator position, std::size_t n, const PointT& pt)
739  {
740  points.insert (std::move(position), n, pt);
741  }
742 
743  /** \brief Insert a new range of points in the cloud, at a certain position.
744  * \note This breaks the organized structure of the cloud by setting the height to 1!
745  * \param[in] position where to insert the data
746  * \param[in] first where to start inserting the points from
747  * \param[in] last where to stop inserting the points from
748  */
749  template <class InputIterator> inline void
750  insert (iterator position, InputIterator first, InputIterator last)
751  {
752  points.insert (std::move(position), std::move(first), std::move(last));
753  width = size ();
754  height = 1;
755  }
756 
757  /** \brief Insert a new range of points in the cloud, at a certain position.
758  * \note This assumes the user would correct the width and height later on!
759  * \param[in] position where to insert the data
760  * \param[in] first where to start inserting the points from
761  * \param[in] last where to stop inserting the points from
762  */
763  template <class InputIterator> inline void
764  transient_insert (iterator position, InputIterator first, InputIterator last)
765  {
766  points.insert (std::move(position), std::move(first), std::move(last));
767  }
768 
769  /** \brief Emplace a new point in the cloud, given an iterator.
770  * \note This breaks the organized structure of the cloud by setting the height to 1!
771  * \param[in] position iterator before which the point will be emplaced
772  * \param[in] args the parameters to forward to the point to construct
773  * \return returns the new position iterator
774  */
775  template <class... Args> inline iterator
776  emplace (iterator position, Args&& ...args)
777  {
778  iterator it = points.emplace (std::move(position), std::forward<Args> (args)...);
779  width = size ();
780  height = 1;
781  return (it);
782  }
783 
784  /** \brief Emplace a new point in the cloud, given an iterator.
785  * \note This assumes the user would correct the width and height later on!
786  * \param[in] position iterator before which the point will be emplaced
787  * \param[in] args the parameters to forward to the point to construct
788  * \return returns the new position iterator
789  */
790  template <class... Args> inline iterator
791  transient_emplace (iterator position, Args&& ...args)
792  {
793  iterator it = points.emplace (std::move(position), std::forward<Args> (args)...);
794  return (it);
795  }
796 
797  /** \brief Erase a point in the cloud.
798  * \note This breaks the organized structure of the cloud by setting the height to 1!
799  * \param[in] position what data point to erase
800  * \return returns the new position iterator
801  */
802  inline iterator
803  erase (iterator position)
804  {
805  iterator it = points.erase (std::move(position));
806  width = size ();
807  height = 1;
808  return (it);
809  }
810 
811  /** \brief Erase a point in the cloud.
812  * \note This assumes the user would correct the width and height later on!
813  * \param[in] position what data point to erase
814  * \return returns the new position iterator
815  */
816  inline iterator
818  {
819  iterator it = points.erase (std::move(position));
820  return (it);
821  }
822 
823  /** \brief Erase a set of points given by a (first, last) iterator pair
824  * \note This breaks the organized structure of the cloud by setting the height to 1!
825  * \param[in] first where to start erasing points from
826  * \param[in] last where to stop erasing points from
827  * \return returns the new position iterator
828  */
829  inline iterator
830  erase (iterator first, iterator last)
831  {
832  iterator it = points.erase (std::move(first), std::move(last));
833  width = size ();
834  height = 1;
835  return (it);
836  }
837 
838  /** \brief Erase a set of points given by a (first, last) iterator pair
839  * \note This assumes the user would correct the width and height later on!
840  * \param[in] first where to start erasing points from
841  * \param[in] last where to stop erasing points from
842  * \return returns the new position iterator
843  */
844  inline iterator
846  {
847  iterator it = points.erase (std::move(first), std::move(last));
848  return (it);
849  }
850 
851  /** \brief Swap a point cloud with another cloud.
852  * \param[in,out] rhs point cloud to swap this with
853  */
854  inline void
856  {
857  std::swap (header, rhs.header);
858  this->points.swap (rhs.points);
859  std::swap (width, rhs.width);
860  std::swap (height, rhs.height);
861  std::swap (is_dense, rhs.is_dense);
862  std::swap (sensor_origin_, rhs.sensor_origin_);
863  std::swap (sensor_orientation_, rhs.sensor_orientation_);
864  }
865 
866  /** \brief Removes all points in a cloud and sets the width and height to 0. */
867  inline void
868  clear ()
869  {
870  points.clear ();
871  width = 0;
872  height = 0;
873  }
874 
875  /** \brief Copy the cloud to the heap and return a smart pointer
876  * Note that deep copy is performed, so avoid using this function on non-empty clouds.
877  * The changes of the returned cloud are not mirrored back to this one.
878  * \return shared pointer to the copy of the cloud
879  */
880  inline Ptr
881  makeShared () const { return Ptr (new PointCloud<PointT> (*this)); }
882 
884  };
885 
886 
887  template <typename PointT> std::ostream&
888  operator << (std::ostream& s, const pcl::PointCloud<PointT> &p)
889  {
890  s << "header: " << p.header << std::endl;
891  s << "points[]: " << p.size () << std::endl;
892  s << "width: " << p.width << std::endl;
893  s << "height: " << p.height << std::endl;
894  s << "is_dense: " << p.is_dense << std::endl;
895  s << "sensor origin (xyz): [" <<
896  p.sensor_origin_.x () << ", " <<
897  p.sensor_origin_.y () << ", " <<
898  p.sensor_origin_.z () << "] / orientation (xyzw): [" <<
899  p.sensor_orientation_.x () << ", " <<
900  p.sensor_orientation_.y () << ", " <<
901  p.sensor_orientation_.z () << ", " <<
902  p.sensor_orientation_.w () << "]" <<
903  std::endl;
904  return (s);
905  }
906 }
907 
908 #define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud<T>;
pcl::PCLHeader::stamp
std::uint64_t stamp
A timestamp associated with the time when the data was acquired.
Definition: PCLHeader.h:18
pcl::PointCloud::swap
void swap(PointCloud< PointT > &rhs)
Swap a point cloud with another cloud.
Definition: point_cloud.h:855
pcl::PointCloud< pcl::RGB >::const_reverse_iterator
typename VectorType::const_reverse_iterator const_reverse_iterator
Definition: point_cloud.h:422
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl
Definition: convolution.h:46
pcl::PointCloud::makeShared
Ptr makeShared() const
Copy the cloud to the heap and return a smart pointer Note that deep copy is performed,...
Definition: point_cloud.h:881
pcl::NdCopyEigenPointFunctor
Helper functor structure for copying data between an Eigen type and a PointT.
Definition: point_cloud.h:76
pcl::PointCloud::assign
void assign(std::initializer_list< PointT > ilist)
Replaces the points with the elements from the initializer list ilist
Definition: point_cloud.h:611
pcl::PointCloud::height
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:394
pcl::PointCloud::resize
void resize(index_t count, const PointT &value)
Resizes the container to contain count elements.
Definition: point_cloud.h:496
pcl::PointCloud::erase
iterator erase(iterator first, iterator last)
Erase a set of points given by a (first, last) iterator pair.
Definition: point_cloud.h:830
pcl::PointCloud::cbegin
const_iterator cbegin() const noexcept
Definition: point_cloud.h:427
pcl::PointCloud::points
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:389
pcl::PointCloud::rbegin
reverse_iterator rbegin() noexcept
Definition: point_cloud.h:429
types.h
Defines basic non-point types used by PCL.
pcl::PointCloud::resize
void resize(index_t new_width, index_t new_height, const PointT &value)
Resizes the container to contain count elements.
Definition: point_cloud.h:517
pcl::NdCopyEigenPointFunctor::Pod
typename traits::POD< PointOutT >::type Pod
Definition: point_cloud.h:78
pcl::NdCopyEigenPointFunctor::operator()
void operator()()
Operator.
Definition: point_cloud.h:91
pcl::PointCloud::begin
iterator begin() noexcept
Definition: point_cloud.h:423
pcl::PointCloud::at
const PointT & at(std::size_t n) const
Definition: point_cloud.h:527
pcl::PointCloud::empty
bool empty() const
Definition: point_cloud.h:440
pcl::PointCloud::cend
const_iterator cend() const noexcept
Definition: point_cloud.h:428
pcl::NdCopyPointEigenFunctor::Pod
typename traits::POD< PointInT >::type Pod
Definition: point_cloud.h:111
pcl::PointCloud::transient_insert
void transient_insert(iterator position, std::size_t n, const PointT &pt)
Insert a new point in the cloud N times, given an iterator.
Definition: point_cloud.h:738
pcl::PointCloud::erase
iterator erase(iterator position)
Erase a point in the cloud.
Definition: point_cloud.h:803
pcl::PointCloud::transient_emplace
iterator transient_emplace(iterator position, Args &&...args)
Emplace a new point in the cloud, given an iterator.
Definition: point_cloud.h:791
pcl::PointCloud::transient_push_back
void transient_push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:658
pcl::PointCloud::emplace
iterator emplace(iterator position, Args &&...args)
Emplace a new point in the cloud, given an iterator.
Definition: point_cloud.h:776
pcl::PointCloud::resize
void resize(uindex_t new_width, uindex_t new_height)
Resizes the container to contain new_width * new_height elements.
Definition: point_cloud.h:476
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::PointCloud::at
PointT & at(int column, int row)
Obtain the point given by the (column, row) coordinates.
Definition: point_cloud.h:276
pcl::index_t
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
Definition: types.h:110
pcl::PointCloud::transient_emplace_back
reference transient_emplace_back(Args &&...args)
Emplace a new point in the cloud, at the end of the container.
Definition: point_cloud.h:683
pcl::PointCloud< pcl::RGB >::VectorType
std::vector< pcl::RGB, Eigen::aligned_allocator< pcl::RGB > > VectorType
Definition: point_cloud.h:405
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:628
pcl::NdCopyPointEigenFunctor::operator()
void operator()()
Operator.
Definition: point_cloud.h:122
pcl::PointCloud::at
const PointT & at(int column, int row) const
Obtain the point given by the (column, row) coordinates.
Definition: point_cloud.h:262
pcl::PointCloud::front
PointT & front()
Definition: point_cloud.h:530
pcl::detail::FieldMapping
Definition: point_cloud.h:62
pcl::PointCloud::isOrganized
bool isOrganized() const
Return whether a dataset is organized (e.g., arranged in a structured grid).
Definition: point_cloud.h:310
pcl::PointCloud< pcl::RGB >::CloudVectorType
std::vector< PointCloud< pcl::RGB >, Eigen::aligned_allocator< PointCloud< pcl::RGB > > > CloudVectorType
Definition: point_cloud.h:406
pcl::PointCloud::data
const PointT * data() const noexcept
Definition: point_cloud.h:442
pcl::operator<<
std::ostream & operator<<(std::ostream &os, const BivariatePolynomialT< real > &p)
Definition: bivariate_polynomial.hpp:240
pcl::detail::FieldMapping::size
std::size_t size
Definition: point_cloud.h:66
pcl::PointCloud::transient_erase
iterator transient_erase(iterator first, iterator last)
Erase a set of points given by a (first, last) iterator pair.
Definition: point_cloud.h:845
pcl::PointCloud::width
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:392
pcl::PointCloud< pcl::RGB >::difference_type
typename VectorType::difference_type difference_type
Definition: point_cloud.h:415
pcl::PointCloud::getMatrixXfMap
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap(int dim, int stride, int offset)
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
Definition: point_cloud.h:330
pcl::PointCloud::transient_insert
iterator transient_insert(iterator position, const PointT &pt)
Insert a new point in the cloud, given an iterator.
Definition: point_cloud.h:711
pcl::PointCloud::assign
void assign(InputIterator first, InputIterator last, index_t new_width)
Replaces the points with copies of those in the range [first, last)
Definition: point_cloud.h:590
pcl::PointCloud::rend
const_reverse_iterator rend() const noexcept
Definition: point_cloud.h:432
pcl::PointCloud::getMatrixXfMap
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap() const
Definition: point_cloud.h:380
pcl::PointCloud< pcl::RGB >::size_type
typename VectorType::size_type size_type
Definition: point_cloud.h:416
pcl::PointCloud::end
const_iterator end() const noexcept
Definition: point_cloud.h:426
pcl::PointCloud::back
const PointT & back() const
Definition: point_cloud.h:531
pcl::PointCloud::getMatrixXfMap
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap()
Definition: point_cloud.h:368
pcl::PointCloud::rend
reverse_iterator rend() noexcept
Definition: point_cloud.h:430
pcl::PointCloud::end
iterator end() noexcept
Definition: point_cloud.h:424
pcl::PointCloud::getMatrixXfMap
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap(int dim, int stride, int offset) const
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
Definition: point_cloud.h:353
pcl::PointCloud::crend
const_reverse_iterator crend() const noexcept
Definition: point_cloud.h:434
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::RGB
A structure representing RGB color information.
Definition: point_types.hpp:345
pcl::PointCloud::reserve
void reserve(std::size_t n)
Definition: point_cloud.h:439
pcl::PointCloud::sensor_origin_
Eigen::Vector4f sensor_origin_
Sensor acquisition pose (origin/translation).
Definition: point_cloud.h:400
pcl::PointCloud::sensor_orientation_
Eigen::Quaternionf sensor_orientation_
Sensor acquisition pose (rotation).
Definition: point_cloud.h:402
pcl::NdCopyEigenPointFunctor::NdCopyEigenPointFunctor
NdCopyEigenPointFunctor(const Eigen::VectorXf &p1, PointOutT &p2)
Constructor.
Definition: point_cloud.h:84
pcl::PointCloud::assign
void assign(std::initializer_list< PointT > ilist, index_t new_width)
Replaces the points with the elements from the initializer list ilist
Definition: point_cloud.h:626
pcl::PointCloud::is_dense
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:397
pcl::PointCloud::resize
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:456
pcl::PointCloud< pcl::RGB >::reverse_iterator
typename VectorType::reverse_iterator reverse_iterator
Definition: point_cloud.h:421
pcl::PointCloud::header
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:386
pcl::NdCopyPointEigenFunctor
Helper functor structure for copying data between an Eigen type and a PointT.
Definition: point_cloud.h:109
pcl::Indices
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:131
pcl::UnorganizedPointCloudException
An exception that is thrown when an organized point cloud is needed but not provided.
Definition: exceptions.h:207
pcl::PointCloud::concatenate
static bool concatenate(pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2)
Definition: point_cloud.h:231
pcl::PointCloud::size
std::size_t size() const
Definition: point_cloud.h:437
pcl::PointCloud::begin
const_iterator begin() const noexcept
Definition: point_cloud.h:425
pcl::PointCloud::insert
iterator insert(iterator position, const PointT &pt)
Insert a new point in the cloud, given an iterator.
Definition: point_cloud.h:696
pcl::PointCloud< pcl::RGB >::Ptr
shared_ptr< PointCloud< pcl::RGB > > Ptr
Definition: point_cloud.h:407
pcl::concatenate
PCL_EXPORTS 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:248
pcl::PointCloud::emplace_back
reference emplace_back(Args &&...args)
Emplace a new point in the cloud, at the end of the container.
Definition: point_cloud.h:669
pcl::PointCloud::insert
void insert(iterator position, std::size_t n, const PointT &pt)
Insert a new point in the cloud N times, given an iterator.
Definition: point_cloud.h:724
pcl::PointCloud::assign
void assign(index_t count, const PointT &value)
Replaces the points with count copies of value
Definition: point_cloud.h:542
pcl::PointCloud::rbegin
const_reverse_iterator rbegin() const noexcept
Definition: point_cloud.h:431
pcl::PointCloud::front
const PointT & front() const
Definition: point_cloud.h:529
pcl::PointCloud::insert
void insert(iterator position, InputIterator first, InputIterator last)
Insert a new range of points in the cloud, at a certain position.
Definition: point_cloud.h:750
pcl::PointCloud< pcl::RGB >::const_iterator
typename VectorType::const_iterator const_iterator
Definition: point_cloud.h:420
pcl::PointCloud::clear
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:868
pcl::PointCloud::back
PointT & back()
Definition: point_cloud.h:532
pcl::PointCloud::PointCloud
PointCloud(const PointCloud< PointT > &pc, const Indices &indices)
Copy constructor from point cloud subset.
Definition: point_cloud.h:185
pcl::PointCloud::data
PointT * data() noexcept
Definition: point_cloud.h:441
pcl::PointCloud< pcl::RGB >::ConstPtr
shared_ptr< const PointCloud< pcl::RGB > > ConstPtr
Definition: point_cloud.h:408
pcl::PointCloud::assign
void assign(index_t new_width, index_t new_height, const PointT &value)
Replaces the points with new_width * new_height copies of value
Definition: point_cloud.h:556
pcl::PointCloud::PointCloud
PointCloud(std::uint32_t width_, std::uint32_t height_, const PointT &value_=PointT())
Allocate constructor from point cloud subset.
Definition: point_cloud.h:201
pcl::PointCloud::concatenate
static bool concatenate(const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< PointT > &cloud_out)
Definition: point_cloud.h:248
pcl::PointCloud::max_size
index_t max_size() const noexcept
Definition: point_cloud.h:438
pcl::detail::FieldMapping::serialized_offset
std::size_t serialized_offset
Definition: point_cloud.h:64
pcl::MsgFieldMap
std::vector< detail::FieldMapping > MsgFieldMap
Definition: point_cloud.h:72
pcl::PointCloud< pcl::RGB >::iterator
typename VectorType::iterator iterator
Definition: point_cloud.h:419
pcl::PointCloud::push_back
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:646
pcl::NdCopyPointEigenFunctor::NdCopyPointEigenFunctor
NdCopyPointEigenFunctor(const PointInT &p1, Eigen::VectorXf &p2)
Constructor.
Definition: point_cloud.h:117
pcl::uindex_t
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
Definition: types.h:118
pcl::PointCloud::assign
void assign(InputIterator first, InputIterator last)
Replaces the points with copies of those in the range [first, last)
Definition: point_cloud.h:572
pcl::PointCloud::crbegin
const_reverse_iterator crbegin() const noexcept
Definition: point_cloud.h:433
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::PCLHeader
Definition: PCLHeader.h:10
PCL_EXPORTS
#define PCL_EXPORTS
Definition: pcl_macros.h:323
pcl::detail::FieldMapping::struct_offset
std::size_t struct_offset
Definition: point_cloud.h:65
pcl::PointCloud::transient_insert
void transient_insert(iterator position, InputIterator first, InputIterator last)
Insert a new range of points in the cloud, at a certain position.
Definition: point_cloud.h:764
pcl::PointCloud::at
PointT & at(std::size_t n)
Definition: point_cloud.h:528
pcl::PointCloud::transient_erase
iterator transient_erase(iterator position)
Erase a point in the cloud.
Definition: point_cloud.h:817