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 
00039 
00040 #ifndef PCL_HARRIS_KEYPOINT_2D_H_
00041 #define PCL_HARRIS_KEYPOINT_2D_H_
00042 
00043 #include <pcl/keypoints/keypoint.h>
00044 #include <pcl/common/intensity.h>
00045 
00046 namespace pcl
00047 {
00053   template <typename PointInT, typename PointOutT, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT> >
00054   class HarrisKeypoint2D : public Keypoint<PointInT, PointOutT>
00055   {
00056     public:
00057       typedef boost::shared_ptr<HarrisKeypoint2D<PointInT, PointOutT, IntensityT> > Ptr;
00058       typedef boost::shared_ptr<const HarrisKeypoint2D<PointInT, PointOutT, IntensityT> > ConstPtr;
00059 
00060       typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00061       typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00062       typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00063       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00064 
00065       using Keypoint<PointInT, PointOutT>::name_;
00066       using Keypoint<PointInT, PointOutT>::input_;
00067       using Keypoint<PointInT, PointOutT>::indices_;
00068 
00069       typedef enum {HARRIS = 1, NOBLE, LOWE, TOMASI} ResponseMethod;
00070 
00075       HarrisKeypoint2D (ResponseMethod method = HARRIS, int window_width = 3, int window_height = 3, int min_distance = 5, float threshold = 0.0)
00076       : threshold_ (threshold)
00077       , refine_ (false)
00078       , nonmax_ (true)
00079       , method_ (method)
00080       , threads_ (0)
00081       , response_ (new pcl::PointCloud<PointOutT> ())
00082       , window_width_ (window_width)
00083       , window_height_ (window_height)
00084       , skipped_pixels_ (0)
00085       , min_distance_ (min_distance)
00086       {
00087         name_ = "HarrisKeypoint2D";
00088       }
00089 
00093       void setMethod (ResponseMethod type);
00094 
00096       void setWindowWidth (int window_width);
00097 
00099       void setWindowHeight (int window_height);      
00100 
00102       void setSkippedPixels (int skipped_pixels);
00103 
00105       void setMinimalDistance (int min_distance);
00106       
00111       void setThreshold (float threshold);
00112 
00117       void setNonMaxSupression (bool = false);
00118 
00124       void setRefine (bool do_refine);
00125 
00129       inline void
00130       setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00131 
00132     protected:
00133       bool 
00134       initCompute ();
00135       void 
00136       detectKeypoints (PointCloudOut &output);
00138       void 
00139       responseHarris (PointCloudOut &output, float& highest_response) const;
00140       void 
00141       responseNoble (PointCloudOut &output, float& highest_response) const;
00142       void 
00143       responseLowe (PointCloudOut &output, float& highest_response) const;
00144       void 
00145       responseTomasi (PointCloudOut &output, float& highest_response) const;
00146 
00151       void 
00152       computeSecondMomentMatrix (std::size_t pos, float* coefficients) const;
00154       float threshold_;
00156       bool refine_;
00158       bool nonmax_;
00160       ResponseMethod method_;
00162       unsigned int threads_;      
00163 
00164     private:
00165       Eigen::MatrixXf derivatives_rows_;
00166       Eigen::MatrixXf derivatives_cols_;
00168       boost::shared_ptr<pcl::PointCloud<PointOutT> > response_;
00170       bool 
00171       greaterIntensityAtIndices (int a, int b) const
00172       {
00173         return (response_->at (a).intensity > response_->at (b).intensity);
00174       }      
00176       int window_width_;
00178       int window_height_;
00180       int half_window_width_;
00182       int half_window_height_;
00184       int skipped_pixels_;
00186       int min_distance_;
00188       IntensityT intensity_;
00189   };
00190 }
00191 
00192 #include <pcl/keypoints/impl/harris_2d.hpp>
00193 
00194 #endif // #ifndef PCL_HARRIS_KEYPOINT_2D_H_