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_FEATURES_CVFH_H_
00042 #define PCL_FEATURES_CVFH_H_
00043
00044 #include <pcl/features/feature.h>
00045 #include <pcl/features/vfh.h>
00046 #include <pcl/search/pcl_search.h>
00047 #include <pcl/common/common.h>
00048
00049 namespace pcl
00050 {
00063 template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
00064 class CVFHEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00065 {
00066 public:
00067 typedef boost::shared_ptr<CVFHEstimation<PointInT, PointNT, PointOutT> > Ptr;
00068 typedef boost::shared_ptr<const CVFHEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00069
00070 using Feature<PointInT, PointOutT>::feature_name_;
00071 using Feature<PointInT, PointOutT>::getClassName;
00072 using Feature<PointInT, PointOutT>::indices_;
00073 using Feature<PointInT, PointOutT>::k_;
00074 using Feature<PointInT, PointOutT>::search_radius_;
00075 using Feature<PointInT, PointOutT>::surface_;
00076 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00077
00078 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00079 typedef typename pcl::search::Search<PointNormal>::Ptr KdTreePtr;
00080 typedef typename pcl::VFHEstimation<PointInT, PointNT, pcl::VFHSignature308> VFHEstimator;
00081
00083 CVFHEstimation () :
00084 vpx_ (0), vpy_ (0), vpz_ (0),
00085 leaf_size_ (0.005f),
00086 normalize_bins_ (false),
00087 curv_threshold_ (0.03f),
00088 cluster_tolerance_ (leaf_size_ * 3),
00089 eps_angle_threshold_ (0.125f),
00090 min_points_ (50),
00091 radius_normals_ (leaf_size_ * 3),
00092 centroids_dominant_orientations_ (),
00093 dominant_normals_ ()
00094 {
00095 search_radius_ = 0;
00096 k_ = 1;
00097 feature_name_ = "CVFHEstimation";
00098 }
00099 ;
00100
00107 void
00108 filterNormalsWithHighCurvature (const pcl::PointCloud<PointNT> & cloud, std::vector<int> & indices_to_use, std::vector<int> &indices_out,
00109 std::vector<int> &indices_in, float threshold);
00110
00116 inline void
00117 setViewPoint (float vpx, float vpy, float vpz)
00118 {
00119 vpx_ = vpx;
00120 vpy_ = vpy;
00121 vpz_ = vpz;
00122 }
00123
00127 inline void
00128 setRadiusNormals (float radius_normals)
00129 {
00130 radius_normals_ = radius_normals;
00131 }
00132
00138 inline void
00139 getViewPoint (float &vpx, float &vpy, float &vpz)
00140 {
00141 vpx = vpx_;
00142 vpy = vpy_;
00143 vpz = vpz_;
00144 }
00145
00149 inline void
00150 getCentroidClusters (std::vector<Eigen::Vector3f> & centroids)
00151 {
00152 for (size_t i = 0; i < centroids_dominant_orientations_.size (); ++i)
00153 centroids.push_back (centroids_dominant_orientations_[i]);
00154 }
00155
00159 inline void
00160 getCentroidNormalClusters (std::vector<Eigen::Vector3f> & centroids)
00161 {
00162 for (size_t i = 0; i < dominant_normals_.size (); ++i)
00163 centroids.push_back (dominant_normals_[i]);
00164 }
00165
00170 inline void
00171 setClusterTolerance (float d)
00172 {
00173 cluster_tolerance_ = d;
00174 }
00175
00179 inline void
00180 setEPSAngleThreshold (float d)
00181 {
00182 eps_angle_threshold_ = d;
00183 }
00184
00188 inline void
00189 setCurvatureThreshold (float d)
00190 {
00191 curv_threshold_ = d;
00192 }
00193
00197 inline void
00198 setMinPoints (size_t min)
00199 {
00200 min_points_ = min;
00201 }
00202
00206 inline void
00207 setNormalizeBins (bool normalize)
00208 {
00209 normalize_bins_ = normalize;
00210 }
00211
00215 void
00216 compute (PointCloudOut &output);
00217
00218 private:
00222 float vpx_, vpy_, vpz_;
00223
00227 float leaf_size_;
00228
00230 bool normalize_bins_;
00231
00233 float curv_threshold_;
00234
00236 float cluster_tolerance_;
00237
00239 float eps_angle_threshold_;
00240
00244 size_t min_points_;
00245
00247 float radius_normals_;
00248
00256 void
00257 computeFeature (PointCloudOut &output);
00258
00272 void
00273 extractEuclideanClustersSmooth (const pcl::PointCloud<pcl::PointNormal> &cloud,
00274 const pcl::PointCloud<pcl::PointNormal> &normals, float tolerance,
00275 const pcl::search::Search<pcl::PointNormal>::Ptr &tree,
00276 std::vector<pcl::PointIndices> &clusters, double eps_angle,
00277 unsigned int min_pts_per_cluster = 1,
00278 unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ());
00279
00280 protected:
00282 std::vector<Eigen::Vector3f> centroids_dominant_orientations_;
00284 std::vector<Eigen::Vector3f> dominant_normals_;
00285 };
00286 }
00287
00288 #ifdef PCL_NO_PRECOMPILE
00289 #include <pcl/features/impl/cvfh.hpp>
00290 #endif
00291
00292 #endif //#ifndef PCL_FEATURES_CVFH_H_