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_FPFH_H_
00042 #define PCL_FPFH_H_
00043
00044 #include <pcl/features/feature.h>
00045 #include <set>
00046
00047 namespace pcl
00048 {
00079 template <typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
00080 class FPFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00081 {
00082 public:
00083 typedef boost::shared_ptr<FPFHEstimation<PointInT, PointNT, PointOutT> > Ptr;
00084 typedef boost::shared_ptr<const FPFHEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00085 using Feature<PointInT, PointOutT>::feature_name_;
00086 using Feature<PointInT, PointOutT>::getClassName;
00087 using Feature<PointInT, PointOutT>::indices_;
00088 using Feature<PointInT, PointOutT>::k_;
00089 using Feature<PointInT, PointOutT>::search_parameter_;
00090 using Feature<PointInT, PointOutT>::input_;
00091 using Feature<PointInT, PointOutT>::surface_;
00092 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00093
00094 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00095
00097 FPFHEstimation () :
00098 nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11),
00099 hist_f1_ (), hist_f2_ (), hist_f3_ (), fpfh_histogram_ (),
00100 d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
00101 {
00102 feature_name_ = "FPFHEstimation";
00103 };
00104
00118 bool
00119 computePairFeatures (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00120 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4);
00121
00133 void
00134 computePointSPFHSignature (const pcl::PointCloud<PointInT> &cloud,
00135 const pcl::PointCloud<PointNT> &normals, int p_idx, int row,
00136 const std::vector<int> &indices,
00137 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3);
00138
00148 void
00149 weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1,
00150 const Eigen::MatrixXf &hist_f2,
00151 const Eigen::MatrixXf &hist_f3,
00152 const std::vector<int> &indices,
00153 const std::vector<float> &dists,
00154 Eigen::VectorXf &fpfh_histogram);
00155
00161 inline void
00162 setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3)
00163 {
00164 nr_bins_f1_ = nr_bins_f1;
00165 nr_bins_f2_ = nr_bins_f2;
00166 nr_bins_f3_ = nr_bins_f3;
00167 }
00168
00174 inline void
00175 getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3)
00176 {
00177 nr_bins_f1 = nr_bins_f1_;
00178 nr_bins_f2 = nr_bins_f2_;
00179 nr_bins_f3 = nr_bins_f3_;
00180 }
00181
00182 protected:
00183
00190 void
00191 computeSPFHSignatures (std::vector<int> &spf_hist_lookup,
00192 Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3);
00193
00199 void
00200 computeFeature (PointCloudOut &output);
00201
00203 int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_;
00204
00206 Eigen::MatrixXf hist_f1_;
00207
00209 Eigen::MatrixXf hist_f2_;
00210
00212 Eigen::MatrixXf hist_f3_;
00213
00215 Eigen::VectorXf fpfh_histogram_;
00216
00218 float d_pi_;
00219 };
00220 }
00221
00222 #ifdef PCL_NO_PRECOMPILE
00223 #include <pcl/features/impl/fpfh.hpp>
00224 #endif
00225
00226 #endif //#ifndef PCL_FPFH_H_