Go to the documentation of this file.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_ESF_H_
00041 #define PCL_ESF_H_
00042 
00043 #include <pcl/features/feature.h>
00044 #define GRIDSIZE 64
00045 #define GRIDSIZE_H GRIDSIZE/2
00046 #include <vector>
00047 
00048 namespace pcl
00049 {
00058   template <typename PointInT,  typename PointOutT = pcl::ESFSignature640>
00059   class ESFEstimation: public Feature<PointInT, PointOutT>
00060   {
00061     public:
00062       typedef boost::shared_ptr<ESFEstimation<PointInT, PointOutT> > Ptr;
00063       typedef boost::shared_ptr<const ESFEstimation<PointInT, PointOutT> > ConstPtr;
00064 
00065       using Feature<PointInT, PointOutT>::feature_name_;
00066       using Feature<PointInT, PointOutT>::getClassName;
00067       using Feature<PointInT, PointOutT>::indices_;
00068       using Feature<PointInT, PointOutT>::k_;
00069       using Feature<PointInT, PointOutT>::search_radius_;
00070       using Feature<PointInT, PointOutT>::input_;
00071       using Feature<PointInT, PointOutT>::surface_;
00072 
00073       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00074       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00075 
00077       ESFEstimation () : lut_ (), local_cloud_ ()
00078       {
00079         feature_name_ = "ESFEstimation";
00080         lut_.resize (GRIDSIZE);
00081         for (int i = 0; i < GRIDSIZE; ++i)
00082         {
00083           lut_[i].resize (GRIDSIZE);
00084           for (int j = 0; j < GRIDSIZE; ++j)
00085             lut_[i][j].resize (GRIDSIZE);
00086         }
00087         
00088         search_radius_ = 0;
00089         k_ = 5;
00090       }
00091 
00095       void
00096       compute (PointCloudOut &output);
00097 
00098     protected:
00099 
00104       void 
00105       computeFeature (PointCloudOut &output);
00106 
00108       int
00109       lci (const int x1, const int y1, const int z1, 
00110            const int x2, const int y2, const int z2, 
00111            float &ratio, int &incnt, int &pointcount);
00112      
00114       void
00115       computeESF (PointCloudIn &pc, std::vector<float> &hist);
00116       
00118       void
00119       voxelize9 (PointCloudIn &cluster);
00120       
00122       void
00123       cleanup9 (PointCloudIn &cluster);
00124 
00126       void
00127       scale_points_unit_sphere (const pcl::PointCloud<PointInT> &pc, float scalefactor, Eigen::Vector4f& centroid);
00128 
00129     private:
00130 
00132       std::vector<std::vector<std::vector<int> > > lut_;
00133       
00135       PointCloudIn local_cloud_;
00136   };
00137 }
00138 
00139 #ifdef PCL_NO_PRECOMPILE
00140 #include <pcl/features/impl/esf.hpp>
00141 #endif
00142 
00143 #endif // #