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_SIFT_KEYPOINT_H_
00037 #define PCL_SIFT_KEYPOINT_H_
00038
00039 #include <pcl/keypoints/keypoint.h>
00040
00041 namespace pcl
00042 {
00043 template<typename PointT>
00044 struct SIFTKeypointFieldSelector
00045 {
00046 inline float
00047 operator () (const PointT & p) const
00048 {
00049 return p.intensity;
00050 }
00051 };
00052 template<>
00053 struct SIFTKeypointFieldSelector<PointNormal>
00054 {
00055 inline float
00056 operator () (const PointNormal & p) const
00057 {
00058 return p.curvature;
00059 }
00060 };
00061 template<>
00062 struct SIFTKeypointFieldSelector<PointXYZRGB>
00063 {
00064 inline float
00065 operator () (const PointXYZRGB & p) const
00066 {
00067 return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f);
00068 }
00069 };
00070 template<>
00071 struct SIFTKeypointFieldSelector<PointXYZRGBA>
00072 {
00073 inline float
00074 operator () (const PointXYZRGBA & p) const
00075 {
00076 return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f);
00077 }
00078 };
00079
00093 template <typename PointInT, typename PointOutT>
00094 class SIFTKeypoint : public Keypoint<PointInT, PointOutT>
00095 {
00096 public:
00097 typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00098 typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00099 typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
00100
00101 using Keypoint<PointInT, PointOutT>::name_;
00102 using Keypoint<PointInT, PointOutT>::input_;
00103 using Keypoint<PointInT, PointOutT>::indices_;
00104 using Keypoint<PointInT, PointOutT>::surface_;
00105 using Keypoint<PointInT, PointOutT>::tree_;
00106 using Keypoint<PointInT, PointOutT>::initCompute;
00107
00109 SIFTKeypoint () : min_scale_ (0.0), nr_octaves_ (0), nr_scales_per_octave_ (0),
00110 min_contrast_ (-std::numeric_limits<float>::max ()), scale_idx_ (-1),
00111 out_fields_ (), getFieldValue_ ()
00112 {
00113 name_ = "SIFTKeypoint";
00114 }
00115
00121 void
00122 setScales (float min_scale, int nr_octaves, int nr_scales_per_octave);
00123
00127 void
00128 setMinimumContrast (float min_contrast);
00129
00130 protected:
00131 bool
00132 initCompute ();
00133
00138 void
00139 detectKeypoints (PointCloudOut &output);
00140
00141 private:
00149 void
00150 detectKeypointsForOctave (const PointCloudIn &input, KdTree &tree,
00151 float base_scale, int nr_scales_per_octave,
00152 PointCloudOut &output);
00153
00160 void
00161 computeScaleSpace (const PointCloudIn &input, KdTree &tree,
00162 const std::vector<float> &scales,
00163 Eigen::MatrixXf &diff_of_gauss);
00164
00172 void
00173 findScaleSpaceExtrema (const PointCloudIn &input, KdTree &tree,
00174 const Eigen::MatrixXf &diff_of_gauss,
00175 std::vector<int> &extrema_indices, std::vector<int> &extrema_scales);
00176
00177
00179 float min_scale_;
00180
00182 int nr_octaves_;
00183
00185 int nr_scales_per_octave_;
00186
00188 float min_contrast_;
00189
00192 int scale_idx_;
00193
00195 std::vector<sensor_msgs::PointField> out_fields_;
00196
00197 SIFTKeypointFieldSelector<PointInT> getFieldValue_;
00198 };
00199 }
00200
00201 #include <pcl/keypoints/impl/sift_keypoint.hpp>
00202
00203 #endif // #ifndef PCL_SIFT_KEYPOINT_H_