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_RIFT_H_
00041 #define PCL_RIFT_H_
00042 
00043 #include <pcl/features/feature.h>
00044 
00045 namespace pcl
00046 {
00058   template <typename PointInT, typename GradientT, typename PointOutT>
00059   class RIFTEstimation: public Feature<PointInT, PointOutT>
00060   {
00061     public:
00062       using Feature<PointInT, PointOutT>::feature_name_;
00063       using Feature<PointInT, PointOutT>::getClassName;
00064 
00065       using Feature<PointInT, PointOutT>::surface_;
00066       using Feature<PointInT, PointOutT>::indices_;
00067 
00068       using Feature<PointInT, PointOutT>::tree_;
00069       using Feature<PointInT, PointOutT>::search_radius_;
00070       
00071       typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00072       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00073 
00074       typedef typename pcl::PointCloud<GradientT> PointCloudGradient;
00075       typedef typename PointCloudGradient::Ptr PointCloudGradientPtr;
00076       typedef typename PointCloudGradient::ConstPtr PointCloudGradientConstPtr;
00077 
00078       typedef typename boost::shared_ptr<RIFTEstimation<PointInT, GradientT, PointOutT> > Ptr;
00079       typedef typename boost::shared_ptr<const RIFTEstimation<PointInT, GradientT, PointOutT> > ConstPtr;
00080 
00081 
00083       RIFTEstimation () : gradient_ (), nr_distance_bins_ (4), nr_gradient_bins_ (8)
00084       {
00085         feature_name_ = "RIFTEstimation";
00086       };
00087 
00091       inline void 
00092       setInputGradient (const PointCloudGradientConstPtr &gradient) { gradient_ = gradient; };
00093 
00095       inline PointCloudGradientConstPtr 
00096       getInputGradient () const { return (gradient_); };
00097 
00101       inline void 
00102       setNrDistanceBins (int nr_distance_bins) { nr_distance_bins_ = nr_distance_bins; };
00103 
00105       inline int 
00106       getNrDistanceBins () const { return (nr_distance_bins_); };
00107 
00111       inline void 
00112       setNrGradientBins (int nr_gradient_bins) { nr_gradient_bins_ = nr_gradient_bins; };
00113 
00115       inline int 
00116       getNrGradientBins () const { return (nr_gradient_bins_); };
00117 
00128       void 
00129       computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius,
00130                    const std::vector<int> &indices, const std::vector<float> &squared_distances, 
00131                    Eigen::MatrixXf &rift_descriptor);
00132 
00133     protected:
00134 
00140       void 
00141       computeFeature (PointCloudOut &output);
00142 
00144       PointCloudGradientConstPtr gradient_;
00145 
00147       int nr_distance_bins_;
00148 
00150       int nr_gradient_bins_;
00151 
00152     private:
00156       void 
00157       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf>&) {}
00158   };
00159 
00171   template <typename PointInT, typename GradientT>
00172   class RIFTEstimation<PointInT, GradientT, Eigen::MatrixXf>: public RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >
00173   {
00174     public:
00175       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::getClassName;
00176       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::surface_;
00177       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::indices_;
00178       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::tree_;
00179       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::search_radius_;
00180       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::gradient_;
00181       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::nr_gradient_bins_;
00182       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::nr_distance_bins_;
00183       using RIFTEstimation<PointInT, GradientT, pcl::Histogram<32> >::compute;
00184       
00185     private:
00191       void 
00192       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00193 
00197       void 
00198       compute (pcl::PointCloud<pcl::Normal>&) {}
00199   };
00200 }
00201 
00202 #endif // #ifndef PCL_RIFT_H_