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_FEATURES_VFH_H_
00039 #define PCL_FEATURES_VFH_H_
00040
00041 #include <pcl/features/feature.h>
00042
00043 namespace pcl
00044 {
00046
00063 template <typename PointInT, typename PointNT, typename PointOutT>
00064 class VFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00065 {
00066 public:
00067 using Feature<PointInT, PointOutT>::feature_name_;
00068 using Feature<PointInT, PointOutT>::getClassName;
00069 using Feature<PointInT, PointOutT>::indices_;
00070 using Feature<PointInT, PointOutT>::k_;
00071 using Feature<PointInT, PointOutT>::search_radius_;
00072 using Feature<PointInT, PointOutT>::surface_;
00073 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00074
00075 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00076
00078 VFHEstimation () : nr_bins_f1_ (45), nr_bins_f2_ (45), nr_bins_f3_ (45), nr_bins_f4_ (45), nr_bins_vp_ (128), vpx_ (0), vpy_ (0), vpz_ (0), d_pi_ (1.0 / (2.0 * M_PI))
00079 {
00080 hist_f1_.setZero (nr_bins_f1_);
00081 hist_f2_.setZero (nr_bins_f2_);
00082 hist_f3_.setZero (nr_bins_f3_);
00083 hist_f4_.setZero (nr_bins_f4_);
00084 search_radius_ = 0;
00085 k_ = 1;
00086 feature_name_ = "VFHEstimation";
00087 };
00088
00097 void computePointSPFHSignature (const Eigen::Vector4f ¢roid_p, const Eigen::Vector4f ¢roid_n, const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals, const std::vector<int> &indices);
00098
00105 void
00106 setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3, int nr_bins_f4)
00107 {
00108 nr_bins_f1_ = nr_bins_f1;
00109 nr_bins_f2_ = nr_bins_f2;
00110 nr_bins_f3_ = nr_bins_f3;
00111 nr_bins_f4_ = nr_bins_f4;
00112 }
00113
00115 void
00116 getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3, int &nr_bins_f4)
00117 {
00118 nr_bins_f1 = nr_bins_f1_;
00119 nr_bins_f2 = nr_bins_f2_;
00120 nr_bins_f3 = nr_bins_f3_;
00121 nr_bins_f4 = nr_bins_f4_;
00122 }
00123
00127 void setNrViewpointSubdivisions (int nr_bins) { nr_bins_vp_ = nr_bins; }
00128
00130 void getNrViewpointSubdivisions (int &nr_bins) { nr_bins = nr_bins_vp_; }
00131
00137 inline void
00138 setViewPoint (float vpx, float vpy, float vpz)
00139 {
00140 vpx_ = vpx;
00141 vpy_ = vpy;
00142 vpz_ = vpz;
00143 }
00144
00146 inline void
00147 getViewPoint (float &vpx, float &vpy, float &vpz)
00148 {
00149 vpx = vpx_;
00150 vpy = vpy_;
00151 vpz = vpz_;
00152 }
00153
00154 private:
00155
00157 int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_, nr_bins_f4_, nr_bins_vp_;
00158
00161 float vpx_, vpy_, vpz_;
00162
00168 void computeFeature (PointCloudOut &output);
00169
00170 protected:
00172 Eigen::VectorXf hist_f1_;
00174 Eigen::VectorXf hist_f2_;
00176 Eigen::VectorXf hist_f3_;
00178 Eigen::VectorXf hist_f4_;
00180 Eigen::VectorXf hist_vp_;
00181
00182 private:
00184 float d_pi_;
00185 };
00186 }
00187
00188 #endif //#ifndef PCL_FEATURES_VFH_H_