Go to the documentation of this file.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 #ifndef PCL_ISS_3D_H_
00037 #define PCL_ISS_3D_H_
00038
00039 #include <pcl/keypoints/keypoint.h>
00040
00041 namespace pcl
00042 {
00084 template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
00085 class ISSKeypoint3D : public Keypoint<PointInT, PointOutT>
00086 {
00087 public:
00088 typedef boost::shared_ptr<ISSKeypoint3D<PointInT, PointOutT, NormalT> > Ptr;
00089 typedef boost::shared_ptr<const ISSKeypoint3D<PointInT, PointOutT, NormalT> > ConstPtr;
00090
00091 typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00092 typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00093
00094 typedef typename pcl::PointCloud<NormalT> PointCloudN;
00095 typedef typename PointCloudN::Ptr PointCloudNPtr;
00096 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00097
00098 typedef typename pcl::octree::OctreePointCloudSearch<PointInT> OctreeSearchIn;
00099 typedef typename OctreeSearchIn::Ptr OctreeSearchInPtr;
00100
00101 using Keypoint<PointInT, PointOutT>::name_;
00102 using Keypoint<PointInT, PointOutT>::input_;
00103 using Keypoint<PointInT, PointOutT>::surface_;
00104 using Keypoint<PointInT, PointOutT>::tree_;
00105 using Keypoint<PointInT, PointOutT>::search_radius_;
00106 using Keypoint<PointInT, PointOutT>::search_parameter_;
00107
00111 ISSKeypoint3D (double salient_radius = 0.0001)
00112 : salient_radius_ (salient_radius)
00113 , non_max_radius_ (0.0)
00114 , normal_radius_ (0.0)
00115 , border_radius_ (0.0)
00116 , gamma_21_ (0.975)
00117 , gamma_32_ (0.975)
00118 , third_eigen_value_ (0)
00119 , edge_points_ (0)
00120 , min_neighbors_ (5)
00121 , normals_ (new pcl::PointCloud<NormalT>)
00122 , angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
00123 , threads_ (0)
00124 {
00125 name_ = "ISSKeypoint3D";
00126 search_radius_ = salient_radius_;
00127 }
00128
00132 void
00133 setSalientRadius (double salient_radius);
00134
00138 void
00139 setNonMaxRadius (double non_max_radius);
00140
00145 void
00146 setNormalRadius (double normal_radius);
00147
00152 void
00153 setBorderRadius (double border_radius);
00154
00158 void
00159 setThreshold21 (double gamma_21);
00160
00164 void
00165 setThreshold32 (double gamma_32);
00166
00170 void
00171 setMinNeighbors (int min_neighbors);
00172
00176 void
00177 setNormals (const PointCloudNConstPtr &normals);
00178
00183 inline void
00184 setAngleThreshold (float angle)
00185 {
00186 angle_threshold_ = angle;
00187 }
00188
00192 inline void
00193 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00194
00195 protected:
00196
00203 bool*
00204 getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold);
00205
00210 void
00211 getScatterMatrix (const int ¤t_index, Eigen::Matrix3d &cov_m);
00212
00216 bool
00217 initCompute ();
00218
00222 void
00223 detectKeypoints (PointCloudOut &output);
00224
00225
00227 double salient_radius_;
00228
00230 double non_max_radius_;
00231
00233 double normal_radius_;
00234
00236 double border_radius_;
00237
00239 double gamma_21_;
00240
00242 double gamma_32_;
00243
00245 double *third_eigen_value_;
00246
00248 bool *edge_points_;
00249
00251 int min_neighbors_;
00252
00254 PointCloudNConstPtr normals_;
00255
00257 float angle_threshold_;
00258
00260 unsigned int threads_;
00261
00262 };
00263
00264 }
00265
00266 #include <pcl/keypoints/impl/iss_3d.hpp>
00267
00268 #endif