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 
00041 #ifndef PCL_RIFT_H_
00042 #define PCL_RIFT_H_
00043 
00044 #include <pcl/features/feature.h>
00045 
00046 namespace pcl
00047 {
00059   template <typename PointInT, typename GradientT, typename PointOutT>
00060   class RIFTEstimation: public Feature<PointInT, PointOutT>
00061   {
00062     public:
00063       using Feature<PointInT, PointOutT>::feature_name_;
00064       using Feature<PointInT, PointOutT>::getClassName;
00065 
00066       using Feature<PointInT, PointOutT>::surface_;
00067       using Feature<PointInT, PointOutT>::indices_;
00068 
00069       using Feature<PointInT, PointOutT>::tree_;
00070       using Feature<PointInT, PointOutT>::search_radius_;
00071       
00072       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00073       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00074 
00075       typedef typename pcl::PointCloud<GradientT> PointCloudGradient;
00076       typedef typename PointCloudGradient::Ptr PointCloudGradientPtr;
00077       typedef typename PointCloudGradient::ConstPtr PointCloudGradientConstPtr;
00078 
00079       typedef typename boost::shared_ptr<RIFTEstimation<PointInT, GradientT, PointOutT> > Ptr;
00080       typedef typename boost::shared_ptr<const RIFTEstimation<PointInT, GradientT, PointOutT> > ConstPtr;
00081 
00082 
00084       RIFTEstimation () : gradient_ (), nr_distance_bins_ (4), nr_gradient_bins_ (8)
00085       {
00086         feature_name_ = "RIFTEstimation";
00087       };
00088 
00092       inline void 
00093       setInputGradient (const PointCloudGradientConstPtr &gradient) { gradient_ = gradient; };
00094 
00096       inline PointCloudGradientConstPtr 
00097       getInputGradient () const { return (gradient_); };
00098 
00102       inline void 
00103       setNrDistanceBins (int nr_distance_bins) { nr_distance_bins_ = nr_distance_bins; };
00104 
00106       inline int 
00107       getNrDistanceBins () const { return (nr_distance_bins_); };
00108 
00112       inline void 
00113       setNrGradientBins (int nr_gradient_bins) { nr_gradient_bins_ = nr_gradient_bins; };
00114 
00116       inline int 
00117       getNrGradientBins () const { return (nr_gradient_bins_); };
00118 
00129       void 
00130       computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius,
00131                    const std::vector<int> &indices, const std::vector<float> &squared_distances, 
00132                    Eigen::MatrixXf &rift_descriptor);
00133 
00134     protected:
00135 
00141       void 
00142       computeFeature (PointCloudOut &output);
00143 
00145       PointCloudGradientConstPtr gradient_;
00146 
00148       int nr_distance_bins_;
00149 
00151       int nr_gradient_bins_;
00152   };
00153 }
00154 
00155 #ifdef PCL_NO_PRECOMPILE
00156 #include <pcl/features/impl/rift.hpp>
00157 #endif
00158 
00159 #endif // #ifndef PCL_RIFT_H_