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 #ifndef KEYPOINTDESCRIPTOR_H_
00029 #define KEYPOINTDESCRIPTOR_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
00032
00033 #include <opencv2/highgui/highgui.hpp>
00034 #include <opencv2/core/core.hpp>
00035 #include <opencv2/features2d/features2d.hpp>
00036 #include <list>
00037 #include "rtabmap/core/Parameters.h"
00038
00039 namespace cv{
00040 class SURF;
00041 class SIFT;
00042 namespace gpu {
00043 class SURF_GPU;
00044 class ORB_GPU;
00045 class FAST_GPU;
00046 }
00047 }
00048
00049 namespace rtabmap {
00050
00051
00052 class RTABMAP_EXP Feature2D {
00053 public:
00054 enum Type {kFeatureUndef=-1,
00055 kFeatureSurf=0,
00056 kFeatureSift=1,
00057 kFeatureOrb=2,
00058 kFeatureFastFreak=3,
00059 kFeatureFastBrief=4,
00060 kFeatureGfttFreak=5,
00061 kFeatureGfttBrief=6,
00062 kFeatureBrisk=7};
00063
00064 static Feature2D * create(Feature2D::Type & type, const ParametersMap & parameters);
00065
00066 static void filterKeypointsByDepth(
00067 std::vector<cv::KeyPoint> & keypoints,
00068 const cv::Mat & depth,
00069 float maxDepth);
00070 static void filterKeypointsByDepth(
00071 std::vector<cv::KeyPoint> & keypoints,
00072 cv::Mat & descriptors,
00073 const cv::Mat & depth,
00074 float maxDepth);
00075
00076 static void filterKeypointsByDisparity(
00077 std::vector<cv::KeyPoint> & keypoints,
00078 const cv::Mat & disparity,
00079 float minDisparity);
00080 static void filterKeypointsByDisparity(
00081 std::vector<cv::KeyPoint> & keypoints,
00082 cv::Mat & descriptors,
00083 const cv::Mat & disparity,
00084 float minDisparity);
00085
00086 static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints);
00087 static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints);
00088
00089 static cv::Rect computeRoi(const cv::Mat & image, const std::string & roiRatios);
00090 static cv::Rect computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
00091
00092 int getMaxFeatures() const {return maxFeatures_;}
00093
00094 public:
00095 virtual ~Feature2D() {}
00096
00097 std::vector<cv::KeyPoint> generateKeypoints(const cv::Mat & image, const cv::Rect & roi = cv::Rect()) const;
00098 cv::Mat generateDescriptors(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00099
00100 virtual void parseParameters(const ParametersMap & parameters);
00101 virtual Feature2D::Type getType() const = 0;
00102
00103 protected:
00104 Feature2D(const ParametersMap & parameters = ParametersMap());
00105
00106 private:
00107 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const = 0;
00108 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
00109
00110 private:
00111 int maxFeatures_;
00112 };
00113
00114
00115 class RTABMAP_EXP SURF : public Feature2D
00116 {
00117 public:
00118 SURF(const ParametersMap & parameters = ParametersMap());
00119 virtual ~SURF();
00120
00121 virtual void parseParameters(const ParametersMap & parameters);
00122 virtual Feature2D::Type getType() const {return kFeatureSurf;}
00123
00124 private:
00125 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00126 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00127
00128 private:
00129 double hessianThreshold_;
00130 int nOctaves_;
00131 int nOctaveLayers_;
00132 bool extended_;
00133 bool upright_;
00134 float gpuKeypointsRatio_;
00135 bool gpuVersion_;
00136
00137 cv::SURF * _surf;
00138 cv::gpu::SURF_GPU * _gpuSurf;
00139 };
00140
00141
00142 class RTABMAP_EXP SIFT : public Feature2D
00143 {
00144 public:
00145 SIFT(const ParametersMap & parameters = ParametersMap());
00146 virtual ~SIFT();
00147
00148 virtual void parseParameters(const ParametersMap & parameters);
00149 virtual Feature2D::Type getType() const {return kFeatureSift;}
00150
00151 private:
00152 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00153 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00154
00155 private:
00156 int nfeatures_;
00157 int nOctaveLayers_;
00158 double contrastThreshold_;
00159 double edgeThreshold_;
00160 double sigma_;
00161
00162 cv::SIFT * _sift;
00163 };
00164
00165
00166 class RTABMAP_EXP ORB : public Feature2D
00167 {
00168 public:
00169 ORB(const ParametersMap & parameters = ParametersMap());
00170 virtual ~ORB();
00171
00172 virtual void parseParameters(const ParametersMap & parameters);
00173 virtual Feature2D::Type getType() const {return kFeatureOrb;}
00174
00175 private:
00176 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00177 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00178
00179 private:
00180 int nFeatures_;
00181 float scaleFactor_;
00182 int nLevels_;
00183 int edgeThreshold_;
00184 int firstLevel_;
00185 int WTA_K_;
00186 int scoreType_;
00187 int patchSize_;
00188 bool gpu_;
00189
00190 int fastThreshold_;
00191 bool nonmaxSuppresion_;
00192
00193 cv::ORB * _orb;
00194 cv::gpu::ORB_GPU * _gpuOrb;
00195 };
00196
00197
00198 class RTABMAP_EXP FAST : public Feature2D
00199 {
00200 public:
00201 FAST(const ParametersMap & parameters = ParametersMap());
00202 virtual ~FAST();
00203
00204 virtual void parseParameters(const ParametersMap & parameters);
00205
00206 private:
00207 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00208
00209 private:
00210 int threshold_;
00211 bool nonmaxSuppression_;
00212 bool gpu_;
00213 double gpuKeypointsRatio_;
00214
00215 cv::FastFeatureDetector * _fast;
00216 cv::gpu::FAST_GPU * _gpuFast;
00217 };
00218
00219
00220 class RTABMAP_EXP FAST_BRIEF : public FAST
00221 {
00222 public:
00223 FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
00224 virtual ~FAST_BRIEF();
00225
00226 virtual void parseParameters(const ParametersMap & parameters);
00227 virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
00228
00229 private:
00230 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00231
00232 private:
00233 int bytes_;
00234
00235 cv::BriefDescriptorExtractor * _brief;
00236 };
00237
00238
00239 class RTABMAP_EXP FAST_FREAK : public FAST
00240 {
00241 public:
00242 FAST_FREAK(const ParametersMap & parameters = ParametersMap());
00243 virtual ~FAST_FREAK();
00244
00245 virtual void parseParameters(const ParametersMap & parameters);
00246 virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
00247
00248 private:
00249 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00250
00251 private:
00252 bool orientationNormalized_;
00253 bool scaleNormalized_;
00254 float patternScale_;
00255 int nOctaves_;
00256
00257 cv::FREAK * _freak;
00258 };
00259
00260
00261 class RTABMAP_EXP GFTT : public Feature2D
00262 {
00263 public:
00264 GFTT(const ParametersMap & parameters = ParametersMap());
00265 virtual ~GFTT();
00266
00267 virtual void parseParameters(const ParametersMap & parameters);
00268
00269 private:
00270 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00271
00272 private:
00273 int _maxCorners;
00274 double _qualityLevel;
00275 double _minDistance;
00276 int _blockSize;
00277 bool _useHarrisDetector;
00278 double _k;
00279
00280 cv::GFTTDetector * _gftt;
00281 };
00282
00283
00284 class RTABMAP_EXP GFTT_BRIEF : public GFTT
00285 {
00286 public:
00287 GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
00288 virtual ~GFTT_BRIEF();
00289
00290 virtual void parseParameters(const ParametersMap & parameters);
00291 virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
00292
00293 private:
00294 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00295
00296 private:
00297 int bytes_;
00298
00299 cv::BriefDescriptorExtractor * _brief;
00300 };
00301
00302
00303 class RTABMAP_EXP GFTT_FREAK : public GFTT
00304 {
00305 public:
00306 GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
00307 virtual ~GFTT_FREAK();
00308
00309 virtual void parseParameters(const ParametersMap & parameters);
00310 virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
00311
00312 private:
00313 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00314
00315 private:
00316 bool orientationNormalized_;
00317 bool scaleNormalized_;
00318 float patternScale_;
00319 int nOctaves_;
00320
00321 cv::FREAK * _freak;
00322 };
00323
00324
00325 class RTABMAP_EXP BRISK : public Feature2D
00326 {
00327 public:
00328 BRISK(const ParametersMap & parameters = ParametersMap());
00329 virtual ~BRISK();
00330
00331 virtual void parseParameters(const ParametersMap & parameters);
00332 virtual Feature2D::Type getType() const {return kFeatureBrisk;}
00333
00334 private:
00335 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi) const;
00336 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00337
00338 private:
00339 int thresh_;
00340 int octaves_;
00341 float patternScale_;
00342
00343 cv::BRISK * brisk_;
00344 };
00345
00346
00347 }
00348
00349 #endif