Point Cloud Library (PCL)  1.4.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
point_representation.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: point_representation.h 3746 2011-12-31 22:19:47Z rusu $
00037  *
00038  */
00039 #ifndef PCL_POINT_REPRESENTATION_H_
00040 #define PCL_POINT_REPRESENTATION_H_
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/pcl_macros.h>
00044 #include <pcl/for_each_type.h>
00045 
00046 namespace pcl
00047 {
00054   template <typename PointT> 
00055   class PointRepresentation
00056   {
00057     protected:
00059       int nr_dimensions_;
00061       std::vector<float> alpha_;
00071       bool trivial_;
00072       
00073     public:
00074       typedef boost::shared_ptr<PointRepresentation<PointT> > Ptr;
00075       typedef boost::shared_ptr<const PointRepresentation<PointT> > ConstPtr;
00076 
00078       PointRepresentation () : nr_dimensions_ (0), alpha_ (0), trivial_ (false) {}
00079       
00084       virtual void copyToFloatArray (const PointT &p, float *out) const = 0;
00085 
00093       inline bool isTrivial() const { return trivial_ && alpha_.empty (); }
00094       
00098       virtual bool 
00099       isValid (const PointT &p) const
00100       {
00101         bool is_valid = true;
00102 
00103         if (trivial_)
00104         {
00105           const float* temp = reinterpret_cast<const float*>(&p);
00106 
00107           for (int i = 0; i < nr_dimensions_; ++i)
00108           {
00109             if (!pcl_isfinite (temp[i]))
00110             {
00111               is_valid = false;
00112               break;
00113             }
00114           }
00115         }
00116         else
00117         {
00118           float *temp = new float[nr_dimensions_];
00119           copyToFloatArray (p, temp);
00120 
00121           for (int i = 0; i < nr_dimensions_; ++i)
00122           {
00123             if (!pcl_isfinite (temp[i]))
00124             {
00125               is_valid = false;
00126               break;
00127             }
00128           }
00129           delete [] temp;
00130         }
00131         return (is_valid);
00132       }
00133       
00138       template <typename OutputType> void
00139       vectorize (const PointT &p, OutputType &out) const
00140       {
00141         float *temp = new float[nr_dimensions_];
00142         copyToFloatArray (p, temp);
00143         if (alpha_.empty ())
00144         {
00145           for (int i = 0; i < nr_dimensions_; ++i)
00146             out[i] = temp[i];
00147         }
00148         else
00149         {
00150           for (int i = 0; i < nr_dimensions_; ++i)
00151             out[i] = temp[i] * alpha_[i];
00152         }
00153         delete [] temp;
00154       }
00155       
00159       void 
00160       setRescaleValues (const float *rescale_array)
00161       {
00162         alpha_.resize (nr_dimensions_);
00163         for (int i = 0; i < nr_dimensions_; ++i)
00164           alpha_[i] = rescale_array[i];
00165       }
00166       
00168       inline int getNumberOfDimensions () const { return (nr_dimensions_); }
00169   };
00170 
00172 
00174   template <typename PointDefault>
00175   class DefaultPointRepresentation : public PointRepresentation <PointDefault>
00176   {
00177     using PointRepresentation <PointDefault>::nr_dimensions_;
00178     using PointRepresentation <PointDefault>::trivial_;
00179 
00180     public:
00181       // Boost shared pointers
00182       typedef boost::shared_ptr<DefaultPointRepresentation<PointDefault> > Ptr;
00183       typedef boost::shared_ptr<const DefaultPointRepresentation<PointDefault> > ConstPtr;
00184 
00185       DefaultPointRepresentation ()
00186       {
00187         // If point type is unknown, assume it's a struct/array of floats, and compute the number of dimensions
00188         nr_dimensions_ = sizeof (PointDefault) / sizeof (float);
00189         // Limit the default representation to the first 3 elements
00190         if (nr_dimensions_ > 3) nr_dimensions_ = 3;
00191 
00192         trivial_ = true;
00193       }
00194 
00195       inline Ptr 
00196       makeShared () const 
00197       { 
00198         return (Ptr (new DefaultPointRepresentation<PointDefault> (*this)));
00199       }
00200 
00201       virtual void 
00202       copyToFloatArray (const PointDefault &p, float * out) const
00203       {
00204         // If point type is unknown, treat it as a struct/array of floats
00205         const float * ptr = (float *)&p;
00206         for (int i = 0; i < nr_dimensions_; ++i)
00207           out[i] = ptr[i];
00208       }
00209   };
00210 
00212 
00215   template <typename PointDefault>
00216   class DefaultFeatureRepresentation : public PointRepresentation <PointDefault>
00217   {
00218     protected:
00219       using PointRepresentation <PointDefault>::nr_dimensions_;
00220 
00221     private:
00222       struct IncrementFunctor
00223       {
00224         IncrementFunctor (int &n) : n_ (n)
00225         {
00226           n_ = 0;
00227         }
00228         
00229         template<typename Key> inline void operator () ()
00230         {
00231           n_ += pcl::traits::datatype<PointDefault, Key>::size;
00232         }
00233         
00234       private:
00235         int &n_;
00236       };
00237 
00238     struct NdCopyPointFunctor
00239     {
00240       typedef typename traits::POD<PointDefault>::type Pod;
00241       
00242       NdCopyPointFunctor (const PointDefault &p1, float * p2)
00243         : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
00244       
00245       template<typename Key> inline void operator() ()
00246       {  
00247         typedef typename pcl::traits::datatype<PointDefault, Key>::type FieldT;
00248         const int NrDims = pcl::traits::datatype<PointDefault, Key>::size;
00249         Helper<Key, FieldT, NrDims>::copyPoint (p1_, p2_, f_idx_);
00250       }
00251       
00252       // Copy helper for scalar fields
00253       template <typename Key, typename FieldT, int NrDims>
00254       struct Helper
00255       {
00256         static void copyPoint (const Pod &p1, float * p2, int &f_idx) 
00257         {
00258           const uint8_t * data_ptr = reinterpret_cast<const uint8_t *> (&p1) + 
00259             pcl::traits::offset<PointDefault, Key>::value;
00260           p2[f_idx++] = *reinterpret_cast<const FieldT*> (data_ptr);
00261         }
00262       };
00263       // Copy helper for array fields
00264       template <typename Key, typename FieldT, int NrDims>
00265       struct Helper<Key, FieldT[NrDims], NrDims>
00266       {
00267         static void copyPoint (const Pod &p1, float * p2, int &f_idx)
00268         {
00269           const uint8_t * data_ptr = reinterpret_cast<const uint8_t *> (&p1) + 
00270             pcl::traits::offset<PointDefault, Key>::value;
00271           int nr_dims = NrDims;
00272           const FieldT * array = reinterpret_cast<const FieldT *> (data_ptr);
00273           for (int i = 0; i < nr_dims; ++i)
00274           {
00275             p2[f_idx++] = array[i];
00276           }
00277         }
00278       };
00279   
00280     private:
00281       const Pod &p1_;
00282       float * p2_;
00283       int f_idx_;
00284     };
00285 
00286     public:
00287       // Boost shared pointers
00288       typedef typename boost::shared_ptr<DefaultFeatureRepresentation<PointDefault> > Ptr;
00289       typedef typename boost::shared_ptr<const DefaultFeatureRepresentation<PointDefault> > ConstPtr;
00290       typedef typename pcl::traits::fieldList<PointDefault>::type FieldList;
00291 
00292       DefaultFeatureRepresentation ()
00293       {      
00294         nr_dimensions_ = 0; // zero-out the nr_dimensions_ before it gets incremented
00295         pcl::for_each_type <FieldList> (IncrementFunctor (nr_dimensions_));
00296       }
00297 
00298       inline Ptr 
00299       makeShared () const 
00300       { 
00301         return (Ptr (new DefaultFeatureRepresentation<PointDefault> (*this)));
00302       }
00303 
00304       virtual void 
00305       copyToFloatArray (const PointDefault &p, float * out) const
00306       {
00307         pcl::for_each_type <FieldList> (NdCopyPointFunctor (p, out));
00308       }
00309   };
00310 
00312   template <>
00313   class DefaultPointRepresentation <PointXYZ> : public  PointRepresentation <PointXYZ>
00314   {
00315     public:
00316       DefaultPointRepresentation ()
00317       {
00318         nr_dimensions_ = 3;
00319         trivial_ = true;
00320       }
00321 
00322       virtual void 
00323       copyToFloatArray (const PointXYZ &p, float * out) const
00324       {
00325         out[0] = p.x;
00326         out[1] = p.y;
00327         out[2] = p.z;
00328       }
00329   };
00330 
00332   template <>
00333   class DefaultPointRepresentation <PointXYZI> : public  PointRepresentation <PointXYZI>
00334   {
00335     public:
00336       DefaultPointRepresentation ()
00337       {
00338         nr_dimensions_ = 3;
00339         trivial_ = true;
00340       }
00341 
00342       virtual void 
00343       copyToFloatArray (const PointXYZI &p, float * out) const
00344       {
00345         out[0] = p.x;
00346         out[1] = p.y;
00347         out[2] = p.z;
00348         // By default, p.intensity is not part of the PointXYZI vectorization
00349       }
00350   };
00351 
00353   template <>
00354   class DefaultPointRepresentation <PointNormal> : public  PointRepresentation <PointNormal>
00355   {
00356     public:
00357       DefaultPointRepresentation ()
00358       {
00359         nr_dimensions_ = 3;
00360         trivial_ = true;
00361       }
00362 
00363       virtual void 
00364       copyToFloatArray (const PointNormal &p, float * out) const
00365       {
00366         out[0] = p.x;
00367         out[1] = p.y;
00368         out[2] = p.z;
00369       }
00370   };
00371 
00373   template <>
00374   class DefaultPointRepresentation <PFHSignature125> : public DefaultFeatureRepresentation <PFHSignature125>
00375   {};
00376 
00378   template <>
00379   class DefaultPointRepresentation <PFHRGBSignature250> : public DefaultFeatureRepresentation <PFHRGBSignature250>
00380   {};
00381 
00383   template <>
00384   class DefaultPointRepresentation <PPFSignature> : public DefaultFeatureRepresentation <PPFSignature>
00385   {
00386     public:
00387       DefaultPointRepresentation ()
00388       {
00389         nr_dimensions_ = 4;
00390         trivial_ = true;
00391       }
00392 
00393       virtual void
00394       copyToFloatArray (const PPFSignature &p, float * out) const
00395       {
00396         out[0] = p.f1;
00397         out[1] = p.f2;
00398         out[2] = p.f3;
00399         out[3] = p.f4;
00400       }
00401   };
00402 
00404   template <>
00405   class DefaultPointRepresentation <FPFHSignature33> : public DefaultFeatureRepresentation <FPFHSignature33>
00406   {};
00407 
00409   template <>
00410   class DefaultPointRepresentation <VFHSignature308> : public DefaultFeatureRepresentation <VFHSignature308>
00411   {};
00412 
00414   template <>
00415   class DefaultPointRepresentation <NormalBasedSignature12> : 
00416     public DefaultFeatureRepresentation <NormalBasedSignature12>
00417   {};
00418 
00420   template <>
00421   class DefaultPointRepresentation<SHOT> : public PointRepresentation<SHOT>
00422   {
00423     public:
00424       DefaultPointRepresentation ()
00425       {
00426         nr_dimensions_ = 352;
00427       }
00428 
00429       virtual void
00430       copyToFloatArray (const SHOT &p, float * out) const
00431       {
00432         for (int i = 0; i < nr_dimensions_; ++i)
00433           out[i] = p.descriptor[i];
00434       }
00435   };
00436 
00437 
00439 
00441   template <typename PointDefault>
00442   class CustomPointRepresentation : public PointRepresentation <PointDefault>
00443   {
00444     using PointRepresentation <PointDefault>::nr_dimensions_;
00445 
00446     public:
00447       // Boost shared pointers
00448       typedef boost::shared_ptr<CustomPointRepresentation<PointDefault> > Ptr;
00449       typedef boost::shared_ptr<const CustomPointRepresentation<PointDefault> > ConstPtr;
00450 
00455       CustomPointRepresentation (const int max_dim = 3, const int start_dim = 0) 
00456         : max_dim_(max_dim), start_dim_(start_dim)
00457       {
00458         // If point type is unknown, assume it's a struct/array of floats, and compute the number of dimensions
00459         nr_dimensions_ = sizeof (PointDefault) / sizeof (float) - start_dim_;
00460         // Limit the default representation to the first 3 elements
00461         if (nr_dimensions_ > max_dim_) 
00462           nr_dimensions_ = max_dim_;
00463       }
00464 
00465       inline Ptr 
00466       makeShared () const 
00467       { 
00468         return Ptr (new CustomPointRepresentation<PointDefault> (*this)); 
00469       }
00470 
00475       virtual void
00476       copyToFloatArray (const PointDefault &p, float *out) const
00477       {
00478         // If point type is unknown, treat it as a struct/array of floats
00479         const float *ptr = ((float*)&p) + start_dim_;
00480         for (int i = 0; i < nr_dimensions_; ++i)
00481           out[i] = ptr[i];
00482       }
00483 
00484     protected:
00486       int max_dim_;
00488       int start_dim_;
00489   };
00490 }
00491 
00492 #endif // #ifndef PCL_POINT_REPRESENTATION_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines