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/rtabmap_core_export.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
106 class RTABMAP_CORE_EXPORT 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, const cv::Size & imageSize = cv::Size(), bool ssc = false);
196  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
197  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
198  static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
199  static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize, int gridRows, int gridCols, bool ssc = false);
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  bool getSSC() const {return SSC_;}
206  float getMinDepth() const {return _minDepth;}
207  float getMaxDepth() const {return _maxDepth;}
208  int getGridRows() const {return gridRows_;}
209  int getGridCols() const {return gridCols_;}
210 
211 public:
212  virtual ~Feature2D();
213 
214  std::vector<cv::KeyPoint> generateKeypoints(
215  const cv::Mat & image,
216  const cv::Mat & mask = cv::Mat());
217  cv::Mat generateDescriptors(
218  const cv::Mat & image,
219  std::vector<cv::KeyPoint> & keypoints) const;
220  std::vector<cv::Point3f> generateKeypoints3D(
221  const SensorData & data,
222  const std::vector<cv::KeyPoint> & keypoints) const;
223 
224  virtual void parseParameters(const ParametersMap & parameters);
225  virtual const ParametersMap & getParameters() const {return parameters_;}
226  virtual Feature2D::Type getType() const = 0;
227 
228 protected:
229  Feature2D(const ParametersMap & parameters = ParametersMap());
230 
231 private:
232  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) = 0;
233  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
234 
235 private:
238  bool SSC_;
239  float _maxDepth; // 0=inf
240  float _minDepth;
241  std::vector<float> _roiRatios; // size 4
244  double _subPixEps;
247  // Stereo stuff
249 };
250 
251 //SURF
252 class RTABMAP_CORE_EXPORT SURF : public Feature2D
253 {
254 public:
255  SURF(const ParametersMap & parameters = ParametersMap());
256  virtual ~SURF();
257 
258  virtual void parseParameters(const ParametersMap & parameters);
259  virtual Feature2D::Type getType() const {return kFeatureSurf;}
260 
261 private:
262  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
263  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
264 
265 private:
269  bool extended_;
270  bool upright_;
273 
274  cv::Ptr<CV_SURF> _surf;
275  cv::Ptr<CV_SURF_GPU> _gpuSurf;
276 };
277 
278 //SIFT
279 class RTABMAP_CORE_EXPORT SIFT : public Feature2D
280 {
281 public:
282  SIFT(const ParametersMap & parameters = ParametersMap());
283  virtual ~SIFT();
284 
285  virtual void parseParameters(const ParametersMap & parameters);
286  virtual Feature2D::Type getType() const {return kFeatureSift;}
287 
288 private:
289  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
290  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
291 
292 private:
296  double sigma_;
297  bool rootSIFT_;
298 
299  cv::Ptr<CV_SIFT> _sift;
300 };
301 
302 //ORB
303 class RTABMAP_CORE_EXPORT ORB : public Feature2D
304 {
305 public:
306  ORB(const ParametersMap & parameters = ParametersMap());
307  virtual ~ORB();
308 
309  virtual void parseParameters(const ParametersMap & parameters);
310  virtual Feature2D::Type getType() const {return kFeatureOrb;}
311 
312 private:
313  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
314  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
315 
316 private:
318  int nLevels_;
321  int WTA_K_;
324  bool gpu_;
325 
328 
329  cv::Ptr<CV_ORB> _orb;
330  cv::Ptr<CV_ORB_GPU> _gpuOrb;
331 };
332 
333 //FAST
334 class RTABMAP_CORE_EXPORT FAST : public Feature2D
335 {
336 public:
337  FAST(const ParametersMap & parameters = ParametersMap());
338  virtual ~FAST();
339 
340  virtual void parseParameters(const ParametersMap & parameters);
341  virtual Feature2D::Type getType() const {return kFeatureUndef;}
342 
343 private:
344  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
345  virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector<cv::KeyPoint> &) const {return cv::Mat();}
346 
347 private:
350  bool gpu_;
356  int fastCV_;
357 
361  uint32_t* fastCVCorners_= NULL;
362  uint32_t* fastCVCornerScores_ = NULL;
363  void* fastCVTempBuf_ = NULL;
364 
365  cv::Ptr<cv::FeatureDetector> _fast;
366  cv::Ptr<CV_FAST_GPU> _gpuFast;
367 };
368 
369 //FAST_BRIEF
370 class RTABMAP_CORE_EXPORT FAST_BRIEF : public FAST
371 {
372 public:
373  FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
374  virtual ~FAST_BRIEF();
375 
376  virtual void parseParameters(const ParametersMap & parameters);
377  virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
378 
379 private:
380  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
381 
382 private:
383  int bytes_;
384 
385  cv::Ptr<CV_BRIEF> _brief;
386 };
387 
388 //FAST_FREAK
389 class RTABMAP_CORE_EXPORT FAST_FREAK : public FAST
390 {
391 public:
392  FAST_FREAK(const ParametersMap & parameters = ParametersMap());
393  virtual ~FAST_FREAK();
394 
395  virtual void parseParameters(const ParametersMap & parameters);
396  virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
397 
398 private:
399  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
400 
401 private:
406 
407  cv::Ptr<CV_FREAK> _freak;
408 };
409 
410 //GFTT
411 class RTABMAP_CORE_EXPORT GFTT : public Feature2D
412 {
413 public:
414  GFTT(const ParametersMap & parameters = ParametersMap());
415  virtual ~GFTT();
416 
417  virtual void parseParameters(const ParametersMap & parameters);
418 
419 private:
420  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
421 
422 private:
424  double _minDistance;
427  double _k;
428 
429  cv::Ptr<CV_GFTT> _gftt;
430 };
431 
432 //GFTT_BRIEF
433 class RTABMAP_CORE_EXPORT GFTT_BRIEF : public GFTT
434 {
435 public:
436  GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
437  virtual ~GFTT_BRIEF();
438 
439  virtual void parseParameters(const ParametersMap & parameters);
440  virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
441 
442 private:
443  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
444 
445 private:
446  int bytes_;
447 
448  cv::Ptr<CV_BRIEF> _brief;
449 };
450 
451 //GFTT_FREAK
452 class RTABMAP_CORE_EXPORT GFTT_FREAK : public GFTT
453 {
454 public:
455  GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
456  virtual ~GFTT_FREAK();
457 
458  virtual void parseParameters(const ParametersMap & parameters);
459  virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
460 
461 private:
462  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
463 
464 private:
469 
470  cv::Ptr<CV_FREAK> _freak;
471 };
472 
473 //SURF_FREAK
474 class RTABMAP_CORE_EXPORT SURF_FREAK : public SURF
475 {
476 public:
477  SURF_FREAK(const ParametersMap & parameters = ParametersMap());
478  virtual ~SURF_FREAK();
479 
480  virtual void parseParameters(const ParametersMap & parameters);
481  virtual Feature2D::Type getType() const {return kFeatureSurfFreak;}
482 
483 private:
484  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
485 
486 private:
491 
492  cv::Ptr<CV_FREAK> _freak;
493 };
494 
495 //GFTT_ORB
496 class RTABMAP_CORE_EXPORT GFTT_ORB : public GFTT
497 {
498 public:
499  GFTT_ORB(const ParametersMap & parameters = ParametersMap());
500  virtual ~GFTT_ORB();
501 
502  virtual void parseParameters(const ParametersMap & parameters);
503  virtual Feature2D::Type getType() const {return kFeatureGfttOrb;}
504 
505 private:
506  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
507 
508 private:
510 };
511 
512 //BRISK
513 class RTABMAP_CORE_EXPORT BRISK : public Feature2D
514 {
515 public:
516  BRISK(const ParametersMap & parameters = ParametersMap());
517  virtual ~BRISK();
518 
519  virtual void parseParameters(const ParametersMap & parameters);
520  virtual Feature2D::Type getType() const {return kFeatureBrisk;}
521 
522 private:
523  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
524  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
525 
526 private:
527  int thresh_;
528  int octaves_;
530 
531  cv::Ptr<CV_BRISK> brisk_;
532 };
533 
534 //KAZE
535 class RTABMAP_CORE_EXPORT KAZE : public Feature2D
536 {
537 public:
538  KAZE(const ParametersMap & parameters = ParametersMap());
539  virtual ~KAZE();
540 
541  virtual void parseParameters(const ParametersMap & parameters);
542  virtual Feature2D::Type getType() const { return kFeatureKaze; }
543 
544 private:
545  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
546  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
547 
548 private:
549  bool extended_;
550  bool upright_;
551  float threshold_;
555 
556 #if CV_MAJOR_VERSION > 2
557  cv::Ptr<cv::KAZE> kaze_;
558 #endif
559 };
560 
561 //ORB OCTREE
562 class RTABMAP_CORE_EXPORT ORBOctree : public Feature2D
563 {
564 public:
565  ORBOctree(const ParametersMap & parameters = ParametersMap());
566  virtual ~ORBOctree();
567 
568  virtual void parseParameters(const ParametersMap & parameters);
569  virtual Feature2D::Type getType() const {return kFeatureOrbOctree;}
570 
571 private:
572  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
573  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
574 
575 private:
577  int nLevels_;
582 
583  cv::Ptr<ORBextractor> _orb;
584  cv::Mat descriptors_;
585 };
586 
587 //SuperPointTorch
588 class RTABMAP_CORE_EXPORT SuperPointTorch : public Feature2D
589 {
590 public:
591  SuperPointTorch(const ParametersMap & parameters = ParametersMap());
592  virtual ~SuperPointTorch();
593 
594  virtual void parseParameters(const ParametersMap & parameters);
595  virtual Feature2D::Type getType() const { return kFeatureSuperPointTorch; }
596 
597 private:
598  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
599  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
600 
601  cv::Ptr<SPDetector> superPoint_;
602 
603  std::string path_;
604  float threshold_;
605  bool nms_;
607  bool cuda_;
608 };
609 
610 //GFTT_DAISY
611 class RTABMAP_CORE_EXPORT GFTT_DAISY : public GFTT
612 {
613 public:
614  GFTT_DAISY(const ParametersMap & parameters = ParametersMap());
615  virtual ~GFTT_DAISY();
616 
617  virtual void parseParameters(const ParametersMap & parameters);
618  virtual Feature2D::Type getType() const {return kFeatureGfttDaisy;}
619 
620 private:
621  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
622 
623 private:
628 
629 #if CV_MAJOR_VERSION > 2
630  cv::Ptr<CV_DAISY> _daisy;
631 #endif
632 };
633 
634 //SURF_DAISY
635 class RTABMAP_CORE_EXPORT SURF_DAISY : public SURF
636 {
637 public:
638  SURF_DAISY(const ParametersMap & parameters = ParametersMap());
639  virtual ~SURF_DAISY();
640 
641  virtual void parseParameters(const ParametersMap & parameters);
642  virtual Feature2D::Type getType() const {return kFeatureSurfDaisy;}
643 
644 private:
645  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
646 
647 private:
652 
653 #if CV_MAJOR_VERSION > 2
654  cv::Ptr<CV_DAISY> _daisy;
655 #endif
656 };
657 
658 }
659 
660 #endif /* FEATURES2D_H_ */
rtabmap::SensorData
Definition: SensorData.h:51
create
ADT create(const Signature &signature)
rtabmap::FAST_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:403
rtabmap::SURF_DAISY::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:642
rtabmap::GFTT_BRIEF::bytes_
int bytes_
Definition: Features2d.h:446
rtabmap::util2d::computeRoi
cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: util2d.cpp:1113
rtabmap::GFTT_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:465
rtabmap::ORBOctree::patchSize_
int patchSize_
Definition: Features2d.h:578
rtabmap::FAST::gridCols_
int gridCols_
Definition: Features2d.h:355
glm::mask
GLM_FUNC_DECL genIType mask(genIType const &count)
rtabmap::ORB::_orb
cv::Ptr< CV_ORB > _orb
Definition: Features2d.h:329
rtabmap::KAZE::extended_
bool extended_
Definition: Features2d.h:549
rtabmap::GFTT_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:625
rtabmap::SURF_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:481
rtabmap::FAST_BRIEF::bytes_
int bytes_
Definition: Features2d.h:383
rtabmap::ORBOctree
Definition: Features2d.h:562
rtabmap::GFTT_ORB::_orb
ORB _orb
Definition: Features2d.h:509
rtabmap::FAST_BRIEF
Definition: Features2d.h:370
rtabmap::SURF::nOctaves_
int nOctaves_
Definition: Features2d.h:267
rtabmap::GFTT::_useHarrisDetector
bool _useHarrisDetector
Definition: Features2d.h:426
rtabmap::GFTT_BRIEF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:440
rtabmap::FAST
Definition: Features2d.h:334
rtabmap::GFTT_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:468
rtabmap::SuperPointTorch::superPoint_
cv::Ptr< SPDetector > superPoint_
Definition: Features2d.h:601
rtabmap::ORBOctree::_orb
cv::Ptr< ORBextractor > _orb
Definition: Features2d.h:583
CV_FREAK
cv::FREAK CV_FREAK
Definition: Features2d.h:53
rtabmap::FAST::maxThreshold_
int maxThreshold_
Definition: Features2d.h:353
rtabmap::ORB::patchSize_
int patchSize_
Definition: Features2d.h:323
uint32_t
::uint32_t uint32_t
rtabmap::SURF_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:492
rtabmap::SURF::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:268
rtabmap::KAZE::nOctaves_
int nOctaves_
Definition: Features2d.h:552
rtabmap::ORBOctree::nLevels_
int nLevels_
Definition: Features2d.h:577
SensorData.h
rtabmap::GFTT_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:459
rtabmap::Stereo
Definition: Stereo.h:38
rtabmap::ORB::scaleFactor_
float scaleFactor_
Definition: Features2d.h:317
rtabmap::GFTT_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:448
rtabmap::SURF
Definition: Features2d.h:252
rtabmap::KAZE::threshold_
float threshold_
Definition: Features2d.h:551
type
rtabmap::Feature2D::getSSC
bool getSSC() const
Definition: Features2d.h:205
rtabmap::FAST_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:402
rtabmap::BRISK
Definition: Features2d.h:513
CV_SIFT
cv::SIFT CV_SIFT
Definition: Features2d.h:50
rtabmap::ORBOctree::fastMinThreshold_
int fastMinThreshold_
Definition: Features2d.h:581
rtabmap::GFTT::_qualityLevel
double _qualityLevel
Definition: Features2d.h:423
rtabmap::FAST::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:341
rtabmap::GFTT::_gftt
cv::Ptr< CV_GFTT > _gftt
Definition: Features2d.h:429
CV_BRISK
cv::BRISK CV_BRISK
Definition: Features2d.h:56
rtabmap::FAST::fastCVLastImageHeight_
int fastCVLastImageHeight_
Definition: Features2d.h:360
rtabmap::Feature2D::_subPixIterations
int _subPixIterations
Definition: Features2d.h:243
rtabmap::SURF::hessianThreshold_
double hessianThreshold_
Definition: Features2d.h:266
rtabmap::SIFT::sigma_
double sigma_
Definition: Features2d.h:296
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::ORB::_gpuOrb
cv::Ptr< CV_ORB_GPU > _gpuOrb
Definition: Features2d.h:330
rtabmap::FAST::gpuKeypointsRatio_
double gpuKeypointsRatio_
Definition: Features2d.h:351
rtabmap::BRISK::octaves_
int octaves_
Definition: Features2d.h:528
rtabmap::Feature2D::typeName
static std::string typeName(Type type)
Definition: Features2d.h:126
rtabmap::BRISK::thresh_
int thresh_
Definition: Features2d.h:527
rtabmap::Feature2D::getParameters
virtual const ParametersMap & getParameters() const
Definition: Features2d.h:225
rtabmap::ORB::nLevels_
int nLevels_
Definition: Features2d.h:318
rtabmap::FAST_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:396
Parameters.h
rtabmap::SURF::_gpuSurf
cv::Ptr< CV_SURF_GPU > _gpuSurf
Definition: Features2d.h:275
rtabmap::ORBOctree::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:569
rtabmap::Feature2D::gridRows_
int gridRows_
Definition: Features2d.h:245
rtabmap::FAST_FREAK
Definition: Features2d.h:389
rtabmap::GFTT_DAISY::patternScale_
float patternScale_
Definition: Features2d.h:626
rtabmap::ORB::gpu_
bool gpu_
Definition: Features2d.h:324
rtabmap::FAST_BRIEF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:377
rtabmap::FAST_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:405
rtabmap::FAST::gpu_
bool gpu_
Definition: Features2d.h:350
rtabmap::KAZE::diffusivity_
int diffusivity_
Definition: Features2d.h:554
rtabmap::FAST::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector< cv::KeyPoint > &) const
Definition: Features2d.h:345
rtabmap::ORB::scoreType_
int scoreType_
Definition: Features2d.h:322
rtabmap::Feature2D::gridCols_
int gridCols_
Definition: Features2d.h:246
rtabmap::SIFT
Definition: Features2d.h:279
rtabmap::GFTT_ORB::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:503
CV_SURF
cv::SURF CV_SURF
Definition: Features2d.h:51
rtabmap::KAZE::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:553
CV_FAST
cv::FastFeatureDetector CV_FAST
Definition: Features2d.h:52
rtabmap::Feature2D::getMaxFeatures
int getMaxFeatures() const
Definition: Features2d.h:204
rtabmap::ORB::fastThreshold_
int fastThreshold_
Definition: Features2d.h:326
rtabmap::Feature2D::_minDepth
float _minDepth
Definition: Features2d.h:240
rtabmap::Feature2D::_stereo
Stereo * _stereo
Definition: Features2d.h:248
rtabmap::GFTT_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:627
rtabmap::FAST::fastCV_
int fastCV_
Definition: Features2d.h:356
rtabmap::SuperPointTorch
Definition: Features2d.h:588
CV_BRIEF
cv::BriefDescriptorExtractor CV_BRIEF
Definition: Features2d.h:55
rtabmap::Feature2D::getMinDepth
float getMinDepth() const
Definition: Features2d.h:206
rtabmap::GFTT_ORB
Definition: Features2d.h:496
rtabmap::SuperPointTorch::nms_
bool nms_
Definition: Features2d.h:605
rtabmap::BRISK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:520
rtabmap::BRISK::brisk_
cv::Ptr< CV_BRISK > brisk_
Definition: Features2d.h:531
rtabmap::FAST::_fast
cv::Ptr< cv::FeatureDetector > _fast
Definition: Features2d.h:365
rtabmap::Feature2D
Definition: Features2d.h:106
rtabmap::SURF::extended_
bool extended_
Definition: Features2d.h:269
rtabmap::SuperPointTorch::path_
std::string path_
Definition: Features2d.h:603
rtabmap::SuperPointTorch::minDistance_
int minDistance_
Definition: Features2d.h:606
rtabmap::Feature2D::Type
Type
Definition: Features2d.h:108
rtabmap::Feature2D::getMaxDepth
float getMaxDepth() const
Definition: Features2d.h:207
rtabmap::SIFT::rootSIFT_
bool rootSIFT_
Definition: Features2d.h:297
rtabmap::BRISK::patternScale_
float patternScale_
Definition: Features2d.h:529
rtabmap::GFTT_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:624
rtabmap::Feature2D::getGridCols
int getGridCols() const
Definition: Features2d.h:209
rtabmap::SURF_DAISY
Definition: Features2d.h:635
rtabmap::FAST::minThreshold_
int minThreshold_
Definition: Features2d.h:352
rtabmap::FAST_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:404
rtabmap::SuperPointTorch::threshold_
float threshold_
Definition: Features2d.h:604
rtabmap::SIFT::_sift
cv::Ptr< CV_SIFT > _sift
Definition: Features2d.h:299
rtabmap::FAST::nonmaxSuppression_
bool nonmaxSuppression_
Definition: Features2d.h:349
rtabmap::SIFT::contrastThreshold_
double contrastThreshold_
Definition: Features2d.h:294
rtabmap::Feature2D::_maxDepth
float _maxDepth
Definition: Features2d.h:239
rtabmap::GFTT_DAISY::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:618
rtabmap::SURF_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:488
rtabmap::GFTT_BRIEF
Definition: Features2d.h:433
rtabmap::Feature2D::getGridRows
int getGridRows() const
Definition: Features2d.h:208
rtabmap::SURF_DAISY::patternScale_
float patternScale_
Definition: Features2d.h:650
rtabmap::Feature2D::_roiRatios
std::vector< float > _roiRatios
Definition: Features2d.h:241
rtabmap::SURF::_surf
cv::Ptr< CV_SURF > _surf
Definition: Features2d.h:274
rtabmap::KAZE::upright_
bool upright_
Definition: Features2d.h:550
rtabmap::GFTT
Definition: Features2d.h:411
CV_SURF_GPU
cv::gpu::SURF_GPU CV_SURF_GPU
Definition: Features2d.h:57
rtabmap::GFTT_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:467
rtabmap::Feature2D::parameters_
ParametersMap parameters_
Definition: Features2d.h:236
rtabmap::SURF_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:489
rtabmap::SURF::gpuKeypointsRatio_
float gpuKeypointsRatio_
Definition: Features2d.h:271
rtabmap::Feature2D::_subPixWinSize
int _subPixWinSize
Definition: Features2d.h:242
rtabmap::SURF_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:648
rtabmap::SURF_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:649
rtabmap::SIFT::edgeThreshold_
double edgeThreshold_
Definition: Features2d.h:295
rtabmap::ORB::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:319
CV_ORB_GPU
cv::gpu::ORB_GPU CV_ORB_GPU
Definition: Features2d.h:58
rtabmap::GFTT_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:470
rtabmap::SuperPointTorch::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:595
rtabmap::ORBOctree::scaleFactor_
float scaleFactor_
Definition: Features2d.h:576
rtabmap::FAST::fastCVMaxFeatures_
int fastCVMaxFeatures_
Definition: Features2d.h:359
rtabmap::SURF_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:490
rtabmap::GFTT_DAISY
Definition: Features2d.h:611
rtabmap::ORB::WTA_K_
int WTA_K_
Definition: Features2d.h:321
rtabmap::ORB::nonmaxSuppresion_
bool nonmaxSuppresion_
Definition: Features2d.h:327
rtabmap::Feature2D::SSC_
bool SSC_
Definition: Features2d.h:238
rtabmap::FAST::gridRows_
int gridRows_
Definition: Features2d.h:354
rtabmap::ORBOctree::fastThreshold_
int fastThreshold_
Definition: Features2d.h:580
rtabmap::KAZE::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:542
rtabmap::ORBOctree::descriptors_
cv::Mat descriptors_
Definition: Features2d.h:584
rtabmap::GFTT_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:466
rtabmap::GFTT::_k
double _k
Definition: Features2d.h:427
cv
Definition: Features2d.h:41
rtabmap::FAST::threshold_
int threshold_
Definition: Features2d.h:348
rtabmap::SuperPointTorch::cuda_
bool cuda_
Definition: Features2d.h:607
rtabmap::Feature2D::maxFeatures_
int maxFeatures_
Definition: Features2d.h:237
rtabmap::SURF::gpuVersion_
bool gpuVersion_
Definition: Features2d.h:272
CV_GFTT
cv::GFTTDetector CV_GFTT
Definition: Features2d.h:54
rtabmap::ORB
Definition: Features2d.h:303
rtabmap::SIFT::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:293
rtabmap::GFTT::_blockSize
int _blockSize
Definition: Features2d.h:425
NULL
#define NULL
rtabmap::SURF_FREAK
Definition: Features2d.h:474
gpu
GpuHelper gpu
rtabmap::SURF_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:651
rtabmap::SIFT::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:286
rtabmap::FAST_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:407
rtabmap::SURF::upright_
bool upright_
Definition: Features2d.h:270
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::ORB::firstLevel_
int firstLevel_
Definition: Features2d.h:320
rtabmap::FAST_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:385
rtabmap::ORBOctree::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:579
rtabmap::KAZE
Definition: Features2d.h:535
rtabmap::SURF_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:487
rtabmap::ORB::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:310
rtabmap::GFTT_FREAK
Definition: Features2d.h:452
rtabmap::GFTT::_minDistance
double _minDistance
Definition: Features2d.h:424
rtabmap::Feature2D::_subPixEps
double _subPixEps
Definition: Features2d.h:244
rtabmap::FAST::_gpuFast
cv::Ptr< CV_FAST_GPU > _gpuFast
Definition: Features2d.h:366
rtabmap::SURF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:259
CV_FAST_GPU
cv::gpu::FAST_GPU CV_FAST_GPU
Definition: Features2d.h:59
rtabmap::FAST::fastCVinit_
bool fastCVinit_
Definition: Features2d.h:358


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:27