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_PFH_H_
00041 #define PCL_PFH_H_
00042
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045 #include <map>
00046
00047 namespace pcl
00048 {
00065 PCL_EXPORTS bool
00066 computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1,
00067 const Eigen::Vector4f &p2, const Eigen::Vector4f &n2,
00068 float &f1, float &f2, float &f3, float &f4);
00069
00100 template <typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
00101 class PFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00102 {
00103 public:
00104 using Feature<PointInT, PointOutT>::feature_name_;
00105 using Feature<PointInT, PointOutT>::getClassName;
00106 using Feature<PointInT, PointOutT>::indices_;
00107 using Feature<PointInT, PointOutT>::k_;
00108 using Feature<PointInT, PointOutT>::search_parameter_;
00109 using Feature<PointInT, PointOutT>::surface_;
00110 using Feature<PointInT, PointOutT>::input_;
00111 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00112
00113 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00114 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00115
00119 PFHEstimation () :
00120 nr_subdiv_ (5),
00121 pfh_histogram_ (),
00122 pfh_tuple_ (),
00123 d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI))),
00124 feature_map_ (),
00125 key_list_ (),
00126
00127 max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair<std::pair<int, int>, Eigen::Vector4f>)),
00128 use_cache_ (false)
00129 {
00130 feature_name_ = "PFHEstimation";
00131 };
00132
00136 inline void
00137 setMaximumCacheSize (unsigned int cache_size)
00138 {
00139 max_cache_size_ = cache_size;
00140 }
00141
00143 inline unsigned int
00144 getMaximumCacheSize ()
00145 {
00146 return (max_cache_size_);
00147 }
00148
00160 inline void
00161 setUseInternalCache (bool use_cache)
00162 {
00163 use_cache_ = use_cache;
00164 }
00165
00167 inline bool
00168 getUseInternalCache ()
00169 {
00170 return (use_cache_);
00171 }
00172
00187 bool
00188 computePairFeatures (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00189 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4);
00190
00199 void
00200 computePointPFHSignature (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00201 const std::vector<int> &indices, int nr_split, Eigen::VectorXf &pfh_histogram);
00202
00203 protected:
00209 void
00210 computeFeature (PointCloudOut &output);
00211
00213 int nr_subdiv_;
00214
00216 Eigen::VectorXf pfh_histogram_;
00217
00219 Eigen::Vector4f pfh_tuple_;
00220
00222 int f_index_[3];
00223
00225 float d_pi_;
00226
00228 std::map<std::pair<int, int>, Eigen::Vector4f, std::less<std::pair<int, int> >, Eigen::aligned_allocator<Eigen::Vector4f> > feature_map_;
00229
00231 std::queue<std::pair<int, int> > key_list_;
00232
00234 unsigned int max_cache_size_;
00235
00237 bool use_cache_;
00238 private:
00242 void
00243 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00244 };
00245
00274 template <typename PointInT, typename PointNT>
00275 class PFHEstimation<PointInT, PointNT, Eigen::MatrixXf> : public PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>
00276 {
00277 public:
00278 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::pfh_histogram_;
00279 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::nr_subdiv_;
00280 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::k_;
00281 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::indices_;
00282 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::search_parameter_;
00283 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::surface_;
00284 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::input_;
00285 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::normals_;
00286 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::computePointPFHSignature;
00287 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::compute;
00288 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::feature_map_;
00289 using PFHEstimation<PointInT, PointNT, pcl::PFHSignature125>::key_list_;
00290
00291 private:
00297 void
00298 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00299
00303 void
00304 compute (pcl::PointCloud<pcl::PFHSignature125> &) {}
00305 };
00306 }
00307
00308 #endif //#ifndef PCL_PFH_H_
00309
00310