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_FPFH_H_
00041 #define PCL_FPFH_H_
00042
00043 #include <pcl/features/feature.h>
00044 #include <set>
00045
00046 namespace pcl
00047 {
00078 template <typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
00079 class FPFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00080 {
00081 public:
00082 using Feature<PointInT, PointOutT>::feature_name_;
00083 using Feature<PointInT, PointOutT>::getClassName;
00084 using Feature<PointInT, PointOutT>::indices_;
00085 using Feature<PointInT, PointOutT>::k_;
00086 using Feature<PointInT, PointOutT>::search_parameter_;
00087 using Feature<PointInT, PointOutT>::input_;
00088 using Feature<PointInT, PointOutT>::surface_;
00089 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00090
00091 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00092
00094 FPFHEstimation () :
00095 nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11),
00096 hist_f1_ (), hist_f2_ (), hist_f3_ (), fpfh_histogram_ (),
00097 d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
00098 {
00099 feature_name_ = "FPFHEstimation";
00100 };
00101
00115 bool
00116 computePairFeatures (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00117 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4);
00118
00130 void
00131 computePointSPFHSignature (const pcl::PointCloud<PointInT> &cloud,
00132 const pcl::PointCloud<PointNT> &normals, int p_idx, int row,
00133 const std::vector<int> &indices,
00134 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3);
00135
00145 void
00146 weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1,
00147 const Eigen::MatrixXf &hist_f2,
00148 const Eigen::MatrixXf &hist_f3,
00149 const std::vector<int> &indices,
00150 const std::vector<float> &dists,
00151 Eigen::VectorXf &fpfh_histogram);
00152
00158 inline void
00159 setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3)
00160 {
00161 nr_bins_f1_ = nr_bins_f1;
00162 nr_bins_f2_ = nr_bins_f2;
00163 nr_bins_f3_ = nr_bins_f3;
00164 }
00165
00171 inline void
00172 getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3)
00173 {
00174 nr_bins_f1 = nr_bins_f1_;
00175 nr_bins_f2 = nr_bins_f2_;
00176 nr_bins_f3 = nr_bins_f3_;
00177 }
00178
00179 protected:
00180
00187 void
00188 computeSPFHSignatures (std::vector<int> &spf_hist_lookup,
00189 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3);
00190
00196 void
00197 computeFeature (PointCloudOut &output);
00198
00200 int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_;
00201
00203 Eigen::MatrixXf hist_f1_;
00204
00206 Eigen::MatrixXf hist_f2_;
00207
00209 Eigen::MatrixXf hist_f3_;
00210
00212 Eigen::VectorXf fpfh_histogram_;
00213
00215 float d_pi_;
00216
00217 private:
00221 void
00222 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00223 };
00224
00253 template <typename PointInT, typename PointNT>
00254 class FPFHEstimation<PointInT, PointNT, Eigen::MatrixXf> : public FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>
00255 {
00256 public:
00257 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::k_;
00258 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::nr_bins_f1_;
00259 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::nr_bins_f2_;
00260 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::nr_bins_f3_;
00261 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::hist_f1_;
00262 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::hist_f2_;
00263 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::hist_f3_;
00264 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::indices_;
00265 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::search_parameter_;
00266 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::input_;
00267 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::compute;
00268 using FPFHEstimation<PointInT, PointNT, pcl::FPFHSignature33>::fpfh_histogram_;
00269
00270 private:
00276 void
00277 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00278
00282 void
00283 compute (pcl::PointCloud<pcl::FPFHSignature33> &) {}
00284 };
00285 }
00286
00287 #endif //#ifndef PCL_FPFH_H_