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_SIFT_KEYPOINT_H_
00037 #define PCL_SIFT_KEYPOINT_H_
00038
00039 #include <pcl/keypoints/keypoint.h>
00040
00041 #include "pcl/filters/voxel_grid.h"
00042
00043 namespace pcl
00044 {
00054 template <typename PointInT, typename PointOutT>
00055 class SIFTKeypoint : public Keypoint<PointInT, PointOutT>
00056 {
00057 public:
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
00062 using Keypoint<PointInT, PointOutT>::name_;
00063 using Keypoint<PointInT, PointOutT>::input_;
00064 using Keypoint<PointInT, PointOutT>::indices_;
00065 using Keypoint<PointInT, PointOutT>::surface_;
00066 using Keypoint<PointInT, PointOutT>::tree_;
00067
00069 SIFTKeypoint () : min_scale_ (0.0), nr_octaves_ (0), nr_scales_per_octave_ (0),
00070 min_contrast_ (-std::numeric_limits<float>::max ())
00071 {
00072 name_ = "SIFTKeypoint";
00073 }
00074
00080 void setScales (float min_scale, int nr_octaves, int nr_scales_per_octave);
00081
00085 void setMinimumContrast (float min_contrast);
00086
00087 protected:
00092 void detectKeypoints (PointCloudOut &output);
00093
00094 private:
00102 void detectKeypointsForOctave (const PointCloudIn &input, KdTree &tree,
00103 float base_scale, int nr_scales_per_octave,
00104 PointCloudOut &output);
00105
00112 void computeScaleSpace (const PointCloudIn &input, KdTree &tree,
00113 const std::vector<float> &scales,
00114 Eigen::MatrixXf &diff_of_gauss);
00115
00123 void findScaleSpaceExtrema (const PointCloudIn &input, KdTree &tree,
00124 const Eigen::MatrixXf &diff_of_gauss,
00125 std::vector<int> &extrema_indices, std::vector<int> &extrema_scales);
00126
00127
00129 float min_scale_;
00130
00132 int nr_octaves_;
00133
00135 int nr_scales_per_octave_;
00136
00138 float min_contrast_;
00139
00140 };
00141 }
00142
00143 #include "pcl/keypoints/sift_keypoint.hpp"
00144
00145 #endif // #ifndef PCL_SIFT_KEYPOINT_H_
00146