point_cloud_color_handlers.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) 2012-, Open Perception, 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 the copyright holder(s) 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  */
00037 #ifndef PCL_POINT_CLOUD_COLOR_HANDLERS_H_
00038 #define PCL_POINT_CLOUD_COLOR_HANDLERS_H_
00039 
00040 #if defined __GNUC__
00041 #pragma GCC system_header
00042 #endif
00043 
00044 // PCL includes
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/common/io.h>
00047 #include <pcl/visualization/common/common.h>
00048 // VTK includes
00049 #include <vtkSmartPointer.h>
00050 #include <vtkDataArray.h>
00051 #include <vtkFloatArray.h>
00052 #include <vtkUnsignedCharArray.h>
00053 
00054 namespace pcl
00055 {
00056   namespace visualization
00057   {
00059 
00063     template <typename PointT>
00064     class PointCloudColorHandler
00065     {
00066       public:
00067         typedef pcl::PointCloud<PointT> PointCloud;
00068         typedef typename PointCloud::Ptr PointCloudPtr;
00069         typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00070 
00071         typedef boost::shared_ptr<PointCloudColorHandler<PointT> > Ptr;
00072         typedef boost::shared_ptr<const PointCloudColorHandler<PointT> > ConstPtr;
00073 
00075         PointCloudColorHandler () :
00076           cloud_ (), capable_ (false), field_idx_ (-1), fields_ ()
00077         {}
00078 
00080         PointCloudColorHandler (const PointCloudConstPtr &cloud) :
00081           cloud_ (cloud), capable_ (false), field_idx_ (-1), fields_ ()
00082         {}
00083 
00085         virtual ~PointCloudColorHandler () {}
00086 
00088         inline bool
00089         isCapable () const { return (capable_); }
00090 
00092         virtual std::string
00093         getName () const = 0;
00094 
00096         virtual std::string
00097         getFieldName () const = 0;
00098 
00104         virtual bool
00105         getColor (vtkSmartPointer<vtkDataArray> &scalars) const = 0;
00106 
00110         virtual void
00111         setInputCloud (const PointCloudConstPtr &cloud)
00112         {
00113           cloud_ = cloud;
00114         }
00115 
00116       protected:
00118         PointCloudConstPtr cloud_;
00119 
00123         bool capable_;
00124 
00126         int field_idx_;
00127 
00129         std::vector<pcl::PCLPointField> fields_;
00130     };
00131 
00133 
00137     template <typename PointT>
00138     class PointCloudColorHandlerRandom : public PointCloudColorHandler<PointT>
00139     {
00140       typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud;
00141       typedef typename PointCloud::Ptr PointCloudPtr;
00142       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00143 
00144       public:
00145         typedef boost::shared_ptr<PointCloudColorHandlerRandom<PointT> > Ptr;
00146         typedef boost::shared_ptr<const PointCloudColorHandlerRandom<PointT> > ConstPtr;
00147 
00149         PointCloudColorHandlerRandom () :
00150           PointCloudColorHandler<PointT> ()
00151         {
00152           capable_ = true;
00153         }
00154 
00156         PointCloudColorHandlerRandom (const PointCloudConstPtr &cloud) :
00157           PointCloudColorHandler<PointT> (cloud)
00158         {
00159           capable_ = true;
00160         }
00161 
00163         virtual std::string
00164         getName () const { return ("PointCloudColorHandlerRandom"); }
00165 
00167         virtual std::string
00168         getFieldName () const { return ("[random]"); }
00169 
00175         virtual bool
00176         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00177 
00178       protected:
00179         // Members derived from the base class
00180         using PointCloudColorHandler<PointT>::cloud_;
00181         using PointCloudColorHandler<PointT>::capable_;
00182     };
00183 
00185 
00190     template <typename PointT>
00191     class PointCloudColorHandlerCustom : public PointCloudColorHandler<PointT>
00192     {
00193       typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud;
00194       typedef typename PointCloud::Ptr PointCloudPtr;
00195       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00196 
00197       public:
00198         typedef boost::shared_ptr<PointCloudColorHandlerCustom<PointT> > Ptr;
00199         typedef boost::shared_ptr<const PointCloudColorHandlerCustom<PointT> > ConstPtr;
00200 
00202         PointCloudColorHandlerCustom (double r, double g, double b)
00203           : PointCloudColorHandler<PointT> ()
00204           , r_ (r)
00205           , g_ (g)
00206           , b_ (b)
00207         {
00208           capable_ = true;
00209         }
00210 
00212         PointCloudColorHandlerCustom (const PointCloudConstPtr &cloud,
00213                                       double r, double g, double b)
00214           : PointCloudColorHandler<PointT> (cloud)
00215           , r_ (r)
00216           , g_ (g)
00217           , b_ (b)
00218         {
00219           capable_ = true;
00220         }
00221 
00223         virtual ~PointCloudColorHandlerCustom () {};
00224 
00226         virtual std::string
00227         getName () const { return ("PointCloudColorHandlerCustom"); }
00228 
00230         virtual std::string
00231         getFieldName () const { return (""); }
00232 
00238         virtual bool
00239         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00240 
00241       protected:
00242         // Members derived from the base class
00243         using PointCloudColorHandler<PointT>::cloud_;
00244         using PointCloudColorHandler<PointT>::capable_;
00245 
00247         double r_, g_, b_;
00248     };
00249 
00251 
00256     template <typename PointT>
00257     class PointCloudColorHandlerRGBField : public PointCloudColorHandler<PointT>
00258     {
00259       typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud;
00260       typedef typename PointCloud::Ptr PointCloudPtr;
00261       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00262 
00263       public:
00264         typedef boost::shared_ptr<PointCloudColorHandlerRGBField<PointT> > Ptr;
00265         typedef boost::shared_ptr<const PointCloudColorHandlerRGBField<PointT> > ConstPtr;
00266 
00268         PointCloudColorHandlerRGBField ()
00269         {
00270           capable_ = false;
00271         }
00272 
00274         PointCloudColorHandlerRGBField (const PointCloudConstPtr &cloud)
00275           : PointCloudColorHandler<PointT> (cloud)
00276         {
00277           setInputCloud (cloud);
00278         }
00279 
00281         virtual ~PointCloudColorHandlerRGBField () {}
00282 
00284         virtual std::string
00285         getFieldName () const { return ("rgb"); }
00286 
00292         virtual bool
00293         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00294 
00298         virtual void
00299         setInputCloud (const PointCloudConstPtr &cloud);
00300 
00301       protected:
00303         virtual std::string
00304         getName () const { return ("PointCloudColorHandlerRGBField"); }
00305 
00306       private:
00307         // Members derived from the base class
00308         using PointCloudColorHandler<PointT>::cloud_;
00309         using PointCloudColorHandler<PointT>::capable_;
00310         using PointCloudColorHandler<PointT>::field_idx_;
00311         using PointCloudColorHandler<PointT>::fields_;
00312     };
00313 
00315 
00319     template <typename PointT>
00320     class PointCloudColorHandlerHSVField : public PointCloudColorHandler<PointT>
00321     {
00322       typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud;
00323       typedef typename PointCloud::Ptr PointCloudPtr;
00324       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00325 
00326       public:
00327         typedef boost::shared_ptr<PointCloudColorHandlerHSVField<PointT> > Ptr;
00328         typedef boost::shared_ptr<const PointCloudColorHandlerHSVField<PointT> > ConstPtr;
00329 
00331         PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud);
00332       
00334         virtual ~PointCloudColorHandlerHSVField () {}
00335 
00337         virtual std::string
00338         getFieldName () const { return ("hsv"); }
00339 
00345         virtual bool
00346         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00347 
00348       protected:
00350         virtual std::string
00351         getName () const { return ("PointCloudColorHandlerHSVField"); }
00352 
00354         int s_field_idx_;
00355 
00357         int v_field_idx_;
00358       private:
00359         // Members derived from the base class
00360         using PointCloudColorHandler<PointT>::cloud_;
00361         using PointCloudColorHandler<PointT>::capable_;
00362         using PointCloudColorHandler<PointT>::field_idx_;
00363         using PointCloudColorHandler<PointT>::fields_;
00364     };
00365 
00367 
00372     template <typename PointT>
00373     class PointCloudColorHandlerGenericField : public PointCloudColorHandler<PointT>
00374     {
00375       typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud;
00376       typedef typename PointCloud::Ptr PointCloudPtr;
00377       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00378 
00379       public:
00380         typedef boost::shared_ptr<PointCloudColorHandlerGenericField<PointT> > Ptr;
00381         typedef boost::shared_ptr<const PointCloudColorHandlerGenericField<PointT> > ConstPtr;
00382 
00384         PointCloudColorHandlerGenericField (const std::string &field_name)
00385           : field_name_ (field_name)
00386         {
00387           capable_ = false;
00388         }
00389 
00391         PointCloudColorHandlerGenericField (const PointCloudConstPtr &cloud,
00392                                             const std::string &field_name)
00393           : PointCloudColorHandler<PointT> (cloud)
00394           , field_name_ (field_name)
00395         {
00396           setInputCloud (cloud);
00397         }
00398 
00400         virtual ~PointCloudColorHandlerGenericField () {}
00401 
00403         virtual std::string getFieldName () const { return (field_name_); }
00404 
00410         virtual bool
00411         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00412 
00416         virtual void
00417         setInputCloud (const PointCloudConstPtr &cloud);
00418 
00419       protected:
00421         virtual std::string
00422         getName () const { return ("PointCloudColorHandlerGenericField"); }
00423 
00424       private:
00425         using PointCloudColorHandler<PointT>::cloud_;
00426         using PointCloudColorHandler<PointT>::capable_;
00427         using PointCloudColorHandler<PointT>::field_idx_;
00428         using PointCloudColorHandler<PointT>::fields_;
00429 
00431         std::string field_name_;
00432     };
00433 
00435 
00439     template <>
00440     class PCL_EXPORTS PointCloudColorHandler<pcl::PCLPointCloud2>
00441     {
00442       public:
00443         typedef pcl::PCLPointCloud2 PointCloud;
00444         typedef PointCloud::Ptr PointCloudPtr;
00445         typedef PointCloud::ConstPtr PointCloudConstPtr;
00446 
00447         typedef boost::shared_ptr<PointCloudColorHandler<PointCloud> > Ptr;
00448         typedef boost::shared_ptr<const PointCloudColorHandler<PointCloud> > ConstPtr;
00449 
00451         PointCloudColorHandler (const PointCloudConstPtr &cloud) :
00452           cloud_ (cloud), capable_ (false), field_idx_ ()
00453         {}
00454         
00456         virtual ~PointCloudColorHandler () {}
00457 
00459         inline bool
00460         isCapable () const { return (capable_); }
00461 
00463         virtual std::string
00464         getName () const = 0;
00465 
00467         virtual std::string
00468         getFieldName () const = 0;
00469 
00475         virtual bool
00476         getColor (vtkSmartPointer<vtkDataArray> &scalars) const = 0;
00477 
00481         void
00482         setInputCloud (const PointCloudConstPtr &cloud)
00483         {
00484           cloud_ = cloud;
00485         }
00486 
00487      protected:
00489         PointCloudConstPtr cloud_;
00490 
00494         bool capable_;
00495 
00497         int field_idx_;
00498     };
00499 
00501 
00505     template <>
00506     class PCL_EXPORTS PointCloudColorHandlerRandom<pcl::PCLPointCloud2> : public PointCloudColorHandler<pcl::PCLPointCloud2>
00507     {
00508       typedef PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00509       typedef PointCloud::Ptr PointCloudPtr;
00510       typedef PointCloud::ConstPtr PointCloudConstPtr;
00511 
00512       public:
00513         typedef boost::shared_ptr<PointCloudColorHandlerRandom<PointCloud> > Ptr;
00514         typedef boost::shared_ptr<const PointCloudColorHandlerRandom<PointCloud> > ConstPtr;
00515 
00517         PointCloudColorHandlerRandom (const PointCloudConstPtr &cloud) :
00518           PointCloudColorHandler<pcl::PCLPointCloud2> (cloud)
00519         {
00520           capable_ = true;
00521         }
00522       
00524         virtual ~PointCloudColorHandlerRandom () {}
00525 
00527         virtual std::string
00528         getName () const { return ("PointCloudColorHandlerRandom"); }
00529 
00531         virtual std::string
00532         getFieldName () const { return ("[random]"); }
00533 
00539         virtual bool
00540         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00541     };
00542 
00544 
00549     template <>
00550     class PCL_EXPORTS PointCloudColorHandlerCustom<pcl::PCLPointCloud2> : public PointCloudColorHandler<pcl::PCLPointCloud2>
00551     {
00552       typedef PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00553       typedef PointCloud::Ptr PointCloudPtr;
00554       typedef PointCloud::ConstPtr PointCloudConstPtr;
00555 
00556       public:
00558         PointCloudColorHandlerCustom (const PointCloudConstPtr &cloud,
00559                                       double r, double g, double b) :
00560           PointCloudColorHandler<pcl::PCLPointCloud2> (cloud),
00561           r_ (r), g_ (g), b_ (b)
00562         {
00563           capable_ = true;
00564         }
00565       
00567         virtual ~PointCloudColorHandlerCustom () {}
00568 
00570         virtual std::string
00571         getName () const { return ("PointCloudColorHandlerCustom"); }
00572 
00574         virtual std::string
00575         getFieldName () const { return (""); }
00576 
00582         virtual bool
00583         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00584 
00585       protected:
00587         double r_, g_, b_;
00588     };
00589 
00591 
00596     template <>
00597     class PCL_EXPORTS PointCloudColorHandlerRGBField<pcl::PCLPointCloud2> : public PointCloudColorHandler<pcl::PCLPointCloud2>
00598     {
00599       typedef PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00600       typedef PointCloud::Ptr PointCloudPtr;
00601       typedef PointCloud::ConstPtr PointCloudConstPtr;
00602 
00603       public:
00604         typedef boost::shared_ptr<PointCloudColorHandlerRGBField<PointCloud> > Ptr;
00605         typedef boost::shared_ptr<const PointCloudColorHandlerRGBField<PointCloud> > ConstPtr;
00606 
00608         PointCloudColorHandlerRGBField (const PointCloudConstPtr &cloud);
00609       
00611         virtual ~PointCloudColorHandlerRGBField () {}
00612 
00618         virtual bool
00619         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00620 
00621       protected:
00623         virtual std::string
00624         getName () const { return ("PointCloudColorHandlerRGBField"); }
00625 
00627         virtual std::string
00628         getFieldName () const { return ("rgb"); }
00629     };
00630 
00632 
00636     template <>
00637     class PCL_EXPORTS PointCloudColorHandlerHSVField<pcl::PCLPointCloud2> : public PointCloudColorHandler<pcl::PCLPointCloud2>
00638     {
00639       typedef PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00640       typedef PointCloud::Ptr PointCloudPtr;
00641       typedef PointCloud::ConstPtr PointCloudConstPtr;
00642 
00643       public:
00644         typedef boost::shared_ptr<PointCloudColorHandlerHSVField<PointCloud> > Ptr;
00645         typedef boost::shared_ptr<const PointCloudColorHandlerHSVField<PointCloud> > ConstPtr;
00646 
00648         PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud);
00649       
00651         virtual ~PointCloudColorHandlerHSVField () {}
00652 
00658         virtual bool
00659         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00660 
00661       protected:
00663         virtual std::string
00664         getName () const { return ("PointCloudColorHandlerHSVField"); }
00665 
00667         virtual std::string
00668         getFieldName () const { return ("hsv"); }
00669 
00671         int s_field_idx_;
00672 
00674         int v_field_idx_;
00675      };
00676 
00678 
00683     template <>
00684     class PCL_EXPORTS PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> : public PointCloudColorHandler<pcl::PCLPointCloud2>
00685     {
00686       typedef PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00687       typedef PointCloud::Ptr PointCloudPtr;
00688       typedef PointCloud::ConstPtr PointCloudConstPtr;
00689 
00690       public:
00691         typedef boost::shared_ptr<PointCloudColorHandlerGenericField<PointCloud> > Ptr;
00692         typedef boost::shared_ptr<const PointCloudColorHandlerGenericField<PointCloud> > ConstPtr;
00693 
00695         PointCloudColorHandlerGenericField (const PointCloudConstPtr &cloud,
00696                                             const std::string &field_name);
00697       
00699         virtual ~PointCloudColorHandlerGenericField () {}
00700 
00706         virtual bool
00707         getColor (vtkSmartPointer<vtkDataArray> &scalars) const;
00708 
00709       protected:
00711         virtual std::string
00712         getName () const { return ("PointCloudColorHandlerGenericField"); }
00713 
00715         virtual std::string
00716         getFieldName () const { return (field_name_); }
00717 
00718       private:
00720         std::string field_name_;
00721     };
00722   }
00723 }
00724 
00725 #include <pcl/visualization/impl/point_cloud_color_handlers.hpp>
00726 
00727 #endif      // PCL_POINT_CLOUD_COLOR_HANDLERS_H_
00728 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:29:51