Point Cloud Library (PCL)  1.7.0
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 #ifndef PCL_POINT_CLOUD_H_
40 #define PCL_POINT_CLOUD_H_
41 
42 #ifdef __GNUC__
43 #pragma GCC system_header
44 #endif
45 
46 #include <Eigen/StdVector>
47 #include <Eigen/Geometry>
48 #include <pcl/PCLHeader.h>
49 #include <pcl/exceptions.h>
50 #include <pcl/point_traits.h>
51 
52 namespace pcl
53 {
54  namespace detail
55  {
56  struct FieldMapping
57  {
59  size_t struct_offset;
60  size_t size;
61  };
62  } // namespace detail
63 
64  // Forward declarations
65  template <typename PointT> class PointCloud;
66  typedef std::vector<detail::FieldMapping> MsgFieldMap;
67 
68  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
69  template <typename PointOutT>
71  {
73 
74  /** \brief Constructor
75  * \param[in] p1 the input Eigen type
76  * \param[out] p2 the output Point type
77  */
78  NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointOutT &p2)
79  : p1_ (p1),
80  p2_ (reinterpret_cast<Pod&>(p2)),
81  f_idx_ (0) { }
82 
83  /** \brief Operator. Data copy happens here. */
84  template<typename Key> inline void
86  {
87  //boost::fusion::at_key<Key> (p2_) = p1_[f_idx_++];
89  uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value;
90  *reinterpret_cast<T*>(data_ptr) = static_cast<T> (p1_[f_idx_++]);
91  }
92 
93  private:
94  const Eigen::VectorXf &p1_;
95  Pod &p2_;
96  int f_idx_;
97  public:
98  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
99  };
100 
101  /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */
102  template <typename PointInT>
104  {
106 
107  /** \brief Constructor
108  * \param[in] p1 the input Point type
109  * \param[out] p2 the output Eigen type
110  */
111  NdCopyPointEigenFunctor (const PointInT &p1, Eigen::VectorXf &p2)
112  : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
113 
114  /** \brief Operator. Data copy happens here. */
115  template<typename Key> inline void
117  {
118  //p2_[f_idx_++] = boost::fusion::at_key<Key> (p1_);
120  const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value;
121  p2_[f_idx_++] = static_cast<float> (*reinterpret_cast<const T*>(data_ptr));
122  }
123 
124  private:
125  const Pod &p1_;
126  Eigen::VectorXf &p2_;
127  int f_idx_;
128  public:
129  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
130  };
131 
132  namespace detail
133  {
134  template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
136  } // namespace detail
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 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  */
180  header (), points (), width (0), height (0), is_dense (true),
181  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
182  mapping_ ()
183  {}
184 
185  /** \brief Copy constructor (needed by compilers such as Intel C++)
186  * \param[in] pc the cloud to copy into this
187  */
189  header (), points (), width (0), height (0), is_dense (true),
190  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
191  mapping_ ()
192  {
193  *this = pc;
194  }
195 
196  /** \brief Copy constructor (needed by compilers such as Intel C++)
197  * \param[in] pc the cloud to copy into this
198  */
200  header (), points (), width (0), height (0), is_dense (true),
201  sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
202  mapping_ ()
203  {
204  *this = pc;
205  }
206 
207  /** \brief Copy constructor from point cloud subset
208  * \param[in] pc the cloud to copy into this
209  * \param[in] indices the subset to copy
210  */
212  const std::vector<int> &indices) :
213  header (pc.header), points (indices.size ()), width (indices.size ()), height (1), is_dense (pc.is_dense),
215  mapping_ ()
216  {
217  // Copy the obvious
218  assert (indices.size () <= pc.size ());
219  for (size_t i = 0; i < indices.size (); i++)
220  points[i] = pc.points[indices[i]];
221  }
222 
223  /** \brief Allocate constructor from point cloud subset
224  * \param[in] width_ the cloud width
225  * \param[in] height_ the cloud height
226  * \param[in] value_ default value
227  */
228  PointCloud (uint32_t width_, uint32_t height_, const PointT& value_ = PointT ())
229  : header ()
230  , points (width_ * height_, value_)
231  , width (width_)
232  , height (height_)
233  , is_dense (true)
234  , sensor_origin_ (Eigen::Vector4f::Zero ())
235  , sensor_orientation_ (Eigen::Quaternionf::Identity ())
236  , mapping_ ()
237  {}
238 
239  /** \brief Destructor. */
240  virtual ~PointCloud () {}
241 
242  /** \brief Add a point cloud to the current cloud.
243  * \param[in] rhs the cloud to add to the current cloud
244  * \return the new cloud as a concatenation of the current cloud and the new given cloud
245  */
246  inline PointCloud&
248  {
249  // Make the resultant point cloud take the newest stamp
250  if (rhs.header.stamp > header.stamp)
251  header.stamp = rhs.header.stamp;
252 
253  size_t nr_points = points.size ();
254  points.resize (nr_points + rhs.points.size ());
255  for (size_t i = nr_points; i < points.size (); ++i)
256  points[i] = rhs.points[i - nr_points];
257 
258  width = static_cast<uint32_t>(points.size ());
259  height = 1;
260  if (rhs.is_dense && is_dense)
261  is_dense = true;
262  else
263  is_dense = false;
264  return (*this);
265  }
266 
267  /** \brief Add a point cloud to another cloud.
268  * \param[in] rhs the cloud to add to the current cloud
269  * \return the new cloud as a concatenation of the current cloud and the new given cloud
270  */
271  inline const PointCloud
273  {
274  return (PointCloud (*this) += rhs);
275  }
276 
277  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
278  * datasets (those that have height != 1).
279  * \param[in] column the column coordinate
280  * \param[in] row the row coordinate
281  */
282  inline const PointT&
283  at (int column, int row) const
284  {
285  if (this->height > 1)
286  return (points.at (row * this->width + column));
287  else
288  throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud");
289  }
290 
291  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
292  * datasets (those that have height != 1).
293  * \param[in] column the column coordinate
294  * \param[in] row the row coordinate
295  */
296  inline PointT&
297  at (int column, int row)
298  {
299  if (this->height > 1)
300  return (points.at (row * this->width + column));
301  else
302  throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud");
303  }
304 
305  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
306  * datasets (those that have height != 1).
307  * \param[in] column the column coordinate
308  * \param[in] row the row coordinate
309  */
310  inline const PointT&
311  operator () (size_t column, size_t row) const
312  {
313  return (points[row * this->width + column]);
314  }
315 
316  /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized
317  * datasets (those that have height != 1).
318  * \param[in] column the column coordinate
319  * \param[in] row the row coordinate
320  */
321  inline PointT&
322  operator () (size_t column, size_t row)
323  {
324  return (points[row * this->width + column]);
325  }
326 
327  /** \brief Return whether a dataset is organized (e.g., arranged in a structured grid).
328  * \note The height value must be different than 1 for a dataset to be organized.
329  */
330  inline bool
331  isOrganized () const
332  {
333  return (height > 1);
334  }
335 
336  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
337  * \anchor getMatrixXfMap
338  * \note This method is for advanced users only! Use with care!
339  *
340  * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL
341  * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure,
342  * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
343  *
344  * \param[in] dim the number of dimensions to consider for each point
345  * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns)
346  * \param[in] offset the number of dimensions to skip from the beginning of each point
347  * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point)
348  * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
349  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
350  */
351  inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
352  getMatrixXfMap (int dim, int stride, int offset)
353  {
354  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
355  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, points.size (), dim, Eigen::OuterStride<> (stride)));
356  else
357  return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, dim, points.size (), Eigen::OuterStride<> (stride)));
358  }
359 
360  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
361  * \anchor getMatrixXfMap
362  * \note This method is for advanced users only! Use with care!
363  *
364  * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL
365  * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure,
366  * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
367  *
368  * \param[in] dim the number of dimensions to consider for each point
369  * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns)
370  * \param[in] offset the number of dimensions to skip from the beginning of each point
371  * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point)
372  * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
373  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
374  */
375  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
376  getMatrixXfMap (int dim, int stride, int offset) const
377  {
378  if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
379  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)));
380  else
381  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)));
382  }
383 
384  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
385  * \note This method is for advanced users only! Use with care!
386  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
387  * See \ref getMatrixXfMap for more information.
388  */
389  inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
391  {
392  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
393  }
394 
395  /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
396  * \note This method is for advanced users only! Use with care!
397  * \attention PointT types are most of the time aligned, so the offsets are not continuous!
398  * See \ref getMatrixXfMap for more information.
399  */
400  inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
401  getMatrixXfMap () const
402  {
403  return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
404  }
405 
406  /** \brief The point cloud header. It contains information about the acquisition time. */
408 
409  /** \brief The point data. */
410  std::vector<PointT, Eigen::aligned_allocator<PointT> > points;
411 
412  /** \brief The point cloud width (if organized as an image-structure). */
413  uint32_t width;
414  /** \brief The point cloud height (if organized as an image-structure). */
415  uint32_t height;
416 
417  /** \brief True if no points are invalid (e.g., have NaN or Inf values). */
418  bool is_dense;
419 
420  /** \brief Sensor acquisition pose (origin/translation). */
421  Eigen::Vector4f sensor_origin_;
422  /** \brief Sensor acquisition pose (rotation). */
423  Eigen::Quaternionf sensor_orientation_;
424 
425  typedef PointT PointType; // Make the template class available from the outside
426  typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > VectorType;
427  typedef std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > > CloudVectorType;
428  typedef boost::shared_ptr<PointCloud<PointT> > Ptr;
429  typedef boost::shared_ptr<const PointCloud<PointT> > ConstPtr;
430 
431  // iterators
432  typedef typename VectorType::iterator iterator;
433  typedef typename VectorType::const_iterator const_iterator;
434  inline iterator begin () { return (points.begin ()); }
435  inline iterator end () { return (points.end ()); }
436  inline const_iterator begin () const { return (points.begin ()); }
437  inline const_iterator end () const { return (points.end ()); }
438 
439  //capacity
440  inline size_t size () const { return (points.size ()); }
441  inline void reserve (size_t n) { points.reserve (n); }
442  inline bool empty () const { return points.empty (); }
443 
444  /** \brief Resize the cloud
445  * \param[in] n the new cloud size
446  */
447  inline void resize (size_t n)
448  {
449  points.resize (n);
450  if (width * height != n)
451  {
452  width = static_cast<uint32_t> (n);
453  height = 1;
454  }
455  }
456 
457  //element access
458  inline const PointT& operator[] (size_t n) const { return (points[n]); }
459  inline PointT& operator[] (size_t n) { return (points[n]); }
460  inline const PointT& at (size_t n) const { return (points.at (n)); }
461  inline PointT& at (size_t n) { return (points.at (n)); }
462  inline const PointT& front () const { return (points.front ()); }
463  inline PointT& front () { return (points.front ()); }
464  inline const PointT& back () const { return (points.back ()); }
465  inline PointT& back () { return (points.back ()); }
466 
467  /** \brief Insert a new point in the cloud, at the end of the container.
468  * \note This breaks the organized structure of the cloud by setting the height to 1!
469  * \param[in] pt the point to insert
470  */
471  inline void
472  push_back (const PointT& pt)
473  {
474  points.push_back (pt);
475  width = static_cast<uint32_t> (points.size ());
476  height = 1;
477  }
478 
479  /** \brief Insert a new point in the cloud, given an iterator.
480  * \note This breaks the organized structure of the cloud by setting the height to 1!
481  * \param[in] position where to insert the point
482  * \param[in] pt the point to insert
483  * \return returns the new position iterator
484  */
485  inline iterator
486  insert (iterator position, const PointT& pt)
487  {
488  iterator it = points.insert (position, pt);
489  width = static_cast<uint32_t> (points.size ());
490  height = 1;
491  return (it);
492  }
493 
494  /** \brief Insert a new point in the cloud N times, given an iterator.
495  * \note This breaks the organized structure of the cloud by setting the height to 1!
496  * \param[in] position where to insert the point
497  * \param[in] n the number of times to insert the point
498  * \param[in] pt the point to insert
499  */
500  inline void
501  insert (iterator position, size_t n, const PointT& pt)
502  {
503  points.insert (position, n, pt);
504  width = static_cast<uint32_t> (points.size ());
505  height = 1;
506  }
507 
508  /** \brief Insert a new range of points in the cloud, at a certain position.
509  * \note This breaks the organized structure of the cloud by setting the height to 1!
510  * \param[in] position where to insert the data
511  * \param[in] first where to start inserting the points from
512  * \param[in] last where to stop inserting the points from
513  */
514  template <class InputIterator> inline void
515  insert (iterator position, InputIterator first, InputIterator last)
516  {
517  points.insert (position, first, last);
518  width = static_cast<uint32_t> (points.size ());
519  height = 1;
520  }
521 
522  /** \brief Erase a point in the cloud.
523  * \note This breaks the organized structure of the cloud by setting the height to 1!
524  * \param[in] position what data point to erase
525  * \return returns the new position iterator
526  */
527  inline iterator
528  erase (iterator position)
529  {
530  iterator it = points.erase (position);
531  width = static_cast<uint32_t> (points.size ());
532  height = 1;
533  return (it);
534  }
535 
536  /** \brief Erase a set of points given by a (first, last) iterator pair
537  * \note This breaks the organized structure of the cloud by setting the height to 1!
538  * \param[in] first where to start erasing points from
539  * \param[in] last where to stop erasing points from
540  * \return returns the new position iterator
541  */
542  inline iterator
543  erase (iterator first, iterator last)
544  {
545  iterator it = points.erase (first, last);
546  width = static_cast<uint32_t> (points.size ());
547  height = 1;
548  return (it);
549  }
550 
551  /** \brief Swap a point cloud with another cloud.
552  * \param[in,out] rhs point cloud to swap this with
553  */
554  inline void
556  {
557  this->points.swap (rhs.points);
558  std::swap (width, rhs.width);
559  std::swap (height, rhs.height);
560  std::swap (is_dense, rhs.is_dense);
561  std::swap (sensor_origin_, rhs.sensor_origin_);
562  std::swap (sensor_orientation_, rhs.sensor_orientation_);
563  }
564 
565  /** \brief Removes all points in a cloud and sets the width and height to 0. */
566  inline void
567  clear ()
568  {
569  points.clear ();
570  width = 0;
571  height = 0;
572  }
573 
574  /** \brief Copy the cloud to the heap and return a smart pointer
575  * Note that deep copy is performed, so avoid using this function on non-empty clouds.
576  * The changes of the returned cloud are not mirrored back to this one.
577  * \return shared pointer to the copy of the cloud
578  */
579  inline Ptr
580  makeShared () const { return Ptr (new PointCloud<PointT> (*this)); }
581 
582  protected:
583  // This is motivated by ROS integration. Users should not need to access mapping_.
584  boost::shared_ptr<MsgFieldMap> mapping_;
585 
586  friend boost::shared_ptr<MsgFieldMap>& detail::getMapping<PointT>(pcl::PointCloud<PointT> &p);
587 
588  public:
589  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
590  };
591 
592  namespace detail
593  {
594  template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
596  {
597  return (p.mapping_);
598  }
599  } // namespace detail
600 
601  template <typename PointT> std::ostream&
602  operator << (std::ostream& s, const pcl::PointCloud<PointT> &p)
603  {
604  s << "points[]: " << p.points.size () << std::endl;
605  s << "width: " << p.width << std::endl;
606  s << "height: " << p.height << std::endl;
607  s << "is_dense: " << p.is_dense << std::endl;
608  s << "sensor origin (xyz): [" <<
609  p.sensor_origin_.x () << ", " <<
610  p.sensor_origin_.y () << ", " <<
611  p.sensor_origin_.z () << "] / orientation (xyzw): [" <<
612  p.sensor_orientation_.x () << ", " <<
613  p.sensor_orientation_.y () << ", " <<
614  p.sensor_orientation_.z () << ", " <<
615  p.sensor_orientation_.w () << "]" <<
616  std::endl;
617  return (s);
618  }
619 }
620 
621 #define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud<T>;
622 
623 #endif //#ifndef PCL_POINT_CLOUD_H_