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_INTENSITY_SPIN_H_
00041 #define PCL_INTENSITY_SPIN_H_
00042 
00043 #include <pcl/features/feature.h>
00044 
00045 namespace pcl
00046 {
00057   template <typename PointInT, typename PointOutT>
00058   class IntensitySpinEstimation: public Feature<PointInT, PointOutT>
00059   {
00060     public:
00061       typedef boost::shared_ptr<IntensitySpinEstimation<PointInT, PointOutT> > Ptr;
00062       typedef boost::shared_ptr<const IntensitySpinEstimation<PointInT, PointOutT> > ConstPtr;
00063       using Feature<PointInT, PointOutT>::feature_name_;
00064       using Feature<PointInT, PointOutT>::getClassName;
00065 
00066       using Feature<PointInT, PointOutT>::input_;
00067       using Feature<PointInT, PointOutT>::indices_;
00068       using Feature<PointInT, PointOutT>::surface_;
00069 
00070       using Feature<PointInT, PointOutT>::tree_;
00071       using Feature<PointInT, PointOutT>::search_radius_;
00072       
00073       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00074       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00075 
00077       IntensitySpinEstimation () : nr_distance_bins_ (4), nr_intensity_bins_ (5), sigma_ (1.0)
00078       {
00079         feature_name_ = "IntensitySpinEstimation";
00080       };
00081 
00092       void 
00093       computeIntensitySpinImage (const PointCloudIn &cloud, 
00094                                  float radius, float sigma, int k, 
00095                                  const std::vector<int> &indices, 
00096                                  const std::vector<float> &squared_distances, 
00097                                  Eigen::MatrixXf &intensity_spin_image);
00098 
00102       inline void 
00103       setNrDistanceBins (size_t nr_distance_bins) { nr_distance_bins_ = static_cast<int> (nr_distance_bins); };
00104 
00106       inline int 
00107       getNrDistanceBins () { return (nr_distance_bins_); };
00108 
00112       inline void 
00113       setNrIntensityBins (size_t nr_intensity_bins) { nr_intensity_bins_ = static_cast<int> (nr_intensity_bins); };
00114 
00116       inline int 
00117       getNrIntensityBins () { return (nr_intensity_bins_); };
00118 
00122       inline void 
00123       setSmoothingBandwith (float sigma) { sigma_ = sigma; };
00124 
00126       inline float 
00127       getSmoothingBandwith () { return (sigma_); };
00128 
00129 
00134       void 
00135       computeFeature (PointCloudOut &output);
00136     
00138       int nr_distance_bins_;
00139 
00141       int nr_intensity_bins_;
00142 
00144       float sigma_;
00145   };
00146 }
00147 
00148 #ifdef PCL_NO_PRECOMPILE
00149 #include <pcl/features/impl/intensity_spin.hpp>
00150 #endif
00151 
00152 #endif // #ifndef PCL_INTENSITY_SPIN_H_