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 #ifndef PCL_RIFT_H_
00039 #define PCL_RIFT_H_
00040
00041 #include "pcl/features/feature.h"
00042
00043 namespace pcl
00044 {
00046
00055 template <typename PointInT, typename GradientT, typename PointOutT>
00056 class RIFTEstimation: public Feature<PointInT, PointOutT>
00057 {
00058 public:
00059 using Feature<PointInT, PointOutT>::feature_name_;
00060 using Feature<PointInT, PointOutT>::getClassName;
00061
00062 using Feature<PointInT, PointOutT>::surface_;
00063 using Feature<PointInT, PointOutT>::indices_;
00064
00065 using Feature<PointInT, PointOutT>::tree_;
00066 using Feature<PointInT, PointOutT>::search_radius_;
00067
00068 typedef typename pcl::PointCloud<PointInT> PointCloudIn;
00069 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00070
00071 typedef typename pcl::PointCloud<GradientT> PointCloudGradient;
00072 typedef typename PointCloudGradient::Ptr PointCloudGradientPtr;
00073 typedef typename PointCloudGradient::ConstPtr PointCloudGradientConstPtr;
00074
00076 RIFTEstimation () : nr_distance_bins_ (4), nr_gradient_bins_ (8)
00077 {
00078 feature_name_ = "RIFTEstimation";
00079 };
00080
00084 inline void setInputGradient (const PointCloudGradientConstPtr &gradient) { gradient_ = gradient; };
00085
00087 inline PointCloudGradientConstPtr getInputGradient () { return (gradient_); };
00088
00089
00093 inline void setNrDistanceBins (size_t nr_distance_bins) { nr_distance_bins_ = (int) nr_distance_bins; };
00094
00096 inline int getNrDistanceBins () { return (nr_distance_bins_); };
00097
00098
00102 inline void setNrGradientBins (size_t nr_gradient_bins) { nr_gradient_bins_ = (int) nr_gradient_bins; };
00103
00105 inline int getNrGradientBins () { return (nr_gradient_bins_); };
00106
00117 void computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius,
00118 const std::vector<int> &indices, const std::vector<float> &squared_distances,
00119 Eigen::MatrixXf &rift_descriptor);
00120
00121 protected:
00122
00128 void computeFeature (PointCloudOut &output);
00129
00130 private:
00131
00133 PointCloudGradientConstPtr gradient_;
00134
00136 int nr_distance_bins_;
00137
00139 int nr_gradient_bins_;
00140
00141 };
00142 }
00143
00144 #endif // #ifndef PCL_RIFT_H_