ORBmatcher.h 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  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 ORBMATCHER_H
  19. #define ORBMATCHER_H
  20. #include<vector>
  21. #include<opencv2/core/core.hpp>
  22. #include<opencv2/features2d/features2d.hpp>
  23. #include"sophus/sim3.hpp"
  24. #include"MapPoint.h"
  25. #include"KeyFrame.h"
  26. #include"Frame.h"
  27. namespace ORB_SLAM3
  28. {
  29. class ORBmatcher
  30. {
  31. public:
  32. ORBmatcher(float nnratio=0.6, bool checkOri=true);
  33. // Computes the Hamming distance between two ORB descriptors
  34. static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b);
  35. // Search matches between Frame keypoints and projected MapPoints. Returns number of matches
  36. // Used to track the local map (Tracking)
  37. int SearchByProjection(Frame &F, const std::vector<MapPoint*> &vpMapPoints, const float th=3, const bool bFarPoints = false, const float thFarPoints = 50.0f);
  38. // Project MapPoints tracked in last frame into the current frame and search matches.
  39. // Used to track from previous frame (Tracking)
  40. int SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono);
  41. // Project MapPoints seen in KeyFrame into the Frame and search matches.
  42. // Used in relocalisation (Tracking)
  43. int SearchByProjection(Frame &CurrentFrame, KeyFrame* pKF, const std::set<MapPoint*> &sAlreadyFound, const float th, const int ORBdist);
  44. // Project MapPoints using a Similarity Transformation and search matches.
  45. // Used in loop detection (Loop Closing)
  46. int SearchByProjection(KeyFrame* pKF, Sophus::Sim3<float> &Scw, const std::vector<MapPoint*> &vpPoints, std::vector<MapPoint*> &vpMatched, int th, float ratioHamming=1.0);
  47. // Project MapPoints using a Similarity Transformation and search matches.
  48. // Used in Place Recognition (Loop Closing and Merging)
  49. int SearchByProjection(KeyFrame* pKF, Sophus::Sim3<float> &Scw, const std::vector<MapPoint*> &vpPoints, const std::vector<KeyFrame*> &vpPointsKFs, std::vector<MapPoint*> &vpMatched, std::vector<KeyFrame*> &vpMatchedKF, int th, float ratioHamming=1.0);
  50. // Search matches between MapPoints in a KeyFrame and ORB in a Frame.
  51. // Brute force constrained to ORB that belong to the same vocabulary node (at a certain level)
  52. // Used in Relocalisation and Loop Detection
  53. int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector<MapPoint*> &vpMapPointMatches);
  54. int SearchByBoW(KeyFrame *pKF1, KeyFrame* pKF2, std::vector<MapPoint*> &vpMatches12);
  55. // Matching for the Map Initialization (only used in the monocular case)
  56. int SearchForInitialization(Frame &F1, Frame &F2, std::vector<cv::Point2f> &vbPrevMatched, std::vector<int> &vnMatches12, int windowSize=10);
  57. // Matching to triangulate new MapPoints. Check Epipolar Constraint.
  58. int SearchForTriangulation(KeyFrame *pKF1, KeyFrame* pKF2,
  59. std::vector<pair<size_t, size_t> > &vMatchedPairs, const bool bOnlyStereo, const bool bCoarse = false);
  60. // Search matches between MapPoints seen in KF1 and KF2 transforming by a Sim3 [s12*R12|t12]
  61. // In the stereo and RGB-D case, s12=1
  62. // int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector<MapPoint *> &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th);
  63. int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector<MapPoint *> &vpMatches12, const Sophus::Sim3f &S12, const float th);
  64. // Project MapPoints into KeyFrame and search for duplicated MapPoints.
  65. int Fuse(KeyFrame* pKF, const vector<MapPoint *> &vpMapPoints, const float th=3.0, const bool bRight = false);
  66. // Project MapPoints into KeyFrame using a given Sim3 and search for duplicated MapPoints.
  67. int Fuse(KeyFrame* pKF, Sophus::Sim3f &Scw, const std::vector<MapPoint*> &vpPoints, float th, vector<MapPoint *> &vpReplacePoint);
  68. public:
  69. static const int TH_LOW;
  70. static const int TH_HIGH;
  71. static const int HISTO_LENGTH;
  72. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  73. protected:
  74. float RadiusByViewingCos(const float &viewCos);
  75. void ComputeThreeMaxima(std::vector<int>* histo, const int L, int &ind1, int &ind2, int &ind3);
  76. float mfNNratio;
  77. bool mbCheckOrientation;
  78. };
  79. }// namespace ORB_SLAM
  80. #endif // ORBMATCHER_H