00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_POINT_CLOUD_H_
00041 #define PCL_POINT_CLOUD_H_
00042
00043 #include <pcl/common/eigen.h>
00044 #include <cstddef>
00045 #include <std_msgs/Header.h>
00046 #include <pcl/pcl_macros.h>
00047 #include <pcl/exceptions.h>
00048 #include <pcl/cloud_properties.h>
00049 #include <pcl/channel_properties.h>
00050 #include <pcl/point_traits.h>
00051 #include <pcl/for_each_type.h>
00052 #include <boost/shared_ptr.hpp>
00053 #include <map>
00054 #include <boost/mpl/size.hpp>
00055
00056 namespace pcl
00057 {
00058 namespace detail
00059 {
00060 struct FieldMapping
00061 {
00062 size_t serialized_offset;
00063 size_t struct_offset;
00064 size_t size;
00065 };
00066 }
00067
00068
00069 template <typename PointT> class PointCloud;
00070 typedef std::vector<detail::FieldMapping> MsgFieldMap;
00071
00073
00074 template <typename PointOutT>
00075 struct NdCopyEigenPointFunctor
00076 {
00077 typedef typename traits::POD<PointOutT>::type Pod;
00078
00083 NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointOutT &p2)
00084 : p1_ (p1),
00085 p2_ (reinterpret_cast<Pod&>(p2)),
00086 f_idx_ (0) { }
00087
00089 template<typename Key> inline void
00090 operator() ()
00091 {
00092
00093 typedef typename pcl::traits::datatype<PointOutT, Key>::type T;
00094 uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value;
00095 *reinterpret_cast<T*>(data_ptr) = static_cast<T> (p1_[f_idx_++]);
00096 }
00097
00098 private:
00099 const Eigen::VectorXf &p1_;
00100 Pod &p2_;
00101 int f_idx_;
00102 public:
00103 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00104 };
00105
00107
00108 template <typename PointInT>
00109 struct NdCopyPointEigenFunctor
00110 {
00111 typedef typename traits::POD<PointInT>::type Pod;
00112
00117 NdCopyPointEigenFunctor (const PointInT &p1, Eigen::VectorXf &p2)
00118 : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
00119
00121 template<typename Key> inline void
00122 operator() ()
00123 {
00124
00125 typedef typename pcl::traits::datatype<PointInT, Key>::type T;
00126 const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value;
00127 p2_[f_idx_++] = static_cast<float> (*reinterpret_cast<const T*>(data_ptr));
00128 }
00129
00130 private:
00131 const Pod &p1_;
00132 Eigen::VectorXf &p2_;
00133 int f_idx_;
00134 public:
00135 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00136 };
00137
00138 namespace detail
00139 {
00140 template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
00141 getMapping (pcl::PointCloud<PointT>& p);
00142 }
00143
00177 template <typename PointT>
00178 class PointCloud
00179 {
00180 public:
00185 PointCloud () :
00186 header (), points (), width (0), height (0), is_dense (true),
00187 sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
00188 mapping_ ()
00189 {}
00190
00194 PointCloud (PointCloud<PointT> &pc) :
00195 header (), points (), width (0), height (0), is_dense (true),
00196 sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
00197 mapping_ ()
00198 {
00199 *this = pc;
00200 }
00201
00205 PointCloud (const PointCloud<PointT> &pc) :
00206 header (), points (), width (0), height (0), is_dense (true),
00207 sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()),
00208 mapping_ ()
00209 {
00210 *this = pc;
00211 }
00212
00217 PointCloud (const PointCloud<PointT> &pc,
00218 const std::vector<int> &indices) :
00219 header (pc.header), points (indices.size ()), width (indices.size ()), height (1), is_dense (pc.is_dense),
00220 sensor_origin_ (pc.sensor_origin_), sensor_orientation_ (pc.sensor_orientation_),
00221 mapping_ ()
00222 {
00223
00224 assert (indices.size () <= pc.size ());
00225 for (size_t i = 0; i < indices.size (); i++)
00226 points[i] = pc.points[indices[i]];
00227 }
00228
00234 PointCloud (uint32_t width_, uint32_t height_, const PointT& value_ = PointT ())
00235 : header ()
00236 , points (width_ * height_, value_)
00237 , width (width_)
00238 , height (height_)
00239 , is_dense (true)
00240 , sensor_origin_ (Eigen::Vector4f::Zero ())
00241 , sensor_orientation_ (Eigen::Quaternionf::Identity ())
00242 , mapping_ ()
00243 {}
00244
00246 virtual ~PointCloud () {}
00247
00249
00253 inline PointCloud&
00254 operator += (const PointCloud& rhs)
00255 {
00256
00257 if (rhs.header.stamp > header.stamp)
00258 header.stamp = rhs.header.stamp;
00259
00260 size_t nr_points = points.size ();
00261 points.resize (nr_points + rhs.points.size ());
00262 for (size_t i = nr_points; i < points.size (); ++i)
00263 points[i] = rhs.points[i - nr_points];
00264
00265 width = static_cast<uint32_t>(points.size ());
00266 height = 1;
00267 if (rhs.is_dense && is_dense)
00268 is_dense = true;
00269 else
00270 is_dense = false;
00271 return (*this);
00272 }
00273
00275
00279 inline const PointCloud
00280 operator + (const PointCloud& rhs)
00281 {
00282 return (PointCloud (*this) += rhs);
00283 }
00284
00286
00291 inline const PointT&
00292 at (int column, int row) const
00293 {
00294 if (this->height > 1)
00295 return (points.at (row * this->width + column));
00296 else
00297 throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud");
00298 }
00299
00305 inline PointT&
00306 at (int column, int row)
00307 {
00308 if (this->height > 1)
00309 return (points.at (row * this->width + column));
00310 else
00311 throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud");
00312 }
00313
00315
00320 inline const PointT&
00321 operator () (size_t column, size_t row) const
00322 {
00323 return (points[row * this->width + column]);
00324 }
00325
00331 inline PointT&
00332 operator () (size_t column, size_t row)
00333 {
00334 return (points[row * this->width + column]);
00335 }
00336
00338
00341 inline bool
00342 isOrganized () const
00343 {
00344 return (height != 1);
00345 }
00346
00348
00363 inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
00364 getMatrixXfMap (int dim, int stride, int offset)
00365 {
00366 if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
00367 return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, points.size (), dim, Eigen::OuterStride<> (stride)));
00368 else
00369 return (Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, dim, points.size (), Eigen::OuterStride<> (stride)));
00370 }
00371
00387 inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
00388 getMatrixXfMap (int dim, int stride, int offset) const
00389 {
00390 if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit)
00391 return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, points.size (), dim, Eigen::OuterStride<> (stride)));
00392 else
00393 return (Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >(reinterpret_cast<float*>(&points[0])+offset, dim, points.size (), Eigen::OuterStride<> (stride)));
00394 }
00395
00397
00402 inline Eigen::Map<Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
00403 getMatrixXfMap ()
00404 {
00405 return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
00406 }
00407
00413 inline const Eigen::Map<const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> >
00414 getMatrixXfMap () const
00415 {
00416 return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0));
00417 }
00418
00420 std_msgs::Header header;
00421
00423 std::vector<PointT, Eigen::aligned_allocator<PointT> > points;
00424
00426 uint32_t width;
00428 uint32_t height;
00429
00431 bool is_dense;
00432
00434 Eigen::Vector4f sensor_origin_;
00436 Eigen::Quaternionf sensor_orientation_;
00437
00438 typedef PointT PointType;
00439 typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > VectorType;
00440 typedef std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > > CloudVectorType;
00441 typedef boost::shared_ptr<PointCloud<PointT> > Ptr;
00442 typedef boost::shared_ptr<const PointCloud<PointT> > ConstPtr;
00443
00444
00445 typedef typename VectorType::iterator iterator;
00446 typedef typename VectorType::const_iterator const_iterator;
00447 inline iterator begin () { return (points.begin ()); }
00448 inline iterator end () { return (points.end ()); }
00449 inline const_iterator begin () const { return (points.begin ()); }
00450 inline const_iterator end () const { return (points.end ()); }
00451
00452
00453 inline size_t size () const { return (points.size ()); }
00454 inline void reserve (size_t n) { points.reserve (n); }
00455 inline bool empty () const { return points.empty (); }
00456
00460 inline void resize (size_t n)
00461 {
00462 points.resize (n);
00463 if (width * height != n)
00464 {
00465 width = static_cast<uint32_t> (n);
00466 height = 1;
00467 }
00468 }
00469
00470
00471 inline const PointT& operator[] (size_t n) const { return (points[n]); }
00472 inline PointT& operator[] (size_t n) { return (points[n]); }
00473 inline const PointT& at (size_t n) const { return (points.at (n)); }
00474 inline PointT& at (size_t n) { return (points.at (n)); }
00475 inline const PointT& front () const { return (points.front ()); }
00476 inline PointT& front () { return (points.front ()); }
00477 inline const PointT& back () const { return (points.back ()); }
00478 inline PointT& back () { return (points.back ()); }
00479
00484 inline void
00485 push_back (const PointT& pt)
00486 {
00487 points.push_back (pt);
00488 width = static_cast<uint32_t> (points.size ());
00489 height = 1;
00490 }
00491
00498 inline iterator
00499 insert (iterator position, const PointT& pt)
00500 {
00501 iterator it = points.insert (position, pt);
00502 width = static_cast<uint32_t> (points.size ());
00503 height = 1;
00504 return (it);
00505 }
00506
00513 inline void
00514 insert (iterator position, size_t n, const PointT& pt)
00515 {
00516 points.insert (position, n, pt);
00517 width = static_cast<uint32_t> (points.size ());
00518 height = 1;
00519 }
00520
00527 template <class InputIterator> inline void
00528 insert (iterator position, InputIterator first, InputIterator last)
00529 {
00530 points.insert (position, first, last);
00531 width = static_cast<uint32_t> (points.size ());
00532 height = 1;
00533 }
00534
00540 inline iterator
00541 erase (iterator position)
00542 {
00543 iterator it = points.erase (position);
00544 width = static_cast<uint32_t> (points.size ());
00545 height = 1;
00546 return (it);
00547 }
00548
00555 inline iterator
00556 erase (iterator first, iterator last)
00557 {
00558 iterator it = points.erase (first, last);
00559 width = static_cast<uint32_t> (points.size ());
00560 height = 1;
00561 return (it);
00562 }
00563
00567 inline void
00568 swap (PointCloud<PointT> &rhs)
00569 {
00570 this->points.swap (rhs.points);
00571 std::swap (width, rhs.width);
00572 std::swap (height, rhs.height);
00573 std::swap (is_dense, rhs.is_dense);
00574 std::swap (sensor_origin_, rhs.sensor_origin_);
00575 std::swap (sensor_orientation_, rhs.sensor_orientation_);
00576 }
00577
00579 inline void
00580 clear ()
00581 {
00582 points.clear ();
00583 width = 0;
00584 height = 0;
00585 }
00586
00592 inline Ptr
00593 makeShared () const { return Ptr (new PointCloud<PointT> (*this)); }
00594
00595 protected:
00596
00597 boost::shared_ptr<MsgFieldMap> mapping_;
00598
00599 friend boost::shared_ptr<MsgFieldMap>& detail::getMapping<PointT>(pcl::PointCloud<PointT> &p);
00600
00601 public:
00602 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00603 };
00604
00623 template <>
00624 class PointCloud<Eigen::MatrixXf>
00625 {
00626 public:
00630 PointCloud () :
00631 properties (), points (Eigen::MatrixXf (0, 0)), channels (), width (0), height (0), is_dense (true)
00632 {}
00633
00637 PointCloud (PointCloud<Eigen::MatrixXf> &pc) :
00638 properties (), points (Eigen::MatrixXf (0, 0)), channels (), width (0), height (0), is_dense (true)
00639 {
00640 *this = pc;
00641 }
00642
00646 template <typename PointT>
00647 PointCloud (PointCloud<PointT> &pc) :
00648 properties (), points (Eigen::MatrixXf (0, 0)), channels (),
00649 width (pc.width), height (pc.height), is_dense (pc.is_dense)
00650 {
00651
00652 properties.acquisition_time = pc.header.stamp.sec;
00653 properties.sensor_origin = pc.sensor_origin_;
00654 properties.sensor_orientation = pc.sensor_orientation_;
00655
00656 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00657
00658 pcl::for_each_type <FieldList> (CopyFieldsChannelProperties <PointT> (channels));
00659
00660
00661 points.resize (pc.points.size (), boost::mpl::size<FieldList>::value);
00662
00663 for (size_t cp = 0; cp < pc.points.size (); ++cp)
00664 pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor<PointT, Eigen::MatrixXf::RowXpr> (pc.points[cp], points.row (cp)));
00665 }
00666
00670 PointCloud (const PointCloud<Eigen::MatrixXf> &pc) :
00671 properties (), points (Eigen::MatrixXf (0, 0)), channels (), width (0), height (0), is_dense (true)
00672 {
00673 *this = pc;
00674 }
00675
00679 template <typename PointT>
00680 PointCloud (const PointCloud<PointT> &pc) :
00681 properties (), points (Eigen::MatrixXf (0, 0)), channels (),
00682 width (pc.width), height (pc.height), is_dense (pc.is_dense)
00683 {
00684
00685 properties.acquisition_time = pc.header.stamp;
00686 properties.sensor_origin = pc.sensor_origin_;
00687 properties.sensor_orientation = pc.sensor_orientation_;
00688
00689 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00690
00691
00692 pcl::for_each_type <FieldList> (CopyFieldsChannelProperties <PointT> (channels));
00693
00694
00695 points.resize (pc.points.size (), boost::mpl::size<FieldList>::value);
00696
00697 for (size_t cp = 0; cp < pc.points.size (); ++cp)
00698 pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor<PointT, Eigen::MatrixXf::RowXpr> (pc.points[cp], points.row (cp)));
00699 }
00700
00705 PointCloud (const PointCloud &pc,
00706 const std::vector<int> &indices) :
00707 properties (pc.properties),
00708 points (Eigen::MatrixXf (indices.size (), pc.points.cols ())),
00709 channels (pc.channels),
00710 width (static_cast<uint32_t> (indices.size ())), height (1), is_dense (pc.is_dense)
00711 {
00712
00713 assert (static_cast<int>(indices.size ()) <= pc.points.rows ());
00714 for (size_t i = 0; i < indices.size (); i++)
00715 points.row (i) = pc.points.row (indices[i]);
00716 }
00717
00723 inline PointCloud (uint32_t _width, uint32_t _height, uint32_t _dim)
00724 : properties ()
00725 , points (Eigen::MatrixXf (_width * _height, _dim))
00726 , channels ()
00727 , width (_width)
00728 , height (_height)
00729 , is_dense (true)
00730 {}
00731
00736 inline PointCloud (uint32_t _num_points, uint32_t _dim)
00737 : properties ()
00738 , points (Eigen::MatrixXf (_num_points, _dim))
00739 , channels ()
00740 , width (_num_points)
00741 , height (1)
00742 , is_dense (true)
00743 {}
00744
00746 virtual ~PointCloud () {}
00747
00749
00753 inline PointCloud&
00754 operator += (const PointCloud& rhs)
00755 {
00756 if (rhs.properties.acquisition_time > properties.acquisition_time)
00757 properties.acquisition_time = rhs.properties.acquisition_time;
00758
00759 properties.sensor_origin = Eigen::Vector4f::Zero ();
00760 properties.sensor_orientation = Eigen::Quaternionf::Identity ();
00761
00762 int nr_points = static_cast<int>(points.rows ());
00763 points.resize (nr_points + rhs.points.rows (), points.cols ());
00764 for (int i = nr_points; i < points.rows (); ++i)
00765 points.row (i) = rhs.points.row (i - nr_points);
00766
00767 channels = rhs.channels;
00768 width = static_cast<uint32_t>(points.rows ());
00769 height = 1;
00770 if (rhs.is_dense && is_dense)
00771 is_dense = true;
00772 else
00773 is_dense = false;
00774 return (*this);
00775 }
00776
00778
00782 inline const PointCloud
00783 operator + (const PointCloud& rhs)
00784 {
00785 return (PointCloud (*this) += rhs);
00786 }
00787
00789
00794 inline Eigen::Map<Eigen::VectorXf>
00795 at (int column, int row)
00796 {
00797 if (height > 1)
00798 return (Eigen::VectorXf::Map (&points (row * width + column, 0), points.cols ()));
00799 else
00800 throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud");
00801 }
00802
00804
00809 inline Eigen::Map<Eigen::VectorXf>
00810 operator () (int column, int row)
00811 {
00812 return (Eigen::VectorXf::Map (&points (row * width + column, 0), points.cols ()));
00813 }
00814
00816
00819 inline bool
00820 isOrganized () const
00821 {
00822 return (height != 1);
00823 }
00824
00826
00827 inline bool
00828 empty () const
00829 {
00830 return (points.rows () == 0);
00831 }
00832
00834 pcl::CloudProperties properties;
00835
00837 Eigen::MatrixXf points;
00838
00840 std::map<std::string, pcl::ChannelProperties> channels;
00841
00843 uint32_t width;
00845 uint32_t height;
00846
00848 bool is_dense;
00849
00850 typedef boost::shared_ptr<PointCloud<Eigen::MatrixXf> > Ptr;
00851 typedef boost::shared_ptr<const PointCloud<Eigen::MatrixXf> > ConstPtr;
00852
00853 inline size_t size () const { return (points.rows ()); }
00854
00858 inline void
00859 swap (PointCloud<Eigen::MatrixXf> &rhs)
00860 {
00861 std::swap (points, rhs.points);
00862 std::swap (width, rhs.width);
00863 std::swap (height, rhs.height);
00864 std::swap (is_dense, rhs.is_dense);
00865 std::swap (properties, rhs.properties);
00866 std::swap (channels, rhs.channels);
00867 }
00868
00870 inline void
00871 clear ()
00872 {
00873 points.resize (0, 0);
00874 width = 0;
00875 height = 0;
00876 }
00877
00883 inline Ptr
00884 makeShared () { return Ptr (new PointCloud<Eigen::MatrixXf> (*this)); }
00885
00890 inline ConstPtr
00891 makeShared () const { return ConstPtr (new PointCloud<Eigen::MatrixXf> (*this)); }
00892
00893 public:
00894 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00895
00896 private:
00898
00899 template <typename PointOutT, typename PointInT>
00900 struct NdCopyEigenPointFunctor
00901 {
00902 typedef typename traits::POD<PointOutT>::type Pod;
00903
00908 NdCopyEigenPointFunctor (const PointInT p1, PointOutT &p2)
00909 : p1_ (p1),
00910 p2_ (reinterpret_cast<Pod&>(p2)),
00911 f_idx_ (0) { }
00912
00914 template<typename Key> inline void
00915 operator() ()
00916 {
00917
00918 typedef typename pcl::traits::datatype<PointOutT, Key>::type T;
00919 uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value;
00920 *reinterpret_cast<T*>(data_ptr) = p1_[f_idx_++];
00921 }
00922
00923 private:
00924 const PointInT p1_;
00925 Pod &p2_;
00926 int f_idx_;
00927 public:
00928 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00929 };
00930
00932
00933 template <typename PointInT, typename PointOutT>
00934 struct NdCopyPointEigenFunctor
00935 {
00936 typedef typename traits::POD<PointInT>::type Pod;
00937
00942 NdCopyPointEigenFunctor (const PointInT &p1, PointOutT p2)
00943 : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
00944
00946 template<typename Key> inline void
00947 operator() ()
00948 {
00949
00950 typedef typename pcl::traits::datatype<PointInT, Key>::type T;
00951 const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value;
00952 p2_[f_idx_++] = *reinterpret_cast<const T*>(data_ptr);
00953 }
00954
00955 private:
00956 const Pod &p1_;
00957 PointOutT p2_;
00958 int f_idx_;
00959 public:
00960 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00961 };
00962
00964
00965 template <typename T>
00966 struct CopyFieldsChannelProperties
00967 {
00971 CopyFieldsChannelProperties (std::map<std::string, pcl::ChannelProperties> &channels)
00972 : channels_ (channels) {}
00973
00975 template<typename U> inline void
00976 operator() ()
00977 {
00978
00979 std::string name = pcl::traits::name<T, U>::value;
00980 channels_[name].name = name;
00981 channels_[name].offset = pcl::traits::offset<T, U>::value;
00982 uint8_t datatype = pcl::traits::datatype<T, U>::value;
00983 channels_[name].datatype = datatype;
00984 int count = pcl::traits::datatype<T, U>::size;
00985 channels_[name].count = count;
00986 switch (datatype)
00987 {
00988 case sensor_msgs::PointField::INT8:
00989 case sensor_msgs::PointField::UINT8:
00990 {
00991 channels_[name].size = count;
00992 break;
00993 }
00994
00995 case sensor_msgs::PointField::INT16:
00996 case sensor_msgs::PointField::UINT16:
00997 {
00998 channels_[name].size = count * 2;
00999 break;
01000 }
01001
01002 case sensor_msgs::PointField::INT32:
01003 case sensor_msgs::PointField::UINT32:
01004 case sensor_msgs::PointField::FLOAT32:
01005 {
01006 channels_[name].size = count * 4;
01007 break;
01008 }
01009
01010 case sensor_msgs::PointField::FLOAT64:
01011 {
01012 channels_[name].size = count * 8;
01013 break;
01014 }
01015 }
01016 }
01017
01018 private:
01019 std::map<std::string, pcl::ChannelProperties> &channels_;
01020 };
01021 };
01022
01024 namespace detail
01025 {
01026 template <typename PointT> boost::shared_ptr<pcl::MsgFieldMap>&
01027 getMapping (pcl::PointCloud<PointT>& p)
01028 {
01029 return (p.mapping_);
01030 }
01031 }
01032
01033 template <typename PointT> std::ostream&
01034 operator << (std::ostream& s, const pcl::PointCloud<PointT> &p)
01035 {
01036 s << "points[]: " << p.points.size () << std::endl;
01037 s << "width: " << p.width << std::endl;
01038 s << "height: " << p.height << std::endl;
01039 s << "is_dense: " << p.is_dense << std::endl;
01040 return (s);
01041 }
01042 }
01043
01044 #endif //#ifndef PCL_POINT_CLOUD_H_