Features2d.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef FEATURES2D_H_
29 #define FEATURES2D_H_
30 
31 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 
33 #include <opencv2/highgui/highgui.hpp>
34 #include <opencv2/core/core.hpp>
35 #include <opencv2/features2d/features2d.hpp>
36 #include <list>
39 
40 #if CV_MAJOR_VERSION < 3
41 namespace cv{
42 class SURF;
43 class SIFT;
44 namespace gpu {
45  class SURF_GPU;
46  class ORB_GPU;
47  class FAST_GPU;
48 }
49 }
50 typedef cv::SIFT CV_SIFT;
51 typedef cv::SURF CV_SURF;
52 typedef cv::FastFeatureDetector CV_FAST;
53 typedef cv::FREAK CV_FREAK;
54 typedef cv::GFTTDetector CV_GFTT;
55 typedef cv::BriefDescriptorExtractor CV_BRIEF;
56 typedef cv::BRISK CV_BRISK;
57 typedef cv::gpu::SURF_GPU CV_SURF_GPU;
58 typedef cv::gpu::ORB_GPU CV_ORB_GPU;
59 typedef cv::gpu::FAST_GPU CV_FAST_GPU;
60 #else
61 namespace cv{
62 namespace xfeatures2d {
63 class FREAK;
64 class DAISY;
65 class BriefDescriptorExtractor;
66 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
67 class SIFT;
68 #endif
69 class SURF;
70 }
71 namespace cuda {
72 class FastFeatureDetector;
73 class ORB;
74 class SURF_CUDA;
75 }
76 }
77 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
78 typedef cv::xfeatures2d::SIFT CV_SIFT;
79 #else
80 typedef cv::SIFT CV_SIFT; // SIFT is back in features2d since 4.4.0 / 3.4.11
81 #endif
82 typedef cv::xfeatures2d::SURF CV_SURF;
83 typedef cv::FastFeatureDetector CV_FAST;
84 typedef cv::xfeatures2d::FREAK CV_FREAK;
85 typedef cv::xfeatures2d::DAISY CV_DAISY;
86 typedef cv::GFTTDetector CV_GFTT;
87 typedef cv::xfeatures2d::BriefDescriptorExtractor CV_BRIEF;
88 typedef cv::BRISK CV_BRISK;
89 typedef cv::ORB CV_ORB;
90 typedef cv::cuda::SURF_CUDA CV_SURF_GPU;
91 typedef cv::cuda::ORB CV_ORB_GPU;
92 typedef cv::cuda::FastFeatureDetector CV_FAST_GPU;
93 #endif
94 
95 namespace rtabmap {
96 
97 class ORBextractor;
98 class SPDetector;
99 
100 class Stereo;
101 #if CV_MAJOR_VERSION < 3
102 class CV_ORB;
103 #endif
104 
105 // Feature2D
107 public:
108  enum Type {kFeatureUndef=-1,
109  kFeatureSurf=0,
110  kFeatureSift=1,
111  kFeatureOrb=2,
112  kFeatureFastFreak=3,
113  kFeatureFastBrief=4,
114  kFeatureGfttFreak=5,
115  kFeatureGfttBrief=6,
116  kFeatureBrisk=7,
117  kFeatureGfttOrb=8, //new 0.10.11
118  kFeatureKaze=9, //new 0.13.2
119  kFeatureOrbOctree=10, //new 0.19.2
120  kFeatureSuperPointTorch=11, //new 0.19.7
121  kFeatureSurfFreak=12, //new 0.20.4
122  kFeatureGfttDaisy=13, //new 0.20.6
123  kFeatureSurfDaisy=14, //new 0.20.6
124  kFeaturePyDetector=15}; //new 0.20.8
125 
126  static std::string typeName(Type type)
127  {
128  switch(type){
129  case kFeatureSurf:
130  return "SURF";
131  case kFeatureSift:
132  return "SIFT";
133  case kFeatureOrb:
134  return "ORB";
135  case kFeatureFastFreak:
136  return "FAST+FREAK";
137  case kFeatureFastBrief:
138  return "FAST+BRIEF";
139  case kFeatureGfttFreak:
140  return "GFTT+Freak";
141  case kFeatureGfttBrief:
142  return "GFTT+Brief";
143  case kFeatureBrisk:
144  return "BRISK";
145  case kFeatureGfttOrb:
146  return "GFTT+ORB";
147  case kFeatureKaze:
148  return "KAZE";
149  case kFeatureOrbOctree:
150  return "ORB-OCTREE";
151  case kFeatureSuperPointTorch:
152  return "SUPERPOINT";
153  case kFeatureSurfFreak:
154  return "SURF+Freak";
155  case kFeatureGfttDaisy:
156  return "GFTT+Daisy";
157  case kFeatureSurfDaisy:
158  return "SURF+Daisy";
159  default:
160  return "Unknown";
161  }
162  }
163 
164  static Feature2D * create(const ParametersMap & parameters = ParametersMap());
165  static Feature2D * create(Feature2D::Type type, const ParametersMap & parameters = ParametersMap()); // for convenience
166 
167  static void filterKeypointsByDepth(
168  std::vector<cv::KeyPoint> & keypoints,
169  const cv::Mat & depth,
170  float minDepth,
171  float maxDepth);
172  static void filterKeypointsByDepth(
173  std::vector<cv::KeyPoint> & keypoints,
174  cv::Mat & descriptors,
175  const cv::Mat & depth,
176  float minDepth,
177  float maxDepth);
178  static void filterKeypointsByDepth(
179  std::vector<cv::KeyPoint> & keypoints,
180  cv::Mat & descriptors,
181  std::vector<cv::Point3f> & keypoints3D,
182  float minDepth,
183  float maxDepth);
184 
185  static void filterKeypointsByDisparity(
186  std::vector<cv::KeyPoint> & keypoints,
187  const cv::Mat & disparity,
188  float minDisparity);
189  static void filterKeypointsByDisparity(
190  std::vector<cv::KeyPoint> & keypoints,
191  cv::Mat & descriptors,
192  const cv::Mat & disparity,
193  float minDisparity);
194 
195  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints);
196  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints);
197  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors, int maxKeypoints);
198  static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints);
199  static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize, int gridRows, int gridCols);
200 
201  static cv::Rect computeRoi(const cv::Mat & image, const std::string & roiRatios);
202  static cv::Rect computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
203 
204  int getMaxFeatures() const {return maxFeatures_;}
205  float getMinDepth() const {return _minDepth;}
206  float getMaxDepth() const {return _maxDepth;}
207  int getGridRows() const {return gridRows_;}
208  int getGridCols() const {return gridCols_;}
209 
210 public:
211  virtual ~Feature2D();
212 
213  std::vector<cv::KeyPoint> generateKeypoints(
214  const cv::Mat & image,
215  const cv::Mat & mask = cv::Mat());
216  cv::Mat generateDescriptors(
217  const cv::Mat & image,
218  std::vector<cv::KeyPoint> & keypoints) const;
219  std::vector<cv::Point3f> generateKeypoints3D(
220  const SensorData & data,
221  const std::vector<cv::KeyPoint> & keypoints) const;
222 
223  virtual void parseParameters(const ParametersMap & parameters);
224  virtual const ParametersMap & getParameters() const {return parameters_;}
225  virtual Feature2D::Type getType() const = 0;
226 
227 protected:
228  Feature2D(const ParametersMap & parameters = ParametersMap());
229 
230 private:
231  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) = 0;
232  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
233 
234 private:
237  float _maxDepth; // 0=inf
238  float _minDepth;
239  std::vector<float> _roiRatios; // size 4
242  double _subPixEps;
245  // Stereo stuff
247 };
248 
249 //SURF
250 class RTABMAP_EXP SURF : public Feature2D
251 {
252 public:
253  SURF(const ParametersMap & parameters = ParametersMap());
254  virtual ~SURF();
255 
256  virtual void parseParameters(const ParametersMap & parameters);
257  virtual Feature2D::Type getType() const {return kFeatureSurf;}
258 
259 private:
260  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
261  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
262 
263 private:
267  bool extended_;
268  bool upright_;
271 
272  cv::Ptr<CV_SURF> _surf;
273  cv::Ptr<CV_SURF_GPU> _gpuSurf;
274 };
275 
276 //SIFT
277 class RTABMAP_EXP SIFT : public Feature2D
278 {
279 public:
280  SIFT(const ParametersMap & parameters = ParametersMap());
281  virtual ~SIFT();
282 
283  virtual void parseParameters(const ParametersMap & parameters);
284  virtual Feature2D::Type getType() const {return kFeatureSift;}
285 
286 private:
287  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
288  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
289 
290 private:
294  double sigma_;
295  bool rootSIFT_;
296 
297  cv::Ptr<CV_SIFT> _sift;
298 };
299 
300 //ORB
301 class RTABMAP_EXP ORB : public Feature2D
302 {
303 public:
304  ORB(const ParametersMap & parameters = ParametersMap());
305  virtual ~ORB();
306 
307  virtual void parseParameters(const ParametersMap & parameters);
308  virtual Feature2D::Type getType() const {return kFeatureOrb;}
309 
310 private:
311  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
312  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
313 
314 private:
316  int nLevels_;
319  int WTA_K_;
322  bool gpu_;
323 
326 
327  cv::Ptr<CV_ORB> _orb;
328  cv::Ptr<CV_ORB_GPU> _gpuOrb;
329 };
330 
331 //FAST
332 class RTABMAP_EXP FAST : public Feature2D
333 {
334 public:
335  FAST(const ParametersMap & parameters = ParametersMap());
336  virtual ~FAST();
337 
338  virtual void parseParameters(const ParametersMap & parameters);
339  virtual Feature2D::Type getType() const {return kFeatureUndef;}
340 
341 private:
342  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
343  virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector<cv::KeyPoint> &) const {return cv::Mat();}
344 
345 private:
348  bool gpu_;
354  int fastCV_;
355 
359  uint32_t* fastCVCorners_= NULL;
360  uint32_t* fastCVCornerScores_ = NULL;
361  void* fastCVTempBuf_ = NULL;
362 
363  cv::Ptr<cv::FeatureDetector> _fast;
364  cv::Ptr<CV_FAST_GPU> _gpuFast;
365 };
366 
367 //FAST_BRIEF
369 {
370 public:
371  FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
372  virtual ~FAST_BRIEF();
373 
374  virtual void parseParameters(const ParametersMap & parameters);
375  virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
376 
377 private:
378  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
379 
380 private:
381  int bytes_;
382 
383  cv::Ptr<CV_BRIEF> _brief;
384 };
385 
386 //FAST_FREAK
388 {
389 public:
390  FAST_FREAK(const ParametersMap & parameters = ParametersMap());
391  virtual ~FAST_FREAK();
392 
393  virtual void parseParameters(const ParametersMap & parameters);
394  virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
395 
396 private:
397  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
398 
399 private:
404 
405  cv::Ptr<CV_FREAK> _freak;
406 };
407 
408 //GFTT
409 class RTABMAP_EXP GFTT : public Feature2D
410 {
411 public:
412  GFTT(const ParametersMap & parameters = ParametersMap());
413  virtual ~GFTT();
414 
415  virtual void parseParameters(const ParametersMap & parameters);
416 
417 private:
418  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
419 
420 private:
422  double _minDistance;
425  double _k;
426 
427  cv::Ptr<CV_GFTT> _gftt;
428 };
429 
430 //GFTT_BRIEF
432 {
433 public:
434  GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
435  virtual ~GFTT_BRIEF();
436 
437  virtual void parseParameters(const ParametersMap & parameters);
438  virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
439 
440 private:
441  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
442 
443 private:
444  int bytes_;
445 
446  cv::Ptr<CV_BRIEF> _brief;
447 };
448 
449 //GFTT_FREAK
451 {
452 public:
453  GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
454  virtual ~GFTT_FREAK();
455 
456  virtual void parseParameters(const ParametersMap & parameters);
457  virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
458 
459 private:
460  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
461 
462 private:
467 
468  cv::Ptr<CV_FREAK> _freak;
469 };
470 
471 //SURF_FREAK
473 {
474 public:
475  SURF_FREAK(const ParametersMap & parameters = ParametersMap());
476  virtual ~SURF_FREAK();
477 
478  virtual void parseParameters(const ParametersMap & parameters);
479  virtual Feature2D::Type getType() const {return kFeatureSurfFreak;}
480 
481 private:
482  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
483 
484 private:
489 
490  cv::Ptr<CV_FREAK> _freak;
491 };
492 
493 //GFTT_ORB
494 class RTABMAP_EXP GFTT_ORB : public GFTT
495 {
496 public:
497  GFTT_ORB(const ParametersMap & parameters = ParametersMap());
498  virtual ~GFTT_ORB();
499 
500  virtual void parseParameters(const ParametersMap & parameters);
501  virtual Feature2D::Type getType() const {return kFeatureGfttOrb;}
502 
503 private:
504  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
505 
506 private:
508 };
509 
510 //BRISK
512 {
513 public:
514  BRISK(const ParametersMap & parameters = ParametersMap());
515  virtual ~BRISK();
516 
517  virtual void parseParameters(const ParametersMap & parameters);
518  virtual Feature2D::Type getType() const {return kFeatureBrisk;}
519 
520 private:
521  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
522  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
523 
524 private:
525  int thresh_;
526  int octaves_;
528 
529  cv::Ptr<CV_BRISK> brisk_;
530 };
531 
532 //KAZE
533 class RTABMAP_EXP KAZE : public Feature2D
534 {
535 public:
536  KAZE(const ParametersMap & parameters = ParametersMap());
537  virtual ~KAZE();
538 
539  virtual void parseParameters(const ParametersMap & parameters);
540  virtual Feature2D::Type getType() const { return kFeatureKaze; }
541 
542 private:
543  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
544  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
545 
546 private:
547  bool extended_;
548  bool upright_;
549  float threshold_;
553 
554 #if CV_MAJOR_VERSION > 2
555  cv::Ptr<cv::KAZE> kaze_;
556 #endif
557 };
558 
559 //ORB OCTREE
561 {
562 public:
563  ORBOctree(const ParametersMap & parameters = ParametersMap());
564  virtual ~ORBOctree();
565 
566  virtual void parseParameters(const ParametersMap & parameters);
567  virtual Feature2D::Type getType() const {return kFeatureOrbOctree;}
568 
569 private:
570  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
571  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
572 
573 private:
575  int nLevels_;
580 
581  cv::Ptr<ORBextractor> _orb;
582  cv::Mat descriptors_;
583 };
584 
585 //SuperPointTorch
587 {
588 public:
589  SuperPointTorch(const ParametersMap & parameters = ParametersMap());
590  virtual ~SuperPointTorch();
591 
592  virtual void parseParameters(const ParametersMap & parameters);
593  virtual Feature2D::Type getType() const { return kFeatureSuperPointTorch; }
594 
595 private:
596  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
597  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
598 
599  cv::Ptr<SPDetector> superPoint_;
600 
601  std::string path_;
602  float threshold_;
603  bool nms_;
605  bool cuda_;
606 };
607 
608 //GFTT_DAISY
610 {
611 public:
612  GFTT_DAISY(const ParametersMap & parameters = ParametersMap());
613  virtual ~GFTT_DAISY();
614 
615  virtual void parseParameters(const ParametersMap & parameters);
616  virtual Feature2D::Type getType() const {return kFeatureGfttDaisy;}
617 
618 private:
619  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
620 
621 private:
626 
627 #if CV_MAJOR_VERSION > 2
628  cv::Ptr<CV_DAISY> _daisy;
629 #endif
630 };
631 
632 //SURF_DAISY
634 {
635 public:
636  SURF_DAISY(const ParametersMap & parameters = ParametersMap());
637  virtual ~SURF_DAISY();
638 
639  virtual void parseParameters(const ParametersMap & parameters);
640  virtual Feature2D::Type getType() const {return kFeatureSurfDaisy;}
641 
642 private:
643  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
644 
645 private:
650 
651 #if CV_MAJOR_VERSION > 2
652  cv::Ptr<CV_DAISY> _daisy;
653 #endif
654 };
655 
656 }
657 
658 #endif /* FEATURES2D_H_ */
GLM_FUNC_DECL genIType mask(genIType const &count)
virtual Feature2D::Type getType() const
Definition: Features2d.h:540
#define NULL
int fastCVLastImageHeight_
Definition: Features2d.h:358
float getMinDepth() const
Definition: Features2d.h:205
int nOctaveLayers_
Definition: Features2d.h:551
virtual Feature2D::Type getType() const
Definition: Features2d.h:308
float getMaxDepth() const
Definition: Features2d.h:206
double gpuKeypointsRatio_
Definition: Features2d.h:349
double _qualityLevel
Definition: Features2d.h:421
int getGridRows() const
Definition: Features2d.h:207
virtual Feature2D::Type getType() const
Definition: Features2d.h:593
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:405
cv::SIFT CV_SIFT
Definition: Features2d.h:50
double edgeThreshold_
Definition: Features2d.h:293
cv::Ptr< CV_ORB > _orb
Definition: Features2d.h:327
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:468
float scaleFactor_
Definition: Features2d.h:315
data
cv::BriefDescriptorExtractor CV_BRIEF
Definition: Features2d.h:55
cv::Ptr< ORBextractor > _orb
Definition: Features2d.h:581
bool nonmaxSuppression_
Definition: Features2d.h:347
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
double contrastThreshold_
Definition: Features2d.h:292
virtual Feature2D::Type getType() const
Definition: Features2d.h:284
std::vector< float > _roiRatios
Definition: Features2d.h:239
int nOctaveLayers_
Definition: Features2d.h:291
virtual Feature2D::Type getType() const
Definition: Features2d.h:640
cv::Ptr< CV_BRISK > brisk_
Definition: Features2d.h:529
cv::Ptr< CV_ORB_GPU > _gpuOrb
Definition: Features2d.h:328
virtual Feature2D::Type getType() const
Definition: Features2d.h:339
Definition: Features2d.h:41
cv::FastFeatureDetector CV_FAST
Definition: Features2d.h:52
cv::SURF CV_SURF
Definition: Features2d.h:51
virtual Feature2D::Type getType() const
Definition: Features2d.h:567
cv::Ptr< CV_FAST_GPU > _gpuFast
Definition: Features2d.h:364
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
cv::BRISK CV_BRISK
Definition: Features2d.h:56
cv::Ptr< SPDetector > superPoint_
Definition: Features2d.h:599
virtual Feature2D::Type getType() const
Definition: Features2d.h:479
virtual Feature2D::Type getType() const
Definition: Features2d.h:616
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:490
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: util2d.cpp:1113
virtual Feature2D::Type getType() const
Definition: Features2d.h:438
virtual Feature2D::Type getType() const
Definition: Features2d.h:518
static std::string typeName(Type type)
Definition: Features2d.h:126
cv::gpu::SURF_GPU CV_SURF_GPU
Definition: Features2d.h:57
int fastThreshold_
Definition: Features2d.h:324
float patternScale_
Definition: Features2d.h:527
double sigma_
Definition: Features2d.h:294
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:383
virtual Feature2D::Type getType() const
Definition: Features2d.h:457
detail::uint32 uint32_t
Definition: fwd.hpp:916
cv::Mat descriptors_
Definition: Features2d.h:582
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector< cv::KeyPoint > &) const
Definition: Features2d.h:343
cv::Ptr< CV_SURF > _surf
Definition: Features2d.h:272
virtual Feature2D::Type getType() const
Definition: Features2d.h:257
virtual Feature2D::Type getType() const
Definition: Features2d.h:394
int nOctaveLayers_
Definition: Features2d.h:266
float gpuKeypointsRatio_
Definition: Features2d.h:269
cv::FREAK CV_FREAK
Definition: Features2d.h:53
virtual Feature2D::Type getType() const
Definition: Features2d.h:375
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:446
cv::Ptr< CV_SIFT > _sift
Definition: Features2d.h:297
int fastCVMaxFeatures_
Definition: Features2d.h:357
float threshold_
Definition: Features2d.h:549
bool fastCVinit_
Definition: Features2d.h:356
double _minDistance
Definition: Features2d.h:422
bool gpuVersion_
Definition: Features2d.h:270
virtual const ParametersMap & getParameters() const
Definition: Features2d.h:224
int edgeThreshold_
Definition: Features2d.h:317
cv::gpu::ORB_GPU CV_ORB_GPU
Definition: Features2d.h:58
cv::GFTTDetector CV_GFTT
Definition: Features2d.h:54
cv::gpu::FAST_GPU CV_FAST_GPU
Definition: Features2d.h:59
int getMaxFeatures() const
Definition: Features2d.h:204
bool nonmaxSuppresion_
Definition: Features2d.h:325
cv::Ptr< cv::FeatureDetector > _fast
Definition: Features2d.h:363
double hessianThreshold_
Definition: Features2d.h:264
virtual Feature2D::Type getType() const
Definition: Features2d.h:501
cv::Ptr< CV_GFTT > _gftt
Definition: Features2d.h:427
ParametersMap parameters_
Definition: Features2d.h:235
bool _useHarrisDetector
Definition: Features2d.h:424
cv::Ptr< CV_SURF_GPU > _gpuSurf
Definition: Features2d.h:273
int getGridCols() const
Definition: Features2d.h:208


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28