/** * This file is part of ORB-SLAM2. * * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) * For more information see * * ORB-SLAM2 is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * ORB-SLAM2 is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with ORB-SLAM2. If not, see . */ #ifndef INITIALIZER_H #define INITIALIZER_H #include #include "Frame.h" namespace ORB_SLAM2 { // THIS IS THE INITIALIZER FOR MONOCULAR SLAM. NOT USED IN THE STEREO OR RGBD CASE. class Initializer { typedef pair Match; public: // Fix the reference frame Initializer(const Frame &ReferenceFrame, float sigma = 1.0, int iterations = 200); // Computes in parallel a fundamental matrix and a homography // Selects a model and tries to recover the motion and the structure from motion bool Initialize(const Frame &CurrentFrame, const vector &vMatches12, cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated); private: void FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21); void FindFundamental(vector &vbInliers, float &score, cv::Mat &F21); cv::Mat ComputeH21(const vector &vP1, const vector &vP2); cv::Mat ComputeF21(const vector &vP1, const vector &vP2); float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma); float CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma); bool ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); bool ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D); void Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T); int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, const vector &vMatches12, vector &vbInliers, const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax); void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t); // Keypoints from Reference Frame (Frame 1) vector mvKeys1; // Keypoints from Current Frame (Frame 2) vector mvKeys2; // Current Matches from Reference to Current vector mvMatches12; vector mvbMatched1; // Calibration cv::Mat mK; // Standard Deviation and Variance float mSigma, mSigma2; // Ransac max iterations int mMaxIterations; // Ransac sets vector > mvSets; }; } //namespace ORB_SLAM #endif // INITIALIZER_H