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>
37 #include <numeric>
40 
41 #if CV_MAJOR_VERSION < 3
42 namespace cv{
43 class SURF;
44 class SIFT;
45 namespace gpu {
46  class SURF_GPU;
47  class ORB_GPU;
48  class FAST_GPU;
49  class GoodFeaturesToTrackDetector_GPU;
50 }
51 }
52 typedef cv::SIFT CV_SIFT;
53 typedef cv::SURF CV_SURF;
54 typedef cv::FastFeatureDetector CV_FAST;
55 typedef cv::FREAK CV_FREAK;
56 typedef cv::GFTTDetector CV_GFTT;
57 typedef cv::BriefDescriptorExtractor CV_BRIEF;
58 typedef cv::BRISK CV_BRISK;
59 typedef cv::gpu::SURF_GPU CV_SURF_GPU;
60 typedef cv::gpu::ORB_GPU CV_ORB_GPU;
61 typedef cv::gpu::FAST_GPU CV_FAST_GPU;
62 typedef cv::gpu::GoodFeaturesToTrackDetector_GPU CV_GFTT_GPU;
63 #else
64 namespace cv{
65 namespace xfeatures2d {
66 class FREAK;
67 class DAISY;
68 class BriefDescriptorExtractor;
69 #if (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
70 class SIFT;
71 #endif
72 class SURF;
73 }
74 namespace cuda {
75 class FastFeatureDetector;
76 class ORB;
77 class SURF_CUDA;
78 class CornersDetector;
79 }
80 }
81 #if (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
82 typedef cv::xfeatures2d::SIFT CV_SIFT;
83 #else
84 typedef cv::SIFT CV_SIFT; // SIFT is back in features2d since 4.4.0 / 3.4.11
85 #endif
86 typedef cv::xfeatures2d::SURF CV_SURF;
87 typedef cv::FastFeatureDetector CV_FAST;
88 typedef cv::xfeatures2d::FREAK CV_FREAK;
89 typedef cv::xfeatures2d::DAISY CV_DAISY;
90 typedef cv::GFTTDetector CV_GFTT;
91 typedef cv::xfeatures2d::BriefDescriptorExtractor CV_BRIEF;
92 typedef cv::BRISK CV_BRISK;
93 typedef cv::ORB CV_ORB;
94 typedef cv::cuda::SURF_CUDA CV_SURF_GPU;
95 typedef cv::cuda::ORB CV_ORB_GPU;
96 typedef cv::cuda::FastFeatureDetector CV_FAST_GPU;
97 typedef cv::cuda::CornersDetector CV_GFTT_GPU;
98 #endif
99 
100 // CudaSift fork: https://github.com/matlabbe/CudaSift
101 class SiftData;
102 
103 namespace rtabmap {
104 
105 class ORBextractor;
106 class SPDetector;
107 
108 class Stereo;
109 #if CV_MAJOR_VERSION < 3
110 class CV_ORB;
111 #endif
112 
113 // Feature2D
114 class RTABMAP_CORE_EXPORT Feature2D {
115 public:
116  enum Type {kFeatureUndef=-1,
117  kFeatureSurf=0,
118  kFeatureSift=1,
119  kFeatureOrb=2,
120  kFeatureFastFreak=3,
121  kFeatureFastBrief=4,
122  kFeatureGfttFreak=5,
123  kFeatureGfttBrief=6,
124  kFeatureBrisk=7,
125  kFeatureGfttOrb=8, //new 0.10.11
126  kFeatureKaze=9, //new 0.13.2
127  kFeatureOrbOctree=10, //new 0.19.2
128  kFeatureSuperPointTorch=11, //new 0.19.7
129  kFeatureSurfFreak=12, //new 0.20.4
130  kFeatureGfttDaisy=13, //new 0.20.6
131  kFeatureSurfDaisy=14, //new 0.20.6
132  kFeaturePyDetector=15}; //new 0.20.8
133 
134  static std::string typeName(Type type)
135  {
136  switch(type){
137  case kFeatureSurf:
138  return "SURF";
139  case kFeatureSift:
140  return "SIFT";
141  case kFeatureOrb:
142  return "ORB";
143  case kFeatureFastFreak:
144  return "FAST+FREAK";
145  case kFeatureFastBrief:
146  return "FAST+BRIEF";
147  case kFeatureGfttFreak:
148  return "GFTT+Freak";
149  case kFeatureGfttBrief:
150  return "GFTT+Brief";
151  case kFeatureBrisk:
152  return "BRISK";
153  case kFeatureGfttOrb:
154  return "GFTT+ORB";
155  case kFeatureKaze:
156  return "KAZE";
157  case kFeatureOrbOctree:
158  return "ORB-OCTREE";
159  case kFeatureSuperPointTorch:
160  return "SUPERPOINT";
161  case kFeatureSurfFreak:
162  return "SURF+Freak";
163  case kFeatureGfttDaisy:
164  return "GFTT+Daisy";
165  case kFeatureSurfDaisy:
166  return "SURF+Daisy";
167  default:
168  return "Unknown";
169  }
170  }
171 
172  static Feature2D * create(const ParametersMap & parameters = ParametersMap());
173  static Feature2D * create(Feature2D::Type type, const ParametersMap & parameters = ParametersMap()); // for convenience
174 
175  static void filterKeypointsByDepth(
176  std::vector<cv::KeyPoint> & keypoints,
177  const cv::Mat & depth,
178  float minDepth,
179  float maxDepth);
180  static void filterKeypointsByDepth(
181  std::vector<cv::KeyPoint> & keypoints,
182  cv::Mat & descriptors,
183  const cv::Mat & depth,
184  float minDepth,
185  float maxDepth);
186  static void filterKeypointsByDepth(
187  std::vector<cv::KeyPoint> & keypoints,
188  cv::Mat & descriptors,
189  std::vector<cv::Point3f> & keypoints3D,
190  float minDepth,
191  float maxDepth);
192 
193  static void filterKeypointsByDisparity(
194  std::vector<cv::KeyPoint> & keypoints,
195  const cv::Mat & disparity,
196  float minDisparity);
197  static void filterKeypointsByDisparity(
198  std::vector<cv::KeyPoint> & keypoints,
199  cv::Mat & descriptors,
200  const cv::Mat & disparity,
201  float minDisparity);
202 
203  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
204  static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
205  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);
206  static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize = cv::Size(), bool ssc = false);
207  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);
208 
209  static cv::Rect computeRoi(const cv::Mat & image, const std::string & roiRatios);
210  static cv::Rect computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
211 
212  int getMaxFeatures() const {return maxFeatures_;}
213  bool getSSC() const {return SSC_;}
214  float getMinDepth() const {return _minDepth;}
215  float getMaxDepth() const {return _maxDepth;}
216  int getGridRows() const {return gridRows_;}
217  int getGridCols() const {return gridCols_;}
218 
219 public:
220  virtual ~Feature2D();
221 
222  std::vector<cv::KeyPoint> generateKeypoints(
223  const cv::Mat & image,
224  const cv::Mat & mask = cv::Mat());
225  cv::Mat generateDescriptors(
226  const cv::Mat & image,
227  std::vector<cv::KeyPoint> & keypoints) const;
228  std::vector<cv::Point3f> generateKeypoints3D(
229  const SensorData & data,
230  const std::vector<cv::KeyPoint> & keypoints) const;
231 
232  virtual void parseParameters(const ParametersMap & parameters);
233  virtual const ParametersMap & getParameters() const {return parameters_;}
234  virtual Feature2D::Type getType() const = 0;
235 
236 protected:
237  Feature2D(const ParametersMap & parameters = ParametersMap());
238 
239 private:
240  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) = 0;
241  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
242 
243 private:
246  bool SSC_;
247  float _maxDepth; // 0=inf
248  float _minDepth;
249  std::vector<float> _roiRatios; // size 4
252  double _subPixEps;
255  // Stereo stuff
257 };
258 
259 //SURF
260 class RTABMAP_CORE_EXPORT SURF : public Feature2D
261 {
262 public:
263  SURF(const ParametersMap & parameters = ParametersMap());
264  virtual ~SURF();
265 
266  virtual void parseParameters(const ParametersMap & parameters);
267  virtual Feature2D::Type getType() const {return kFeatureSurf;}
268 
269 private:
270  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
271  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
272 
273 private:
277  bool extended_;
278  bool upright_;
281 
282  cv::Ptr<CV_SURF> _surf;
283  cv::Ptr<CV_SURF_GPU> _gpuSurf;
284 };
285 
286 //SIFT
287 class RTABMAP_CORE_EXPORT SIFT : public Feature2D
288 {
289 public:
290  SIFT(const ParametersMap & parameters = ParametersMap());
291  virtual ~SIFT();
292 
293  virtual void parseParameters(const ParametersMap & parameters);
294  virtual Feature2D::Type getType() const {return kFeatureSift;}
295 
296 private:
297  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
298  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
299 
300 private:
304  double sigma_;
306  bool rootSIFT_;
307  bool gpu_;
309  bool upscale_;
310 
311  cv::Ptr<CV_SIFT> sift_;
312  SiftData * cudaSiftData_;
317 };
318 
319 //ORB
320 class RTABMAP_CORE_EXPORT ORB : public Feature2D
321 {
322 public:
323  ORB(const ParametersMap & parameters = ParametersMap());
324  virtual ~ORB();
325 
326  virtual void parseParameters(const ParametersMap & parameters);
327  virtual Feature2D::Type getType() const {return kFeatureOrb;}
328 
329 private:
330  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
331  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
332 
333 private:
335  int nLevels_;
338  int WTA_K_;
341  bool gpu_;
342 
345 
346  cv::Ptr<CV_ORB> _orb;
347  cv::Ptr<CV_ORB_GPU> _gpuOrb;
348 };
349 
350 //FAST
351 class RTABMAP_CORE_EXPORT FAST : public Feature2D
352 {
353 public:
354  FAST(const ParametersMap & parameters = ParametersMap());
355  virtual ~FAST();
356 
357  virtual void parseParameters(const ParametersMap & parameters);
358  virtual Feature2D::Type getType() const {return kFeatureUndef;}
359 
360 private:
361  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
362  virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector<cv::KeyPoint> &) const {return cv::Mat();}
363 
364 private:
367  bool gpu_;
373  int fastCV_;
374 
378  uint32_t* fastCVCorners_= NULL;
379  uint32_t* fastCVCornerScores_ = NULL;
380  void* fastCVTempBuf_ = NULL;
381 
382  cv::Ptr<cv::FeatureDetector> _fast;
383  cv::Ptr<CV_FAST_GPU> _gpuFast;
384 };
385 
386 //FAST_BRIEF
387 class RTABMAP_CORE_EXPORT FAST_BRIEF : public FAST
388 {
389 public:
390  FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
391  virtual ~FAST_BRIEF();
392 
393  virtual void parseParameters(const ParametersMap & parameters);
394  virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
395 
396 private:
397  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
398 
399 private:
400  int bytes_;
401 
402  cv::Ptr<CV_BRIEF> _brief;
403 };
404 
405 //FAST_FREAK
406 class RTABMAP_CORE_EXPORT FAST_FREAK : public FAST
407 {
408 public:
409  FAST_FREAK(const ParametersMap & parameters = ParametersMap());
410  virtual ~FAST_FREAK();
411 
412  virtual void parseParameters(const ParametersMap & parameters);
413  virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
414 
415 private:
416  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
417 
418 private:
423 
424  cv::Ptr<CV_FREAK> _freak;
425 };
426 
427 //GFTT
428 class RTABMAP_CORE_EXPORT GFTT : public Feature2D
429 {
430 public:
431  GFTT(const ParametersMap & parameters = ParametersMap());
432  virtual ~GFTT();
433 
434  virtual void parseParameters(const ParametersMap & parameters);
435 
436 private:
437  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
438 
439 private:
441  double _minDistance;
444  double _k;
445  bool _gpu;
446 
447  cv::Ptr<CV_GFTT> _gftt;
448  cv::Ptr<CV_GFTT_GPU> _gpuGftt;
449 };
450 
451 //GFTT_BRIEF
452 class RTABMAP_CORE_EXPORT GFTT_BRIEF : public GFTT
453 {
454 public:
455  GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
456  virtual ~GFTT_BRIEF();
457 
458  virtual void parseParameters(const ParametersMap & parameters);
459  virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
460 
461 private:
462  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
463 
464 private:
465  int bytes_;
466 
467  cv::Ptr<CV_BRIEF> _brief;
468 };
469 
470 //GFTT_FREAK
471 class RTABMAP_CORE_EXPORT GFTT_FREAK : public GFTT
472 {
473 public:
474  GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
475  virtual ~GFTT_FREAK();
476 
477  virtual void parseParameters(const ParametersMap & parameters);
478  virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
479 
480 private:
481  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
482 
483 private:
488 
489  cv::Ptr<CV_FREAK> _freak;
490 };
491 
492 //SURF_FREAK
493 class RTABMAP_CORE_EXPORT SURF_FREAK : public SURF
494 {
495 public:
496  SURF_FREAK(const ParametersMap & parameters = ParametersMap());
497  virtual ~SURF_FREAK();
498 
499  virtual void parseParameters(const ParametersMap & parameters);
500  virtual Feature2D::Type getType() const {return kFeatureSurfFreak;}
501 
502 private:
503  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
504 
505 private:
510 
511  cv::Ptr<CV_FREAK> _freak;
512 };
513 
514 //GFTT_ORB
515 class RTABMAP_CORE_EXPORT GFTT_ORB : public GFTT
516 {
517 public:
518  GFTT_ORB(const ParametersMap & parameters = ParametersMap());
519  virtual ~GFTT_ORB();
520 
521  virtual void parseParameters(const ParametersMap & parameters);
522  virtual Feature2D::Type getType() const {return kFeatureGfttOrb;}
523 
524 private:
525  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
526 
527 private:
529 };
530 
531 //BRISK
532 class RTABMAP_CORE_EXPORT BRISK : public Feature2D
533 {
534 public:
535  BRISK(const ParametersMap & parameters = ParametersMap());
536  virtual ~BRISK();
537 
538  virtual void parseParameters(const ParametersMap & parameters);
539  virtual Feature2D::Type getType() const {return kFeatureBrisk;}
540 
541 private:
542  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
543  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
544 
545 private:
546  int thresh_;
547  int octaves_;
549 
550  cv::Ptr<CV_BRISK> brisk_;
551 };
552 
553 //KAZE
554 class RTABMAP_CORE_EXPORT KAZE : public Feature2D
555 {
556 public:
557  KAZE(const ParametersMap & parameters = ParametersMap());
558  virtual ~KAZE();
559 
560  virtual void parseParameters(const ParametersMap & parameters);
561  virtual Feature2D::Type getType() const { return kFeatureKaze; }
562 
563 private:
564  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
565  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
566 
567 private:
568  bool extended_;
569  bool upright_;
570  float threshold_;
574 
575 #if CV_MAJOR_VERSION > 2
576  cv::Ptr<cv::KAZE> kaze_;
577 #endif
578 };
579 
580 //ORB OCTREE
581 class RTABMAP_CORE_EXPORT ORBOctree : public Feature2D
582 {
583 public:
584  ORBOctree(const ParametersMap & parameters = ParametersMap());
585  virtual ~ORBOctree();
586 
587  virtual void parseParameters(const ParametersMap & parameters);
588  virtual Feature2D::Type getType() const {return kFeatureOrbOctree;}
589 
590 private:
591  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
592  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
593 
594 private:
596  int nLevels_;
601 
602  cv::Ptr<ORBextractor> _orb;
603  cv::Mat descriptors_;
604 };
605 
606 //SuperPointTorch
607 class RTABMAP_CORE_EXPORT SuperPointTorch : public Feature2D
608 {
609 public:
610  SuperPointTorch(const ParametersMap & parameters = ParametersMap());
611  virtual ~SuperPointTorch();
612 
613  virtual void parseParameters(const ParametersMap & parameters);
614  virtual Feature2D::Type getType() const { return kFeatureSuperPointTorch; }
615 
616 private:
617  virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat());
618  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
619 
620  cv::Ptr<SPDetector> superPoint_;
621 
622  std::string path_;
623  float threshold_;
624  bool nms_;
626  bool cuda_;
627 };
628 
629 //GFTT_DAISY
630 class RTABMAP_CORE_EXPORT GFTT_DAISY : public GFTT
631 {
632 public:
633  GFTT_DAISY(const ParametersMap & parameters = ParametersMap());
634  virtual ~GFTT_DAISY();
635 
636  virtual void parseParameters(const ParametersMap & parameters);
637  virtual Feature2D::Type getType() const {return kFeatureGfttDaisy;}
638 
639 private:
640  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
641 
642 private:
647 
648 #if CV_MAJOR_VERSION > 2
649  cv::Ptr<CV_DAISY> _daisy;
650 #endif
651 };
652 
653 //SURF_DAISY
654 class RTABMAP_CORE_EXPORT SURF_DAISY : public SURF
655 {
656 public:
657  SURF_DAISY(const ParametersMap & parameters = ParametersMap());
658  virtual ~SURF_DAISY();
659 
660  virtual void parseParameters(const ParametersMap & parameters);
661  virtual Feature2D::Type getType() const {return kFeatureSurfDaisy;}
662 
663 private:
664  virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
665 
666 private:
671 
672 #if CV_MAJOR_VERSION > 2
673  cv::Ptr<CV_DAISY> _daisy;
674 #endif
675 };
676 
677 }
678 
679 #endif /* FEATURES2D_H_ */
rtabmap::SensorData
Definition: SensorData.h:51
create
ADT create(const Signature &signature)
rtabmap::FAST_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:420
rtabmap::SURF_DAISY::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:661
rtabmap::GFTT_BRIEF::bytes_
int bytes_
Definition: Features2d.h:465
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:484
rtabmap::ORBOctree::patchSize_
int patchSize_
Definition: Features2d.h:597
rtabmap::FAST::gridCols_
int gridCols_
Definition: Features2d.h:372
glm::mask
GLM_FUNC_DECL genIType mask(genIType const &count)
rtabmap::ORB::_orb
cv::Ptr< CV_ORB > _orb
Definition: Features2d.h:346
rtabmap::GFTT::_gpuGftt
cv::Ptr< CV_GFTT_GPU > _gpuGftt
Definition: Features2d.h:448
rtabmap::KAZE::extended_
bool extended_
Definition: Features2d.h:568
rtabmap::GFTT_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:644
rtabmap::SURF_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:500
rtabmap::FAST_BRIEF::bytes_
int bytes_
Definition: Features2d.h:400
rtabmap::ORBOctree
Definition: Features2d.h:581
rtabmap::GFTT_ORB::_orb
ORB _orb
Definition: Features2d.h:528
rtabmap::FAST_BRIEF
Definition: Features2d.h:387
rtabmap::SURF::nOctaves_
int nOctaves_
Definition: Features2d.h:275
rtabmap::GFTT::_useHarrisDetector
bool _useHarrisDetector
Definition: Features2d.h:443
CV_GFTT_GPU
cv::gpu::GoodFeaturesToTrackDetector_GPU CV_GFTT_GPU
Definition: Features2d.h:62
rtabmap::GFTT_BRIEF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:459
rtabmap::FAST
Definition: Features2d.h:351
rtabmap::GFTT_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:487
rtabmap::SuperPointTorch::superPoint_
cv::Ptr< SPDetector > superPoint_
Definition: Features2d.h:620
rtabmap::ORBOctree::_orb
cv::Ptr< ORBextractor > _orb
Definition: Features2d.h:602
CV_FREAK
cv::FREAK CV_FREAK
Definition: Features2d.h:55
rtabmap::FAST::maxThreshold_
int maxThreshold_
Definition: Features2d.h:370
rtabmap::ORB::patchSize_
int patchSize_
Definition: Features2d.h:340
uint32_t
::uint32_t uint32_t
rtabmap::SURF_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:511
rtabmap::SURF::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:276
rtabmap::KAZE::nOctaves_
int nOctaves_
Definition: Features2d.h:571
rtabmap::ORBOctree::nLevels_
int nLevels_
Definition: Features2d.h:596
rtabmap::SIFT::gpu_
bool gpu_
Definition: Features2d.h:307
rtabmap::SIFT::upscale_
bool upscale_
Definition: Features2d.h:309
SensorData.h
rtabmap::GFTT_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:478
rtabmap::Stereo
Definition: Stereo.h:38
rtabmap::ORB::scaleFactor_
float scaleFactor_
Definition: Features2d.h:334
rtabmap::GFTT_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:467
rtabmap::SURF
Definition: Features2d.h:260
rtabmap::KAZE::threshold_
float threshold_
Definition: Features2d.h:570
type
rtabmap::Feature2D::getSSC
bool getSSC() const
Definition: Features2d.h:213
rtabmap::FAST_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:419
rtabmap::BRISK
Definition: Features2d.h:532
CV_SIFT
cv::SIFT CV_SIFT
Definition: Features2d.h:52
rtabmap::ORBOctree::fastMinThreshold_
int fastMinThreshold_
Definition: Features2d.h:600
rtabmap::GFTT::_qualityLevel
double _qualityLevel
Definition: Features2d.h:440
rtabmap::FAST::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:358
rtabmap::GFTT::_gftt
cv::Ptr< CV_GFTT > _gftt
Definition: Features2d.h:447
CV_BRISK
cv::BRISK CV_BRISK
Definition: Features2d.h:58
rtabmap::FAST::fastCVLastImageHeight_
int fastCVLastImageHeight_
Definition: Features2d.h:377
rtabmap::Feature2D::_subPixIterations
int _subPixIterations
Definition: Features2d.h:251
rtabmap::SURF::hessianThreshold_
double hessianThreshold_
Definition: Features2d.h:274
rtabmap::SIFT::preciseUpscale_
bool preciseUpscale_
Definition: Features2d.h:305
rtabmap::SIFT::sigma_
double sigma_
Definition: Features2d.h:304
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:347
rtabmap::FAST::gpuKeypointsRatio_
double gpuKeypointsRatio_
Definition: Features2d.h:368
rtabmap::BRISK::octaves_
int octaves_
Definition: Features2d.h:547
rtabmap::Feature2D::typeName
static std::string typeName(Type type)
Definition: Features2d.h:134
rtabmap::BRISK::thresh_
int thresh_
Definition: Features2d.h:546
rtabmap::Feature2D::getParameters
virtual const ParametersMap & getParameters() const
Definition: Features2d.h:233
rtabmap::ORB::nLevels_
int nLevels_
Definition: Features2d.h:335
rtabmap::FAST_FREAK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:413
Parameters.h
rtabmap::SIFT::cudaSiftDescriptors_
cv::Mat cudaSiftDescriptors_
Definition: Features2d.h:315
rtabmap::SURF::_gpuSurf
cv::Ptr< CV_SURF_GPU > _gpuSurf
Definition: Features2d.h:283
rtabmap::ORBOctree::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:588
rtabmap::Feature2D::gridRows_
int gridRows_
Definition: Features2d.h:253
rtabmap::FAST_FREAK
Definition: Features2d.h:406
rtabmap::GFTT_DAISY::patternScale_
float patternScale_
Definition: Features2d.h:645
rtabmap::ORB::gpu_
bool gpu_
Definition: Features2d.h:341
Type
rtabmap::FAST_BRIEF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:394
rtabmap::FAST_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:422
rtabmap::FAST::gpu_
bool gpu_
Definition: Features2d.h:367
rtabmap::KAZE::diffusivity_
int diffusivity_
Definition: Features2d.h:573
rtabmap::FAST::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &, std::vector< cv::KeyPoint > &) const
Definition: Features2d.h:362
rtabmap::ORB::scoreType_
int scoreType_
Definition: Features2d.h:339
rtabmap::Feature2D::gridCols_
int gridCols_
Definition: Features2d.h:254
rtabmap::SIFT
Definition: Features2d.h:287
rtabmap::GFTT_ORB::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:522
CV_SURF
cv::SURF CV_SURF
Definition: Features2d.h:53
rtabmap::KAZE::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:572
CV_FAST
cv::FastFeatureDetector CV_FAST
Definition: Features2d.h:54
rtabmap::Feature2D::getMaxFeatures
int getMaxFeatures() const
Definition: Features2d.h:212
rtabmap::ORB::fastThreshold_
int fastThreshold_
Definition: Features2d.h:343
rtabmap::Feature2D::_minDepth
float _minDepth
Definition: Features2d.h:248
rtabmap::Feature2D::_stereo
Stereo * _stereo
Definition: Features2d.h:256
rtabmap::GFTT_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:646
rtabmap::FAST::fastCV_
int fastCV_
Definition: Features2d.h:373
rtabmap::SuperPointTorch
Definition: Features2d.h:607
CV_BRIEF
cv::BriefDescriptorExtractor CV_BRIEF
Definition: Features2d.h:57
rtabmap::Feature2D::getMinDepth
float getMinDepth() const
Definition: Features2d.h:214
rtabmap::GFTT_ORB
Definition: Features2d.h:515
rtabmap::SuperPointTorch::nms_
bool nms_
Definition: Features2d.h:624
rtabmap::BRISK::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:539
rtabmap::BRISK::brisk_
cv::Ptr< CV_BRISK > brisk_
Definition: Features2d.h:550
rtabmap::FAST::_fast
cv::Ptr< cv::FeatureDetector > _fast
Definition: Features2d.h:382
rtabmap::Feature2D
Definition: Features2d.h:114
rtabmap::SURF::extended_
bool extended_
Definition: Features2d.h:277
rtabmap::SuperPointTorch::path_
std::string path_
Definition: Features2d.h:622
rtabmap::SuperPointTorch::minDistance_
int minDistance_
Definition: Features2d.h:625
rtabmap::Feature2D::Type
Type
Definition: Features2d.h:116
rtabmap::Feature2D::getMaxDepth
float getMaxDepth() const
Definition: Features2d.h:215
rtabmap::SIFT::rootSIFT_
bool rootSIFT_
Definition: Features2d.h:306
rtabmap::BRISK::patternScale_
float patternScale_
Definition: Features2d.h:548
rtabmap::GFTT_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:643
rtabmap::Feature2D::getGridCols
int getGridCols() const
Definition: Features2d.h:217
rtabmap::SURF_DAISY
Definition: Features2d.h:654
rtabmap::FAST::minThreshold_
int minThreshold_
Definition: Features2d.h:369
rtabmap::FAST_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:421
rtabmap::SuperPointTorch::threshold_
float threshold_
Definition: Features2d.h:623
rtabmap::SIFT::cudaSiftUpscaling_
bool cudaSiftUpscaling_
Definition: Features2d.h:316
rtabmap::FAST::nonmaxSuppression_
bool nonmaxSuppression_
Definition: Features2d.h:366
rtabmap::SIFT::contrastThreshold_
double contrastThreshold_
Definition: Features2d.h:302
rtabmap::Feature2D::_maxDepth
float _maxDepth
Definition: Features2d.h:247
rtabmap::GFTT::_gpu
bool _gpu
Definition: Features2d.h:445
rtabmap::GFTT_DAISY::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:637
rtabmap::SURF_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:507
rtabmap::GFTT_BRIEF
Definition: Features2d.h:452
rtabmap::Feature2D::getGridRows
int getGridRows() const
Definition: Features2d.h:216
rtabmap::SURF_DAISY::patternScale_
float patternScale_
Definition: Features2d.h:669
rtabmap::SIFT::cudaSiftMemorySize_
cv::Size cudaSiftMemorySize_
Definition: Features2d.h:314
rtabmap::Feature2D::_roiRatios
std::vector< float > _roiRatios
Definition: Features2d.h:249
rtabmap::SURF::_surf
cv::Ptr< CV_SURF > _surf
Definition: Features2d.h:282
rtabmap::KAZE::upright_
bool upright_
Definition: Features2d.h:569
rtabmap::GFTT
Definition: Features2d.h:428
CV_SURF_GPU
cv::gpu::SURF_GPU CV_SURF_GPU
Definition: Features2d.h:59
rtabmap::GFTT_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:486
rtabmap::SIFT::cudaSiftMemory_
float * cudaSiftMemory_
Definition: Features2d.h:313
rtabmap::Feature2D::parameters_
ParametersMap parameters_
Definition: Features2d.h:244
rtabmap::SURF_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:508
rtabmap::SURF::gpuKeypointsRatio_
float gpuKeypointsRatio_
Definition: Features2d.h:279
rtabmap::Feature2D::_subPixWinSize
int _subPixWinSize
Definition: Features2d.h:250
rtabmap::SURF_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:667
rtabmap::SURF_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:668
rtabmap::SIFT::edgeThreshold_
double edgeThreshold_
Definition: Features2d.h:303
rtabmap::ORB::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:336
CV_ORB_GPU
cv::gpu::ORB_GPU CV_ORB_GPU
Definition: Features2d.h:60
rtabmap::GFTT_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:489
rtabmap::SuperPointTorch::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:614
rtabmap::ORBOctree::scaleFactor_
float scaleFactor_
Definition: Features2d.h:595
rtabmap::FAST::fastCVMaxFeatures_
int fastCVMaxFeatures_
Definition: Features2d.h:376
rtabmap::SURF_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:509
rtabmap::GFTT_DAISY
Definition: Features2d.h:630
rtabmap::ORB::WTA_K_
int WTA_K_
Definition: Features2d.h:338
rtabmap::ORB::nonmaxSuppresion_
bool nonmaxSuppresion_
Definition: Features2d.h:344
rtabmap::Feature2D::SSC_
bool SSC_
Definition: Features2d.h:246
rtabmap::FAST::gridRows_
int gridRows_
Definition: Features2d.h:371
rtabmap::ORBOctree::fastThreshold_
int fastThreshold_
Definition: Features2d.h:599
rtabmap::KAZE::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:561
rtabmap::ORBOctree::descriptors_
cv::Mat descriptors_
Definition: Features2d.h:603
rtabmap::GFTT_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:485
rtabmap::GFTT::_k
double _k
Definition: Features2d.h:444
cv
Definition: Features2d.h:42
rtabmap::FAST::threshold_
int threshold_
Definition: Features2d.h:365
rtabmap::SuperPointTorch::cuda_
bool cuda_
Definition: Features2d.h:626
rtabmap::Feature2D::maxFeatures_
int maxFeatures_
Definition: Features2d.h:245
rtabmap::SURF::gpuVersion_
bool gpuVersion_
Definition: Features2d.h:280
CV_GFTT
cv::GFTTDetector CV_GFTT
Definition: Features2d.h:56
rtabmap::ORB
Definition: Features2d.h:320
rtabmap::SIFT::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:301
rtabmap::GFTT::_blockSize
int _blockSize
Definition: Features2d.h:442
NULL
#define NULL
rtabmap::SURF_FREAK
Definition: Features2d.h:493
gpu
GpuHelper gpu
rtabmap::SURF_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:670
rtabmap::SIFT::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:294
rtabmap::FAST_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:424
rtabmap::SURF::upright_
bool upright_
Definition: Features2d.h:278
rtabmap::SIFT::sift_
cv::Ptr< CV_SIFT > sift_
Definition: Features2d.h:311
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::ORB::firstLevel_
int firstLevel_
Definition: Features2d.h:337
rtabmap::SIFT::cudaSiftData_
SiftData * cudaSiftData_
Definition: Features2d.h:312
rtabmap::FAST_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:402
rtabmap::ORBOctree::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:598
rtabmap::KAZE
Definition: Features2d.h:554
rtabmap::SURF_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:506
rtabmap::ORB::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:327
rtabmap::GFTT_FREAK
Definition: Features2d.h:471
rtabmap::GFTT::_minDistance
double _minDistance
Definition: Features2d.h:441
rtabmap::Feature2D::_subPixEps
double _subPixEps
Definition: Features2d.h:252
rtabmap::FAST::_gpuFast
cv::Ptr< CV_FAST_GPU > _gpuFast
Definition: Features2d.h:383
rtabmap::SURF::getType
virtual Feature2D::Type getType() const
Definition: Features2d.h:267
CV_FAST_GPU
cv::gpu::FAST_GPU CV_FAST_GPU
Definition: Features2d.h:61
rtabmap::SIFT::guaussianThreshold_
float guaussianThreshold_
Definition: Features2d.h:308
rtabmap::FAST::fastCVinit_
bool fastCVinit_
Definition: Features2d.h:375


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:45