ORBextractor.h 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef ORBEXTRACTOR_H
  19. #define ORBEXTRACTOR_H
  20. #include <vector>
  21. #include <list>
  22. #include <opencv2/opencv.hpp>
  23. namespace ORB_SLAM3
  24. {
  25. class ExtractorNode
  26. {
  27. public:
  28. ExtractorNode():bNoMore(false){}
  29. void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4);
  30. std::vector<cv::KeyPoint> vKeys;
  31. cv::Point2i UL, UR, BL, BR;
  32. std::list<ExtractorNode>::iterator lit;
  33. bool bNoMore;
  34. };
  35. class ORBextractor
  36. {
  37. public:
  38. enum {HARRIS_SCORE=0, FAST_SCORE=1 };
  39. ORBextractor(int nfeatures, float scaleFactor, int nlevels,
  40. int iniThFAST, int minThFAST);
  41. ~ORBextractor(){}
  42. // Compute the ORB features and descriptors on an image.
  43. // ORB are dispersed on the image using an octree.
  44. // Mask is ignored in the current implementation.
  45. int operator()( cv::InputArray _image, cv::InputArray _mask,
  46. std::vector<cv::KeyPoint>& _keypoints,
  47. cv::OutputArray _descriptors, std::vector<int> &vLappingArea);
  48. int inline GetLevels(){
  49. return nlevels;}
  50. float inline GetScaleFactor(){
  51. return scaleFactor;}
  52. std::vector<float> inline GetScaleFactors(){
  53. return mvScaleFactor;
  54. }
  55. std::vector<float> inline GetInverseScaleFactors(){
  56. return mvInvScaleFactor;
  57. }
  58. std::vector<float> inline GetScaleSigmaSquares(){
  59. return mvLevelSigma2;
  60. }
  61. std::vector<float> inline GetInverseScaleSigmaSquares(){
  62. return mvInvLevelSigma2;
  63. }
  64. std::vector<cv::Mat> mvImagePyramid;
  65. protected:
  66. void ComputePyramid(cv::Mat image);
  67. void ComputeKeyPointsOctTree(std::vector<std::vector<cv::KeyPoint> >& allKeypoints);
  68. std::vector<cv::KeyPoint> DistributeOctTree(const std::vector<cv::KeyPoint>& vToDistributeKeys, const int &minX,
  69. const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level);
  70. void ComputeKeyPointsOld(std::vector<std::vector<cv::KeyPoint> >& allKeypoints);
  71. std::vector<cv::Point> pattern;
  72. int nfeatures;
  73. double scaleFactor;
  74. int nlevels;
  75. int iniThFAST;
  76. int minThFAST;
  77. std::vector<int> mnFeaturesPerLevel;
  78. std::vector<int> umax;
  79. std::vector<float> mvScaleFactor;
  80. std::vector<float> mvInvScaleFactor;
  81. std::vector<float> mvLevelSigma2;
  82. std::vector<float> mvInvLevelSigma2;
  83. };
  84. } //namespace ORB_SLAM
  85. #endif