TwoViewReconstruction.h 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  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 TwoViewReconstruction_H
  19. #define TwoViewReconstruction_H
  20. #include <opencv2/opencv.hpp>
  21. #include <Eigen/Core>
  22. #include <unordered_set>
  23. #include <sophus/se3.hpp>
  24. namespace ORB_SLAM3
  25. {
  26. class TwoViewReconstruction
  27. {
  28. typedef std::pair<int,int> Match;
  29. public:
  30. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  31. // Fix the reference frame
  32. TwoViewReconstruction(const Eigen::Matrix3f& k, float sigma = 1.0, int iterations = 200);
  33. // Computes in parallel a fundamental matrix and a homography
  34. // Selects a model and tries to recover the motion and the structure from motion
  35. bool Reconstruct(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  36. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  37. private:
  38. void FindHomography(std::vector<bool> &vbMatchesInliers, float &score, Eigen::Matrix3f &H21);
  39. void FindFundamental(std::vector<bool> &vbInliers, float &score, Eigen::Matrix3f &F21);
  40. Eigen::Matrix3f ComputeH21(const std::vector<cv::Point2f> &vP1, const std::vector<cv::Point2f> &vP2);
  41. Eigen::Matrix3f ComputeF21(const std::vector<cv::Point2f> &vP1, const std::vector<cv::Point2f> &vP2);
  42. float CheckHomography(const Eigen::Matrix3f &H21, const Eigen::Matrix3f &H12, std::vector<bool> &vbMatchesInliers, float sigma);
  43. float CheckFundamental(const Eigen::Matrix3f &F21, std::vector<bool> &vbMatchesInliers, float sigma);
  44. bool ReconstructF(std::vector<bool> &vbMatchesInliers, Eigen::Matrix3f &F21, Eigen::Matrix3f &K,
  45. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated, float minParallax, int minTriangulated);
  46. bool ReconstructH(std::vector<bool> &vbMatchesInliers, Eigen::Matrix3f &H21, Eigen::Matrix3f &K,
  47. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D,std:: vector<bool> &vbTriangulated, float minParallax, int minTriangulated);
  48. void Normalize(const std::vector<cv::KeyPoint> &vKeys, std::vector<cv::Point2f> &vNormalizedPoints, Eigen::Matrix3f &T);
  49. int CheckRT(const Eigen::Matrix3f &R, const Eigen::Vector3f &t, const std::vector<cv::KeyPoint> &vKeys1, const std::vector<cv::KeyPoint> &vKeys2,
  50. const std::vector<Match> &vMatches12, std::vector<bool> &vbMatchesInliers,
  51. const Eigen::Matrix3f &K, std::vector<cv::Point3f> &vP3D, float th2, std::vector<bool> &vbGood, float &parallax);
  52. void DecomposeE(const Eigen::Matrix3f &E, Eigen::Matrix3f &R1, Eigen::Matrix3f &R2, Eigen::Vector3f &t);
  53. // Keypoints from Reference Frame (Frame 1)
  54. std::vector<cv::KeyPoint> mvKeys1;
  55. // Keypoints from Current Frame (Frame 2)
  56. std::vector<cv::KeyPoint> mvKeys2;
  57. // Current Matches from Reference to Current
  58. std::vector<Match> mvMatches12;
  59. std::vector<bool> mvbMatched1;
  60. // Calibration
  61. Eigen::Matrix3f mK;
  62. // Standard Deviation and Variance
  63. float mSigma, mSigma2;
  64. // Ransac max iterations
  65. int mMaxIterations;
  66. // Ransac sets
  67. std::vector<std::vector<size_t> > mvSets;
  68. };
  69. } //namespace ORB_SLAM
  70. #endif // TwoViewReconstruction_H