Features2d.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef FEATURES2D_H_
00029 #define FEATURES2D_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
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 // Feature2D
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,  //new 0.10.11
00108                 kFeatureKaze=9};    //new 0.13.2
00109 
00110         static Feature2D * create(const ParametersMap & parameters = ParametersMap());
00111         static Feature2D * create(Feature2D::Type type, const ParametersMap & parameters = ParametersMap()); // for convenience
00112 
00113         static void filterKeypointsByDepth(
00114                                 std::vector<cv::KeyPoint> & keypoints,
00115                                 const cv::Mat & depth,
00116                                 float minDepth,
00117                                 float maxDepth);
00118         static void filterKeypointsByDepth(
00119                         std::vector<cv::KeyPoint> & keypoints,
00120                         cv::Mat & descriptors,
00121                         const cv::Mat & depth,
00122                         float minDepth,
00123                         float maxDepth);
00124 
00125         static void filterKeypointsByDisparity(
00126                                 std::vector<cv::KeyPoint> & keypoints,
00127                                 const cv::Mat & disparity,
00128                                 float minDisparity);
00129         static void filterKeypointsByDisparity(
00130                         std::vector<cv::KeyPoint> & keypoints,
00131                         cv::Mat & descriptors,
00132                         const cv::Mat & disparity,
00133                         float minDisparity);
00134 
00135         static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints);
00136         static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints);
00137         static void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors, int maxKeypoints);
00138         static void limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints);
00139 
00140         static cv::Rect computeRoi(const cv::Mat & image, const std::string & roiRatios);
00141         static cv::Rect computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
00142 
00143         int getMaxFeatures() const {return maxFeatures_;}
00144         float getMinDepth() const {return _minDepth;}
00145         float getMaxDepth() const {return _maxDepth;}
00146 
00147 public:
00148         virtual ~Feature2D();
00149 
00150         std::vector<cv::KeyPoint> generateKeypoints(
00151                         const cv::Mat & image,
00152                         const cv::Mat & mask = cv::Mat()) const;
00153         cv::Mat generateDescriptors(
00154                         const cv::Mat & image,
00155                         std::vector<cv::KeyPoint> & keypoints) const;
00156         std::vector<cv::Point3f> generateKeypoints3D(
00157                         const SensorData & data,
00158                         const std::vector<cv::KeyPoint> & keypoints) const;
00159 
00160         virtual void parseParameters(const ParametersMap & parameters);
00161         virtual const ParametersMap & getParameters() const {return parameters_;}
00162         virtual Feature2D::Type getType() const = 0;
00163 
00164 protected:
00165         Feature2D(const ParametersMap & parameters = ParametersMap());
00166 
00167 private:
00168         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const = 0;
00169         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const = 0;
00170 
00171 private:
00172         ParametersMap parameters_;
00173         int maxFeatures_;
00174         float _maxDepth; // 0=inf
00175         float _minDepth;
00176         std::vector<float> _roiRatios; // size 4
00177         int _subPixWinSize;
00178         int _subPixIterations;
00179         double _subPixEps;
00180         int gridRows_;
00181         int gridCols_;
00182         // Stereo stuff
00183         Stereo * _stereo;
00184 };
00185 
00186 //SURF
00187 class RTABMAP_EXP SURF : public Feature2D
00188 {
00189 public:
00190         SURF(const ParametersMap & parameters = ParametersMap());
00191         virtual ~SURF();
00192 
00193         virtual void parseParameters(const ParametersMap & parameters);
00194         virtual Feature2D::Type getType() const {return kFeatureSurf;}
00195 
00196 private:
00197         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00198         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00199 
00200 private:
00201         double hessianThreshold_;
00202         int nOctaves_;
00203         int nOctaveLayers_;
00204         bool extended_;
00205         bool upright_;
00206         float gpuKeypointsRatio_;
00207         bool gpuVersion_;
00208 
00209         cv::Ptr<CV_SURF> _surf;
00210         cv::Ptr<CV_SURF_GPU> _gpuSurf;
00211 };
00212 
00213 //SIFT
00214 class RTABMAP_EXP SIFT : public Feature2D
00215 {
00216 public:
00217         SIFT(const ParametersMap & parameters = ParametersMap());
00218         virtual ~SIFT();
00219 
00220         virtual void parseParameters(const ParametersMap & parameters);
00221         virtual Feature2D::Type getType() const {return kFeatureSift;}
00222 
00223 private:
00224         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00225         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00226 
00227 private:
00228         int nOctaveLayers_;
00229         double contrastThreshold_;
00230         double edgeThreshold_;
00231         double sigma_;
00232 
00233         cv::Ptr<CV_SIFT> _sift;
00234 };
00235 
00236 //ORB
00237 class RTABMAP_EXP ORB : public Feature2D
00238 {
00239 public:
00240         ORB(const ParametersMap & parameters = ParametersMap());
00241         virtual ~ORB();
00242 
00243         virtual void parseParameters(const ParametersMap & parameters);
00244         virtual Feature2D::Type getType() const {return kFeatureOrb;}
00245 
00246 private:
00247         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00248         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00249 
00250 private:
00251         float scaleFactor_;
00252         int nLevels_;
00253         int edgeThreshold_;
00254         int firstLevel_;
00255         int WTA_K_;
00256         int scoreType_;
00257         int patchSize_;
00258         bool gpu_;
00259 
00260         int fastThreshold_;
00261         bool nonmaxSuppresion_;
00262 
00263         cv::Ptr<CV_ORB> _orb;
00264         cv::Ptr<CV_ORB_GPU> _gpuOrb;
00265 };
00266 
00267 //FAST
00268 class RTABMAP_EXP FAST : public Feature2D
00269 {
00270 public:
00271         FAST(const ParametersMap & parameters = ParametersMap());
00272         virtual ~FAST();
00273 
00274         virtual void parseParameters(const ParametersMap & parameters);
00275         virtual Feature2D::Type getType() const {return kFeatureUndef;}
00276 
00277 private:
00278         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00279         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const {return cv::Mat();}
00280 
00281 private:
00282         int threshold_;
00283         bool nonmaxSuppression_;
00284         bool gpu_;
00285         double gpuKeypointsRatio_;
00286         int minThreshold_;
00287         int maxThreshold_;
00288         int gridRows_;
00289         int gridCols_;
00290 
00291         cv::Ptr<cv::FeatureDetector> _fast;
00292         cv::Ptr<CV_FAST_GPU> _gpuFast;
00293 };
00294 
00295 //FAST_BRIEF
00296 class RTABMAP_EXP FAST_BRIEF : public FAST
00297 {
00298 public:
00299         FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
00300         virtual ~FAST_BRIEF();
00301 
00302         virtual void parseParameters(const ParametersMap & parameters);
00303         virtual Feature2D::Type getType() const {return kFeatureFastBrief;}
00304 
00305 private:
00306         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00307 
00308 private:
00309         int bytes_;
00310 
00311         cv::Ptr<CV_BRIEF> _brief;
00312 };
00313 
00314 //FAST_FREAK
00315 class RTABMAP_EXP FAST_FREAK : public FAST
00316 {
00317 public:
00318         FAST_FREAK(const ParametersMap & parameters = ParametersMap());
00319         virtual ~FAST_FREAK();
00320 
00321         virtual void parseParameters(const ParametersMap & parameters);
00322         virtual Feature2D::Type getType() const {return kFeatureFastFreak;}
00323 
00324 private:
00325         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00326 
00327 private:
00328         bool orientationNormalized_;
00329         bool scaleNormalized_;
00330         float patternScale_;
00331         int nOctaves_;
00332 
00333         cv::Ptr<CV_FREAK> _freak;
00334 };
00335 
00336 //GFTT
00337 class RTABMAP_EXP GFTT : public Feature2D
00338 {
00339 public:
00340         GFTT(const ParametersMap & parameters = ParametersMap());
00341         virtual ~GFTT();
00342 
00343         virtual void parseParameters(const ParametersMap & parameters);
00344 
00345 private:
00346         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00347 
00348 private:
00349         double _qualityLevel;
00350         double _minDistance;
00351         int _blockSize;
00352         bool _useHarrisDetector;
00353         double _k;
00354 
00355         cv::Ptr<CV_GFTT> _gftt;
00356 };
00357 
00358 //GFTT_BRIEF
00359 class RTABMAP_EXP GFTT_BRIEF : public GFTT
00360 {
00361 public:
00362         GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
00363         virtual ~GFTT_BRIEF();
00364 
00365         virtual void parseParameters(const ParametersMap & parameters);
00366         virtual Feature2D::Type getType() const {return kFeatureGfttBrief;}
00367 
00368 private:
00369         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00370 
00371 private:
00372         int bytes_;
00373 
00374         cv::Ptr<CV_BRIEF> _brief;
00375 };
00376 
00377 //GFTT_FREAK
00378 class RTABMAP_EXP GFTT_FREAK : public GFTT
00379 {
00380 public:
00381         GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
00382         virtual ~GFTT_FREAK();
00383 
00384         virtual void parseParameters(const ParametersMap & parameters);
00385         virtual Feature2D::Type getType() const {return kFeatureGfttFreak;}
00386 
00387 private:
00388         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00389 
00390 private:
00391         bool orientationNormalized_;
00392         bool scaleNormalized_;
00393         float patternScale_;
00394         int nOctaves_;
00395 
00396         cv::Ptr<CV_FREAK> _freak;
00397 };
00398 
00399 //GFTT_ORB
00400 class RTABMAP_EXP GFTT_ORB : public GFTT
00401 {
00402 public:
00403         GFTT_ORB(const ParametersMap & parameters = ParametersMap());
00404         virtual ~GFTT_ORB();
00405 
00406         virtual void parseParameters(const ParametersMap & parameters);
00407         virtual Feature2D::Type getType() const {return kFeatureGfttOrb;}
00408 
00409 private:
00410         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00411 
00412 private:
00413         ORB _orb;
00414 };
00415 
00416 //BRISK
00417 class RTABMAP_EXP BRISK : public Feature2D
00418 {
00419 public:
00420         BRISK(const ParametersMap & parameters = ParametersMap());
00421         virtual ~BRISK();
00422 
00423         virtual void parseParameters(const ParametersMap & parameters);
00424         virtual Feature2D::Type getType() const {return kFeatureBrisk;}
00425 
00426 private:
00427         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00428         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00429 
00430 private:
00431         int thresh_;
00432         int octaves_;
00433         float patternScale_;
00434 
00435         cv::Ptr<CV_BRISK> brisk_;
00436 };
00437 
00438 //KAZE
00439 class RTABMAP_EXP KAZE : public Feature2D
00440 {
00441 public:
00442         KAZE(const ParametersMap & parameters = ParametersMap());
00443         virtual ~KAZE();
00444 
00445         virtual void parseParameters(const ParametersMap & parameters);
00446         virtual Feature2D::Type getType() const { return kFeatureKaze; }
00447 
00448 private:
00449         virtual std::vector<cv::KeyPoint> generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask = cv::Mat()) const;
00450         virtual cv::Mat generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const;
00451 
00452 private:
00453         bool extended_;
00454         bool upright_;
00455         float threshold_;
00456         int nOctaves_;
00457         int nOctaveLayers_;
00458         int diffusivity_;
00459 
00460 #if CV_MAJOR_VERSION > 2
00461         cv::Ptr<cv::KAZE> kaze_;
00462 #endif
00463 };
00464 
00465 
00466 }
00467 
00468 #endif /* FEATURES2D_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20