ORBmatcher.h
Go to the documentation of this file.
1 
22 #ifndef ORBMATCHER_H
23 #define ORBMATCHER_H
24 
25 #include<vector>
26 #include<opencv2/core/core.hpp>
27 #include<opencv2/features2d/features2d.hpp>
28 
29 #include"MapPoint.h"
30 #include"KeyFrame.h"
31 #include"Frame.h"
32 
33 
34 namespace ORB_SLAM2
35 {
36 
38 {
39 public:
40 
41  ORBmatcher(float nnratio=0.6, bool checkOri=true);
42 
43  // Computes the Hamming distance between two ORB descriptors
44  static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b);
45 
46  // Search matches between Frame keypoints and projected MapPoints. Returns number of matches
47  // Used to track the local map (Tracking)
48  int SearchByProjection(Frame &F, const std::vector<MapPoint*> &vpMapPoints, const float th=3);
49 
50  // Project MapPoints tracked in last frame into the current frame and search matches.
51  // Used to track from previous frame (Tracking)
52  int SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono);
53 
54  // Project MapPoints seen in KeyFrame into the Frame and search matches.
55  // Used in relocalisation (Tracking)
56  int SearchByProjection(Frame &CurrentFrame, KeyFrame* pKF, const std::set<MapPoint*> &sAlreadyFound, const float th, const int ORBdist);
57 
58  // Project MapPoints using a Similarity Transformation and search matches.
59  // Used in loop detection (Loop Closing)
60  int SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const std::vector<MapPoint*> &vpPoints, std::vector<MapPoint*> &vpMatched, int th);
61 
62  // Search matches between MapPoints in a KeyFrame and ORB in a Frame.
63  // Brute force constrained to ORB that belong to the same vocabulary node (at a certain level)
64  // Used in Relocalisation and Loop Detection
65  int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector<MapPoint*> &vpMapPointMatches);
66  int SearchByBoW(KeyFrame *pKF1, KeyFrame* pKF2, std::vector<MapPoint*> &vpMatches12);
67 
68  // Matching for the Map Initialization (only used in the monocular case)
69  int SearchForInitialization(Frame &F1, Frame &F2, std::vector<cv::Point2f> &vbPrevMatched, std::vector<int> &vnMatches12, int windowSize=10);
70 
71  // Matching to triangulate new MapPoints. Check Epipolar Constraint.
72  int SearchForTriangulation(KeyFrame *pKF1, KeyFrame* pKF2, cv::Mat F12,
73  std::vector<pair<size_t, size_t> > &vMatchedPairs, const bool bOnlyStereo);
74 
75  // Search matches between MapPoints seen in KF1 and KF2 transforming by a Sim3 [s12*R12|t12]
76  // In the stereo and RGB-D case, s12=1
77  int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector<MapPoint *> &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th);
78 
79  // Project MapPoints into KeyFrame and search for duplicated MapPoints.
80  int Fuse(KeyFrame* pKF, const vector<MapPoint *> &vpMapPoints, const float th=3.0);
81 
82  // Project MapPoints into KeyFrame using a given Sim3 and search for duplicated MapPoints.
83  int Fuse(KeyFrame* pKF, cv::Mat Scw, const std::vector<MapPoint*> &vpPoints, float th, vector<MapPoint *> &vpReplacePoint);
84 
85 public:
86 
87  static const int TH_LOW;
88  static const int TH_HIGH;
89  static const int HISTO_LENGTH;
90 
91 
92 protected:
93 
94  bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF);
95 
96  float RadiusByViewingCos(const float &viewCos);
97 
98  void ComputeThreeMaxima(std::vector<int>* histo, const int L, int &ind1, int &ind2, int &ind3);
99 
100  float mfNNratio;
102 };
103 
104 }// namespace ORB_SLAM
105 
106 #endif // ORBMATCHER_H
ORBmatcher(float nnratio=0.6, bool checkOri=true)
Definition: ORBmatcher.cc:41
int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
int SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
Definition: ORBmatcher.cc:1102
int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
Definition: ORBmatcher.cc:657
static const int TH_LOW
Definition: ORBmatcher.h:87
static const int TH_HIGH
Definition: ORBmatcher.h:88
bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF)
Definition: ORBmatcher.cc:140
float RadiusByViewingCos(const float &viewCos)
Definition: ORBmatcher.cc:131
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
Definition: ORBmatcher.cc:1647
int SearchByProjection(Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
int SearchForInitialization(Frame &F1, Frame &F2, std::vector< cv::Point2f > &vbPrevMatched, std::vector< int > &vnMatches12, int windowSize=10)
Definition: ORBmatcher.cc:405
static const int HISTO_LENGTH
Definition: ORBmatcher.h:89
void ComputeThreeMaxima(std::vector< int > *histo, const int L, int &ind1, int &ind2, int &ind3)
Definition: ORBmatcher.cc:1601
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)
Definition: ORBmatcher.cc:825


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05