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
00037
00038 #ifndef PCL_HARRIS_KEYPOINT_3D_H_
00039 #define PCL_HARRIS_KEYPOINT_3D_H_
00040
00041 #include <pcl/keypoints/keypoint.h>
00042
00043 namespace pcl
00044 {
00051 template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
00052 class HarrisKeypoint3D : public Keypoint<PointInT, PointOutT>
00053 {
00054 public:
00055 typedef boost::shared_ptr<HarrisKeypoint3D<PointInT, PointOutT, NormalT> > Ptr;
00056 typedef boost::shared_ptr<const HarrisKeypoint3D<PointInT, PointOutT, NormalT> > ConstPtr;
00057
00058 typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00059 typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00060 typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00061 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00062
00063 typedef typename pcl::PointCloud<NormalT> PointCloudN;
00064 typedef typename PointCloudN::Ptr PointCloudNPtr;
00065 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00066
00067 using Keypoint<PointInT, PointOutT>::name_;
00068 using Keypoint<PointInT, PointOutT>::input_;
00069 using Keypoint<PointInT, PointOutT>::indices_;
00070 using Keypoint<PointInT, PointOutT>::surface_;
00071 using Keypoint<PointInT, PointOutT>::tree_;
00072 using Keypoint<PointInT, PointOutT>::k_;
00073 using Keypoint<PointInT, PointOutT>::search_radius_;
00074 using Keypoint<PointInT, PointOutT>::search_parameter_;
00075 using Keypoint<PointInT, PointOutT>::initCompute;
00076
00077 typedef enum {HARRIS = 1, NOBLE, LOWE, TOMASI, CURVATURE} ResponseMethod;
00078
00084 HarrisKeypoint3D (ResponseMethod method = HARRIS, float radius = 0.01f, float threshold = 0.0f)
00085 : threshold_ (threshold)
00086 , refine_ (true)
00087 , nonmax_ (true)
00088 , method_ (method)
00089 , threads_ (0)
00090 {
00091 name_ = "HarrisKeypoint3D";
00092 search_radius_ = radius;
00093 }
00094
00096 virtual ~HarrisKeypoint3D () {}
00097
00101 void
00102 setMethod (ResponseMethod type);
00103
00107 void
00108 setRadius (float radius);
00109
00114 void
00115 setThreshold (float threshold);
00116
00121 void
00122 setNonMaxSupression (bool = false);
00123
00128 void
00129 setRefine (bool do_refine);
00130
00134 void
00135 setNormals (const PointCloudNConstPtr &normals);
00136
00144 virtual void
00145 setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; normals_.reset(); }
00146
00150 inline void
00151 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00152 protected:
00153 bool
00154 initCompute ();
00155 void detectKeypoints (PointCloudOut &output);
00157 void responseHarris (PointCloudOut &output) const;
00158 void responseNoble (PointCloudOut &output) const;
00159 void responseLowe (PointCloudOut &output) const;
00160 void responseTomasi (PointCloudOut &output) const;
00161 void responseCurvature (PointCloudOut &output) const;
00162 void refineCorners (PointCloudOut &corners) const;
00164 void calculateNormalCovar (const std::vector<int>& neighbors, float* coefficients) const;
00165 private:
00166 float threshold_;
00167 bool refine_;
00168 bool nonmax_;
00169 ResponseMethod method_;
00170 PointCloudNConstPtr normals_;
00171 unsigned int threads_;
00172 };
00173 }
00174
00175 #include <pcl/keypoints/impl/harris_3d.hpp>
00176
00177 #endif // #ifndef PCL_HARRIS_KEYPOINT_3D_H_
00178