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 FEATURES2D_H_
00029 #define FEATURES2D_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 #include "rtabmap/core/SensorData.h"
00039
00040 #if CV_MAJOR_VERSION < 3
00041 namespace cv{
00042 class SURF;
00043 class SIFT;
00044 namespace gpu {
00045 class SURF_GPU;
00046 class ORB_GPU;
00047 class FAST_GPU;
00048 }
00049 }
00050 typedef cv::SIFT CV_SIFT;
00051 typedef cv::SURF CV_SURF;
00052 typedef cv::FastFeatureDetector CV_FAST;
00053 typedef cv::FREAK CV_FREAK;
00054 typedef cv::GFTTDetector CV_GFTT;
00055 typedef cv::BriefDescriptorExtractor CV_BRIEF;
00056 typedef cv::BRISK CV_BRISK;
00057 typedef cv::gpu::SURF_GPU CV_SURF_GPU;
00058 typedef cv::gpu::ORB_GPU CV_ORB_GPU;
00059 typedef cv::gpu::FAST_GPU CV_FAST_GPU;
00060 #else
00061 namespace cv{
00062 namespace xfeatures2d {
00063 class FREAK;
00064 class BriefDescriptorExtractor;
00065 class SIFT;
00066 class SURF;
00067 }
00068 namespace cuda {
00069 class FastFeatureDetector;
00070 class ORB;
00071 class SURF_CUDA;
00072 }
00073 }
00074 typedef cv::xfeatures2d::SIFT CV_SIFT;
00075 typedef cv::xfeatures2d::SURF CV_SURF;
00076 typedef cv::FastFeatureDetector CV_FAST;
00077 typedef cv::xfeatures2d::FREAK CV_FREAK;
00078 typedef cv::GFTTDetector CV_GFTT;
00079 typedef cv::xfeatures2d::BriefDescriptorExtractor CV_BRIEF;
00080 typedef cv::BRISK CV_BRISK;
00081 typedef cv::ORB CV_ORB;
00082 typedef cv::cuda::SURF_CUDA CV_SURF_GPU;
00083 typedef cv::cuda::ORB CV_ORB_GPU;
00084 typedef cv::cuda::FastFeatureDetector CV_FAST_GPU;
00085 #endif
00086
00087
00088 namespace rtabmap {
00089
00090 class Stereo;
00091 #if CV_MAJOR_VERSION < 3
00092 class CV_ORB;
00093 #endif
00094
00095
00096 class RTABMAP_EXP Feature2D {
00097 public:
00098 enum Type {kFeatureUndef=-1,
00099 kFeatureSurf=0,
00100 kFeatureSift=1,
00101 kFeatureOrb=2,
00102 kFeatureFastFreak=3,
00103 kFeatureFastBrief=4,
00104 kFeatureGfttFreak=5,
00105 kFeatureGfttBrief=6,
00106 kFeatureBrisk=7,
00107 kFeatureGfttOrb=8};
00108
00109 static Feature2D * create(const ParametersMap & parameters = ParametersMap());
00110 static Feature2D * create(Feature2D::Type type, const ParametersMap & parameters = ParametersMap());
00111
00112 static void filterKeypointsByDepth(
00113 std::vector<cv::KeyPoint> & keypoints,
00114 const cv::Mat & depth,
00115 float minDepth,
00116 float maxDepth);
00117 static void filterKeypointsByDepth(
00118 std::vector<cv::KeyPoint> & keypoints,
00119 cv::Mat & descriptors,
00120 const cv::Mat & depth,
00121 float minDepth,
00122 float maxDepth);
00123
00124 static void filterKeypointsByDisparity(
00125 std::vector<cv::KeyPoint> & keypoints,
00126 const cv::Mat & disparity,
00127 float minDisparity);
00128 static void filterKeypointsByDisparity(
00129 std::vector<cv::KeyPoint> & keypoints,
00130 cv::Mat & descriptors,
00131 const cv::Mat & disparity,
00132 float minDisparity);
00133
00134 static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints);
00135 static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints);
00136
00137 static cv::Rect computeRoi(const cv::Mat & image, const std::string & roiRatios);
00138 static cv::Rect computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
00139
00140 int getMaxFeatures() const {return maxFeatures_;}
00141 float getMinDepth() const {return _minDepth;}
00142 float getMaxDepth() const {return _maxDepth;}
00143
00144 public:
00145 virtual ~Feature2D();
00146
00147 std::vector<cv::KeyPoint> generateKeypoints(
00148 const cv::Mat & image,
00149 const cv::Mat & mask = cv::Mat()) const;
00150 cv::Mat generateDescriptors(
00151 const cv::Mat & image,
00152 std::vector<cv::KeyPoint> & keypoints) const;
00153 std::vector<cv::Point3f> generateKeypoints3D(
00154 const SensorData & data,
00155 const std::vector<cv::KeyPoint> & keypoints) const;
00156
00157 virtual void parseParameters(const ParametersMap & parameters);
00158 virtual const ParametersMap & getParameters() const {return parameters_;}
00159 virtual Feature2D::Type getType() const = 0;
00160
00161 protected:
00162 Feature2D(const ParametersMap & parameters = ParametersMap());
00163
00164 private:
00165 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const = 0;
00166 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
00167
00168 private:
00169 ParametersMap parameters_;
00170 int maxFeatures_;
00171 float _maxDepth;
00172 float _minDepth;
00173 std::vector<float> _roiRatios;
00174 int _subPixWinSize;
00175 int _subPixIterations;
00176 double _subPixEps;
00177
00178 Stereo * _stereo;
00179 };
00180
00181
00182 class RTABMAP_EXP SURF : public Feature2D
00183 {
00184 public:
00185 SURF(const ParametersMap & parameters = ParametersMap());
00186 virtual ~SURF();
00187
00188 virtual void parseParameters(const ParametersMap & parameters);
00189 virtual Feature2D::Type getType() const {return kFeatureSurf;}
00190
00191 private:
00192 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00193 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00194
00195 private:
00196 double hessianThreshold_;
00197 int nOctaves_;
00198 int nOctaveLayers_;
00199 bool extended_;
00200 bool upright_;
00201 float gpuKeypointsRatio_;
00202 bool gpuVersion_;
00203
00204 cv::Ptr<CV_SURF> _surf;
00205 cv::Ptr<CV_SURF_GPU> _gpuSurf;
00206 };
00207
00208
00209 class RTABMAP_EXP SIFT : public Feature2D
00210 {
00211 public:
00212 SIFT(const ParametersMap & parameters = ParametersMap());
00213 virtual ~SIFT();
00214
00215 virtual void parseParameters(const ParametersMap & parameters);
00216 virtual Feature2D::Type getType() const {return kFeatureSift;}
00217
00218 private:
00219 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00220 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00221
00222 private:
00223 int nOctaveLayers_;
00224 double contrastThreshold_;
00225 double edgeThreshold_;
00226 double sigma_;
00227
00228 cv::Ptr<CV_SIFT> _sift;
00229 };
00230
00231
00232 class RTABMAP_EXP ORB : public Feature2D
00233 {
00234 public:
00235 ORB(const ParametersMap & parameters = ParametersMap());
00236 virtual ~ORB();
00237
00238 virtual void parseParameters(const ParametersMap & parameters);
00239 virtual Feature2D::Type getType() const {return kFeatureOrb;}
00240
00241 private:
00242 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00243 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00244
00245 private:
00246 float scaleFactor_;
00247 int nLevels_;
00248 int edgeThreshold_;
00249 int firstLevel_;
00250 int WTA_K_;
00251 int scoreType_;
00252 int patchSize_;
00253 bool gpu_;
00254
00255 int fastThreshold_;
00256 bool nonmaxSuppresion_;
00257
00258 cv::Ptr<CV_ORB> _orb;
00259 cv::Ptr<CV_ORB_GPU> _gpuOrb;
00260 };
00261
00262
00263 class RTABMAP_EXP FAST : public Feature2D
00264 {
00265 public:
00266 FAST(const ParametersMap & parameters = ParametersMap());
00267 virtual ~FAST();
00268
00269 virtual void parseParameters(const ParametersMap & parameters);
00270 virtual Feature2D::Type getType() const {return kFeatureUndef;}
00271
00272 private:
00273 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00274 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const {return cv::Mat();}
00275
00276 private:
00277 int threshold_;
00278 bool nonmaxSuppression_;
00279 bool gpu_;
00280 double gpuKeypointsRatio_;
00281 int minThreshold_;
00282 int maxThreshold_;
00283 int gridRows_;
00284 int gridCols_;
00285
00286 cv::Ptr<cv::FeatureDetector> _fast;
00287 cv::Ptr<CV_FAST_GPU> _gpuFast;
00288 };
00289
00290
00291 class RTABMAP_EXP FAST_BRIEF : public FAST
00292 {
00293 public:
00294 FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
00295 virtual ~FAST_BRIEF();
00296
00297 virtual void parseParameters(const ParametersMap & parameters);
00298 virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
00299
00300 private:
00301 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00302
00303 private:
00304 int bytes_;
00305
00306 cv::Ptr<CV_BRIEF> _brief;
00307 };
00308
00309
00310 class RTABMAP_EXP FAST_FREAK : public FAST
00311 {
00312 public:
00313 FAST_FREAK(const ParametersMap & parameters = ParametersMap());
00314 virtual ~FAST_FREAK();
00315
00316 virtual void parseParameters(const ParametersMap & parameters);
00317 virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
00318
00319 private:
00320 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00321
00322 private:
00323 bool orientationNormalized_;
00324 bool scaleNormalized_;
00325 float patternScale_;
00326 int nOctaves_;
00327
00328 cv::Ptr<CV_FREAK> _freak;
00329 };
00330
00331
00332 class RTABMAP_EXP GFTT : public Feature2D
00333 {
00334 public:
00335 GFTT(const ParametersMap & parameters = ParametersMap());
00336 virtual ~GFTT();
00337
00338 virtual void parseParameters(const ParametersMap & parameters);
00339
00340 private:
00341 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00342
00343 private:
00344 double _qualityLevel;
00345 double _minDistance;
00346 int _blockSize;
00347 bool _useHarrisDetector;
00348 double _k;
00349
00350 cv::Ptr<CV_GFTT> _gftt;
00351 };
00352
00353
00354 class RTABMAP_EXP GFTT_BRIEF : public GFTT
00355 {
00356 public:
00357 GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
00358 virtual ~GFTT_BRIEF();
00359
00360 virtual void parseParameters(const ParametersMap & parameters);
00361 virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
00362
00363 private:
00364 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00365
00366 private:
00367 int bytes_;
00368
00369 cv::Ptr<CV_BRIEF> _brief;
00370 };
00371
00372
00373 class RTABMAP_EXP GFTT_FREAK : public GFTT
00374 {
00375 public:
00376 GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
00377 virtual ~GFTT_FREAK();
00378
00379 virtual void parseParameters(const ParametersMap & parameters);
00380 virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
00381
00382 private:
00383 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00384
00385 private:
00386 bool orientationNormalized_;
00387 bool scaleNormalized_;
00388 float patternScale_;
00389 int nOctaves_;
00390
00391 cv::Ptr<CV_FREAK> _freak;
00392 };
00393
00394
00395 class RTABMAP_EXP GFTT_ORB : public GFTT
00396 {
00397 public:
00398 GFTT_ORB(const ParametersMap & parameters = ParametersMap());
00399 virtual ~GFTT_ORB();
00400
00401 virtual void parseParameters(const ParametersMap & parameters);
00402 virtual Feature2D::Type getType() const {return kFeatureGfttOrb;}
00403
00404 private:
00405 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00406
00407 private:
00408 ORB _orb;
00409 };
00410
00411
00412 class RTABMAP_EXP BRISK : public Feature2D
00413 {
00414 public:
00415 BRISK(const ParametersMap & parameters = ParametersMap());
00416 virtual ~BRISK();
00417
00418 virtual void parseParameters(const ParametersMap & parameters);
00419 virtual Feature2D::Type getType() const {return kFeatureBrisk;}
00420
00421 private:
00422 virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00423 virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00424
00425 private:
00426 int thresh_;
00427 int octaves_;
00428 float patternScale_;
00429
00430 cv::Ptr<CV_BRISK> brisk_;
00431 };
00432
00433
00434 }
00435
00436 #endif