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_FPFH_H_
00039 #define PCL_FPFH_H_
00040
00041 #include <pcl/features/feature.h>
00042
00043 namespace pcl
00044 {
00046
00068 template <typename PointInT, typename PointNT, typename PointOutT>
00069 class FPFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00070 {
00071 public:
00072 using Feature<PointInT, PointOutT>::feature_name_;
00073 using Feature<PointInT, PointOutT>::getClassName;
00074 using Feature<PointInT, PointOutT>::indices_;
00075 using Feature<PointInT, PointOutT>::k_;
00076 using Feature<PointInT, PointOutT>::search_parameter_;
00077 using Feature<PointInT, PointOutT>::surface_;
00078 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00079
00080 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00081
00083 FPFHEstimation () : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), d_pi_ (1.0 / (2.0 * M_PI))
00084 {
00085 feature_name_ = "FPFHEstimation";
00086 };
00087
00101 bool computePairFeatures (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00102 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4);
00103
00114 void computePointSPFHSignature (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals, int p_idx, const std::vector<int> &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3);
00115
00125 void weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const std::vector<int> &indices, const std::vector<float> &dists, Eigen::VectorXf &fpfh_histogram);
00126
00130 inline void
00131 setIndices (const IndicesConstPtr &indices)
00132 {
00133 indices_ = indices;
00134 size_t data_size = indices_->size ();
00135 hist_f1_.setZero (data_size, nr_bins_f1_);
00136 hist_f2_.setZero (data_size, nr_bins_f2_);
00137 hist_f3_.setZero (data_size, nr_bins_f3_);
00138 }
00139
00145 inline void
00146 setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3)
00147 {
00148 nr_bins_f1_ = nr_bins_f1;
00149 nr_bins_f2_ = nr_bins_f2;
00150 nr_bins_f3_ = nr_bins_f3;
00151 }
00152
00154 inline void
00155 getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3)
00156 {
00157 nr_bins_f1 = nr_bins_f1_;
00158 nr_bins_f2 = nr_bins_f2_;
00159 nr_bins_f3 = nr_bins_f3_;
00160 }
00161
00162 protected:
00163
00169 void computeFeature (PointCloudOut &output);
00170
00172 int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_;
00173
00175 Eigen::MatrixXf hist_f1_;
00176
00178 Eigen::MatrixXf hist_f2_;
00179
00181 Eigen::MatrixXf hist_f3_;
00182
00183 private:
00185 Eigen::VectorXf fpfh_histogram_;
00186
00188 float d_pi_;
00189 };
00190 }
00191
00192 #endif //#ifndef PCL_FPFH_H_
00193
00194