Point Cloud Library (PCL)  1.9.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/pcl_macros.h>
50 #include <pcl/point_traits.h>
51 #include <utility>
52 
53 namespace pcl
54 {
55  namespace detail
56  {
57  struct FieldMapping
58  {
60  size_t struct_offset;
61  size_t size;
62  };
63  } // namespace detail
64 
65  // Forward declarations
66  template <typename PointT> class PointCloud;
67  using MsgFieldMap = std::vector<detail::FieldMapping>;
68 
69  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
70  template <typename PointOutT>
72  {
74 
75  /** \brief Constructor
76  * \param[in] p1 the input Eigen type
77  * \param[out] p2 the output Point type
78  */
79  NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointOutT &p2)
80  : p1_ (p1),
81  p2_ (reinterpret_cast<Pod&>(p2)),
82  f_idx_ (0) { }
83 
84  /** \brief Operator. Data copy happens here. */
85  template<typename Key> inline void
86  operator() ()
87  {
88  //boost::fusion::at_key<Key> (p2_) = p1_[f_idx_++];
90  uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value;
91  *reinterpret_cast<T*>(data_ptr) = static_cast<T> (p1_[f_idx_++]);
92  }
93 
94  private:
95  const Eigen::VectorXf &p1_;
96  Pod &p2_;
97  int f_idx_;
98  public:
100  };
101 
102  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
103  template <typename PointInT>
105  {
107 
108  /** \brief Constructor
109  * \param[in] p1 the input Point type
110  * \param[out] p2 the output Eigen type
111  */
112  NdCopyPointEigenFunctor (const PointInT &p1, Eigen::VectorXf &p2)
113  : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
114 
115  /** \brief Operator. Data copy happens here. */
116  template<typename Key> inline void
117  operator() ()
118  {
119  //p2_[f_idx_++] = boost::fusion::at_key<Key> (p1_);
121  const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value;
122  p2_[f_idx_++] = static_cast<float> (*reinterpret_cast<const T*>(data_ptr));
123  }
124 
125  private:
126  const Pod &p1_;
127  Eigen::VectorXf &p2_;
128  int f_idx_;
129  public:
131  };
132 
133  namespace detail
134  {
135  template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
137  } // namespace detail
138 
139  /** \brief PointCloud represents the base class in PCL for storing collections of 3D points.
140  *
141  * The class is templated, which means you need to specify the type of data
142  * that it should contain. For example, to create a point cloud that holds 4
143  * random XYZ data points, use:
144  *
145  * \code
146  * pcl::PointCloud<pcl::PointXYZ> cloud;
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  * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
151  * \endcode
152  *
153  * The PointCloud class contains the following elements:
154  * - \b width - specifies the width of the point cloud dataset in the number of points. WIDTH has two meanings:
155  * - it can specify the total number of points in the cloud (equal with POINTS see below) for unorganized datasets;
156  * - it can specify the width (total number of points in a row) of an organized point cloud dataset.
157  * \a Mandatory.
158  * - \b height - specifies the height of the point cloud dataset in the number of points. HEIGHT has two meanings:
159  * - it can specify the height (total number of rows) of an organized point cloud dataset;
160  * - it is set to 1 for unorganized datasets (thus used to check whether a dataset is organized or not).
161  * \a Mandatory.
162  * - \b points - the data array where all points of type <b>PointT</b> are stored. \a Mandatory.
163  *
164  * - \b is_dense - specifies if all the data in <b>points</b> is finite (true), or whether it might contain Inf/NaN values
165  * (false). \a Mandatory.
166  *
167  * - \b sensor_origin_ - specifies the sensor acquisition pose (origin/translation). \a Optional.
168  * - \b sensor_orientation_ - specifies the sensor acquisition pose (rotation). \a Optional.
169  *
170  * \author Patrick Mihelich, Radu B. Rusu
171  */
172  template <typename PointT>
173  class PCL_EXPORTS PointCloud
174  {
175  public:
176  /** \brief Default constructor. Sets \ref is_dense to true, \ref width
177  * and \ref height to 0, and the \ref sensor_origin_ and \ref
178  * sensor_orientation_ to identity.
179  */
181  header (), points (), width (0), height (0), is_dense (true),
182  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
183  mapping_ ()
184  {}
185 
186  /** \brief Copy constructor (needed by compilers such as Intel C++)
187  * \param[in] pc the cloud to copy into this
188  */
190  header (), points (), width (0), height (0), is_dense (true),
191  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
192  mapping_ ()
193  {
194  *this = pc;
195  }
196 
197  /** \brief Copy constructor (needed by compilers such as Intel C++)
198  * \param[in] pc the cloud to copy into this
199  */
201  header (), points (), width (0), height (0), is_dense (true),
202  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
203  mapping_ ()
204  {
205  *this = pc;
206  }
207 
208  /** \brief Copy constructor from point cloud subset
209  * \param[in] pc the cloud to copy into this
210  * \param[in] indices the subset to copy
211  */
213  const std::vector<int> &indices) :
214  header (pc.header), points (indices.size ()), width (indices.size ()), height (1), is_dense (pc.is_dense),
215  sensor_origin_ (pc.sensor_origin_), sensor_orientation_ (pc.sensor_orientation_),
216  mapping_ ()
217  {
218  // Copy the obvious
219  assert (indices.size () <= pc.size ());
220  for (size_t i = 0; i < indices.size (); i++)
221  points[i] = pc.points[indices[i]];
222  }
223 
224  /** \brief Allocate constructor from point cloud subset
225  * \param[in] width_ the cloud width
226  * \param[in] height_ the cloud height
227  * \param[in] value_ default value
228  */
229  PointCloud (uint32_t width_, uint32_t height_, const PointT& value_ = PointT ())
230  : header ()
231  , points (width_ * height_, value_)
232  , width (width_)
233  , height (height_)
234  , is_dense (true)
235  , sensor_origin_ (Eigen::Vector4f::Zero ())
236  , sensor_orientation_ (Eigen::Quaternionf::Identity ())
237  , mapping_ ()
238  {}
239 
240  /** \brief Destructor. */
241  virtual ~PointCloud () {}
242 
243  /** \brief Add a point cloud to the current cloud.
244  * \param[in] rhs the cloud to add to the current cloud
245  * \return the new cloud as a concatenation of the current cloud and the new given cloud
246  */
247  inline PointCloud&
248  operator += (const PointCloud& rhs)
249  {
250  // Make the resultant point cloud take the newest stamp
251  if (rhs.header.stamp > header.stamp)
252  header.stamp = rhs.header.stamp;
253 
254  size_t nr_points = points.size ();
255  points.resize (nr_points + rhs.points.size ());
256  for (size_t i = nr_points; i < points.size (); ++i)
257  points[i] = rhs.points[i - nr_points];
258 
259  width = static_cast<uint32_t>(points.size ());
260  height = 1;
261  if (rhs.is_dense && is_dense)
262  is_dense = true;
263  else
264  is_dense = false;
265  return (*this);
266  }
267 
268  /** \brief Add a point cloud to another cloud.
269  * \param[in] rhs the cloud to add to the current cloud
270  * \return the new cloud as a concatenation of the current cloud and the new given cloud
271  */
272  inline const PointCloud
273  operator + (const PointCloud& rhs)
274  {
275  return (PointCloud (*this) += rhs);
276  }
277 
278  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
279  * datasets (those that have height != 1).
280  * \param[in] column the column coordinate
281  * \param[in] row the row coordinate
282  */
283  inline const PointT&
284  at (int column, int row) const
285  {
286  if (this->height > 1)
287  return (points.at (row * this->width + column));
288  else
289  throw UnorganizedPointCloudException ("Can't use 2D indexing with an unorganized point cloud");
290  }
291 
292  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
293  * datasets (those that have height != 1).
294  * \param[in] column the column coordinate
295  * \param[in] row the row coordinate
296  */
297  inline PointT&
298  at (int column, int row)
299  {
300  if (this->height > 1)
301  return (points.at (row * this->width + column));
302  else
303  throw UnorganizedPointCloudException ("Can't use 2D indexing with an unorganized point cloud");
304  }
305 
306  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
307  * datasets (those that have height != 1).
308  * \param[in] column the column coordinate
309  * \param[in] row the row coordinate
310  */
311  inline const PointT&
312  operator () (size_t column, size_t row) const
313  {
314  return (points[row * this->width + column]);
315  }
316 
317  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
318  * datasets (those that have height != 1).
319  * \param[in] column the column coordinate
320  * \param[in] row the row coordinate
321  */
322  inline PointT&
323  operator () (size_t column, size_t row)
324  {
325  return (points[row * this->width + column]);
326  }
327 
328  /** \brief Return whether a dataset is organized (e.g., arranged in a structured grid).
329  * \note The height value must be different than 1 for a dataset to be organized.
330  */
331  inline bool
332  isOrganized () const
333  {
334  return (height > 1);
335  }
336 
337  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
338  * \anchor getMatrixXfMap
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 Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
353  getMatrixXfMap (int dim, int stride, int offset)
354  {
355  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
356  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, points.size (), dim, Eigen::OuterStride<> (stride)));
357  else
358  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, dim, points.size (), Eigen::OuterStride<> (stride)));
359  }
360 
361  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
362  * \anchor getMatrixXfMap
363  * \note This method is for advanced users only! Use with care!
364  *
365  * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL
366  * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure,
367  * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
368  *
369  * \param[in] dim the number of dimensions to consider for each point
370  * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns)
371  * \param[in] offset the number of dimensions to skip from the beginning of each point
372  * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point)
373  * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
374  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
375  */
376  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
377  getMatrixXfMap (int dim, int stride, int offset) const
378  {
379  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
380  return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(const_cast<PointT*>(&points[0]))+offset, points.size (), dim, Eigen::OuterStride<> (stride)));
381  else
382  return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(const_cast<PointT*>(&points[0]))+offset, dim, points.size (), Eigen::OuterStride<> (stride)));
383  }
384 
385  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
386  * \note This method is for advanced users only! Use with care!
387  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
388  * See \ref getMatrixXfMap for more information.
389  */
390  inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
392  {
393  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
394  }
395 
396  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
397  * \note This method is for advanced users only! Use with care!
398  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
399  * See \ref getMatrixXfMap for more information.
400  */
401  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
402  getMatrixXfMap () const
403  {
404  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
405  }
406 
407  /** \brief The point cloud header. It contains information about the acquisition time. */
409 
410  /** \brief The point data. */
411  std::vector<PointT, Eigen::aligned_allocator<PointT> > points;
412 
413  /** \brief The point cloud width (if organized as an image-structure). */
414  uint32_t width;
415  /** \brief The point cloud height (if organized as an image-structure). */
416  uint32_t height;
417 
418  /** \brief True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields). */
419  bool is_dense;
420 
421  /** \brief Sensor acquisition pose (origin/translation). */
422  Eigen::Vector4f sensor_origin_;
423  /** \brief Sensor acquisition pose (rotation). */
424  Eigen::Quaternionf sensor_orientation_;
425 
426  using PointType = PointT; // Make the template class available from the outside
427  using VectorType = std::vector<PointT, Eigen::aligned_allocator<PointT> >;
428  using CloudVectorType = std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > >;
429  using Ptr = boost::shared_ptr<PointCloud<PointT> >;
430  using ConstPtr = boost::shared_ptr<const PointCloud<PointT> >;
431 
432  // std container compatibility typedefs according to
433  // http://en.cppreference.com/w/cpp/concept/Container
435  using reference = PointT&;
436  using const_reference = const PointT&;
437  using difference_type = typename VectorType::difference_type;
438  using size_type = typename VectorType::size_type;
439 
440  // iterators
441  using iterator = typename VectorType::iterator;
442  using const_iterator = typename VectorType::const_iterator;
443  inline iterator begin () { return (points.begin ()); }
444  inline iterator end () { return (points.end ()); }
445  inline const_iterator begin () const { return (points.begin ()); }
446  inline const_iterator end () const { return (points.end ()); }
447 
448  //capacity
449  inline size_t size () const { return (points.size ()); }
450  inline void reserve (size_t n) { points.reserve (n); }
451  inline bool empty () const { return points.empty (); }
452 
453  /** \brief Resize the cloud
454  * \param[in] n the new cloud size
455  */
456  inline void resize (size_t n)
457  {
458  points.resize (n);
459  if (width * height != n)
460  {
461  width = static_cast<uint32_t> (n);
462  height = 1;
463  }
464  }
465 
466  //element access
467  inline const PointT& operator[] (size_t n) const { return (points[n]); }
468  inline PointT& operator[] (size_t n) { return (points[n]); }
469  inline const PointT& at (size_t n) const { return (points.at (n)); }
470  inline PointT& at (size_t n) { return (points.at (n)); }
471  inline const PointT& front () const { return (points.front ()); }
472  inline PointT& front () { return (points.front ()); }
473  inline const PointT& back () const { return (points.back ()); }
474  inline PointT& back () { return (points.back ()); }
475 
476  /** \brief Insert a new point in the cloud, at the end of the container.
477  * \note This breaks the organized structure of the cloud by setting the height to 1!
478  * \param[in] pt the point to insert
479  */
480  inline void
481  push_back (const PointT& pt)
482  {
483  points.push_back (pt);
484  width = static_cast<uint32_t> (points.size ());
485  height = 1;
486  }
487 
488  /** \brief Emplace a new point in the cloud, at the end of the container.
489  * \note This breaks the organized structure of the cloud by setting the height to 1!
490  * \param[in] args the parameters to forward to the point to construct
491  * \return reference to the emplaced point
492  */
493  template <class... Args> inline reference
494  emplace_back (Args&& ...args)
495  {
496  points.emplace_back (std::forward<Args> (args)...);
497  width = static_cast<uint32_t> (points.size ());
498  height = 1;
499  return points.back();
500  }
501 
502  /** \brief Insert a new point in the cloud, given an iterator.
503  * \note This breaks the organized structure of the cloud by setting the height to 1!
504  * \param[in] position where to insert the point
505  * \param[in] pt the point to insert
506  * \return returns the new position iterator
507  */
508  inline iterator
509  insert (iterator position, const PointT& pt)
510  {
511  iterator it = points.insert (position, pt);
512  width = static_cast<uint32_t> (points.size ());
513  height = 1;
514  return (it);
515  }
516 
517  /** \brief Insert a new point in the cloud N times, given an iterator.
518  * \note This breaks the organized structure of the cloud by setting the height to 1!
519  * \param[in] position where to insert the point
520  * \param[in] n the number of times to insert the point
521  * \param[in] pt the point to insert
522  */
523  inline void
524  insert (iterator position, size_t n, const PointT& pt)
525  {
526  points.insert (position, n, pt);
527  width = static_cast<uint32_t> (points.size ());
528  height = 1;
529  }
530 
531  /** \brief Insert a new range of points in the cloud, at a certain position.
532  * \note This breaks the organized structure of the cloud by setting the height to 1!
533  * \param[in] position where to insert the data
534  * \param[in] first where to start inserting the points from
535  * \param[in] last where to stop inserting the points from
536  */
537  template <class InputIterator> inline void
538  insert (iterator position, InputIterator first, InputIterator last)
539  {
540  points.insert (position, first, last);
541  width = static_cast<uint32_t> (points.size ());
542  height = 1;
543  }
544 
545  /** \brief Emplace a new point in the cloud, given an iterator.
546  * \note This breaks the organized structure of the cloud by setting the height to 1!
547  * \param[in] position iterator before which the point will be emplaced
548  * \param[in] args the parameters to forward to the point to construct
549  * \return returns the new position iterator
550  */
551  template <class... Args> inline iterator
552  emplace (iterator position, Args&& ...args)
553  {
554  iterator it = points.emplace (position, std::forward<Args> (args)...);
555  width = static_cast<uint32_t> (points.size ());
556  height = 1;
557  return (it);
558  }
559 
560  /** \brief Erase a point in the cloud.
561  * \note This breaks the organized structure of the cloud by setting the height to 1!
562  * \param[in] position what data point to erase
563  * \return returns the new position iterator
564  */
565  inline iterator
566  erase (iterator position)
567  {
568  iterator it = points.erase (position);
569  width = static_cast<uint32_t> (points.size ());
570  height = 1;
571  return (it);
572  }
573 
574  /** \brief Erase a set of points given by a (first, last) iterator pair
575  * \note This breaks the organized structure of the cloud by setting the height to 1!
576  * \param[in] first where to start erasing points from
577  * \param[in] last where to stop erasing points from
578  * \return returns the new position iterator
579  */
580  inline iterator
581  erase (iterator first, iterator last)
582  {
583  iterator it = points.erase (first, last);
584  width = static_cast<uint32_t> (points.size ());
585  height = 1;
586  return (it);
587  }
588 
589  /** \brief Swap a point cloud with another cloud.
590  * \param[in,out] rhs point cloud to swap this with
591  */
592  inline void
594  {
595  std::swap (header, rhs.header);
596  this->points.swap (rhs.points);
597  std::swap (width, rhs.width);
598  std::swap (height, rhs.height);
599  std::swap (is_dense, rhs.is_dense);
600  std::swap (sensor_origin_, rhs.sensor_origin_);
601  std::swap (sensor_orientation_, rhs.sensor_orientation_);
602  }
603 
604  /** \brief Removes all points in a cloud and sets the width and height to 0. */
605  inline void
606  clear ()
607  {
608  points.clear ();
609  width = 0;
610  height = 0;
611  }
612 
613  /** \brief Copy the cloud to the heap and return a smart pointer
614  * Note that deep copy is performed, so avoid using this function on non-empty clouds.
615  * The changes of the returned cloud are not mirrored back to this one.
616  * \return shared pointer to the copy of the cloud
617  */
618  inline Ptr
619  makeShared () const { return Ptr (new PointCloud<PointT> (*this)); }
620 
621  protected:
622  // This is motivated by ROS integration. Users should not need to access mapping_.
623  boost::shared_ptr<MsgFieldMap> mapping_;
624 
625  friend boost::shared_ptr<MsgFieldMap>& detail::getMapping<PointT>(pcl::PointCloud<PointT> &p);
626 
627  public:
629  };
630 
631  namespace detail
632  {
633  template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
635  {
636  return (p.mapping_);
637  }
638  } // namespace detail
639 
640  template <typename PointT> std::ostream&
641  operator << (std::ostream& s, const pcl::PointCloud<PointT> &p)
642  {
643  s << "header: " << p.header << std::endl;
644  s << "points[]: " << p.points.size () << std::endl;
645  s << "width: " << p.width << std::endl;
646  s << "height: " << p.height << std::endl;
647  s << "is_dense: " << p.is_dense << std::endl;
648  s << "sensor origin (xyz): [" <<
649  p.sensor_origin_.x () << ", " <<
650  p.sensor_origin_.y () << ", " <<
651  p.sensor_origin_.z () << "] / orientation (xyzw): [" <<
652  p.sensor_orientation_.x () << ", " <<
653  p.sensor_orientation_.y () << ", " <<
654  p.sensor_orientation_.z () << ", " <<
655  p.sensor_orientation_.w () << "]" <<
656  std::endl;
657  return (s);
658  }
659 }
660 
661 #define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud<T>;
Helper functor structure for copying data between an Eigen type and a PointT.
Definition: point_cloud.h:104
iterator erase(iterator position)
Erase a point in the cloud.
Definition: point_cloud.h:566
NdCopyPointEigenFunctor(const PointInT &p1, Eigen::VectorXf &p2)
Constructor.
Definition: point_cloud.h:112
std::vector< detail::FieldMapping > MsgFieldMap
Definition: point_cloud.h:67
size_t size() const
Definition: point_cloud.h:449
void reserve(size_t n)
Definition: point_cloud.h:450
reference emplace_back(Args &&...args)
Emplace a new point in the cloud, at the end of the container.
Definition: point_cloud.h:494
PointT & at(int column, int row)
Obtain the point given by the (column, row) coordinates.
Definition: point_cloud.h:298
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:411
Helper functor structure for copying data between an Eigen type and a PointT.
Definition: point_cloud.h:71
typename VectorType::const_iterator const_iterator
Definition: point_cloud.h:442
NdCopyEigenPointFunctor(const Eigen::VectorXf &p1, PointOutT &p2)
Constructor.
Definition: point_cloud.h:79
boost::shared_ptr< pcl::MsgFieldMap > & getMapping(pcl::PointCloud< PointT > &p)
Definition: point_cloud.h:634
Ptr makeShared() const
Copy the cloud to the heap and return a smart pointer Note that deep copy is performed, so avoid using this function on non-empty clouds.
Definition: point_cloud.h:619
PointT & back()
Definition: point_cloud.h:474
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
const_iterator begin() const
Definition: point_cloud.h:445
iterator end()
Definition: point_cloud.h:444
PointCloud(const PointCloud< PointT > &pc)
Copy constructor (needed by compilers such as Intel C++)
Definition: point_cloud.h:200
const PointT & at(size_t n) const
Definition: point_cloud.h:469
iterator emplace(iterator position, Args &&...args)
Emplace a new point in the cloud, given an iterator.
Definition: point_cloud.h:552
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:481
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap() const
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition: point_cloud.h:402
PointCloud(const PointCloud< PointT > &pc, const std::vector< int > &indices)
Copy constructor from point cloud subset.
Definition: point_cloud.h:212
PointCloud(PointCloud< PointT > &pc)
Copy constructor (needed by compilers such as Intel C++)
Definition: point_cloud.h:189
boost::shared_ptr< MsgFieldMap > mapping_
Definition: point_cloud.h:623
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: pcl_macros.h:344
std::vector< pcl::pcl::PointXYZI, Eigen::aligned_allocator< pcl::pcl::PointXYZI > > VectorType
Definition: point_cloud.h:427
Definition: bfgs.h:9
uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:416
const_iterator end() const
Definition: point_cloud.h:446
Eigen::Vector4f sensor_origin_
Sensor acquisition pose (origin/translation).
Definition: point_cloud.h:422
void insert(iterator position, size_t n, const PointT &pt)
Insert a new point in the cloud N times, given an iterator.
Definition: point_cloud.h:524
uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:414
void swap(PointCloud< PointT > &rhs)
Swap a point cloud with another cloud.
Definition: point_cloud.h:593
std::vector< PointCloud< pcl::pcl::PointXYZI >, Eigen::aligned_allocator< PointCloud< pcl::pcl::PointXYZI > > > CloudVectorType
Definition: point_cloud.h:428
Eigen::Quaternionf sensor_orientation_
Sensor acquisition pose (rotation).
Definition: point_cloud.h:424
PointT & front()
Definition: point_cloud.h:472
boost::shared_ptr< PointCloud< pcl::pcl::PointXYZI > > Ptr
Definition: point_cloud.h:429
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:606
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap()
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition: point_cloud.h:391
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:353
iterator erase(iterator first, iterator last)
Erase a set of points given by a (first, last) iterator pair.
Definition: point_cloud.h:581
PointCloud()
Default constructor.
Definition: point_cloud.h:180
PointCloud(uint32_t width_, uint32_t height_, const PointT &value_=PointT())
Allocate constructor from point cloud subset.
Definition: point_cloud.h:229
const PointT & back() const
Definition: point_cloud.h:473
virtual ~PointCloud()
Destructor.
Definition: point_cloud.h:241
const PointT & front() const
Definition: point_cloud.h:471
PointCloud represents the base class in PCL for storing collections of 3D points. ...
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:408
typename VectorType::iterator iterator
Definition: point_cloud.h:441
typename traits::POD< PointOutT >::type Pod
Definition: point_cloud.h:73
An exception that is thrown when an organized point cloud is needed but not provided.
Definition: exceptions.h:208
const pcl::pcl::PointXYZI & const_reference
Definition: point_cloud.h:436
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:538
boost::shared_ptr< const PointCloud< pcl::pcl::PointXYZI > > ConstPtr
Definition: point_cloud.h:430
typename VectorType::difference_type difference_type
Definition: point_cloud.h:437
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:419
bool isOrganized() const
Return whether a dataset is organized (e.g., arranged in a structured grid).
Definition: point_cloud.h:332
iterator begin()
Definition: point_cloud.h:443
void resize(size_t n)
Resize the cloud.
Definition: point_cloud.h:456
A point structure representing Euclidean xyz coordinates, and the RGB color.
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:377
PointT & at(size_t n)
Definition: point_cloud.h:470
const PointT & at(int column, int row) const
Obtain the point given by the (column, row) coordinates.
Definition: point_cloud.h:284
typename VectorType::size_type size_type
Definition: point_cloud.h:438
iterator insert(iterator position, const PointT &pt)
Insert a new point in the cloud, given an iterator.
Definition: point_cloud.h:509
bool empty() const
Definition: point_cloud.h:451
pcl::uint64_t stamp
A timestamp associated with the time when the data was acquired.
Definition: PCLHeader.h:26
typename traits::POD< PointInT >::type Pod
Definition: point_cloud.h:106