26 #include<opencv2/core/core.hpp> 27 #include<opencv2/features2d/features2d.hpp> 41 ORBmatcher(
float nnratio=0.6,
bool checkOri=
true);
60 int SearchByProjection(
KeyFrame* pKF, cv::Mat Scw,
const std::vector<MapPoint*> &vpPoints, std::vector<MapPoint*> &vpMatched,
int th);
73 std::vector<pair<size_t, size_t> > &vMatchedPairs,
const bool bOnlyStereo);
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);
80 int Fuse(
KeyFrame* pKF,
const vector<MapPoint *> &vpMapPoints,
const float th=3.0);
83 int Fuse(
KeyFrame* pKF, cv::Mat Scw,
const std::vector<MapPoint*> &vpPoints,
float th, vector<MapPoint *> &vpReplacePoint);
98 void ComputeThreeMaxima(std::vector<int>* histo,
const int L,
int &ind1,
int &ind2,
int &ind3);
106 #endif // ORBMATCHER_H ORBmatcher(float nnratio=0.6, bool checkOri=true)
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)
int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF)
float RadiusByViewingCos(const float &viewCos)
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
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)
static const int HISTO_LENGTH
void ComputeThreeMaxima(std::vector< int > *histo, const int L, int &ind1, int &ind2, int &ind3)
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)