Sim3Solver.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135
  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 SIM3SOLVER_H
  19. #define SIM3SOLVER_H
  20. #include <opencv2/opencv.hpp>
  21. #include <vector>
  22. #include "KeyFrame.h"
  23. namespace ORB_SLAM3
  24. {
  25. class Sim3Solver
  26. {
  27. public:
  28. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  29. Sim3Solver(KeyFrame* pKF1, KeyFrame* pKF2, const std::vector<MapPoint*> &vpMatched12, const bool bFixScale = true,
  30. const vector<KeyFrame*> vpKeyFrameMatchedMP = vector<KeyFrame*>());
  31. void SetRansacParameters(double probability = 0.99, int minInliers = 6 , int maxIterations = 300);
  32. Eigen::Matrix4f find(std::vector<bool> &vbInliers12, int &nInliers);
  33. Eigen::Matrix4f iterate(int nIterations, bool &bNoMore, std::vector<bool> &vbInliers, int &nInliers);
  34. Eigen::Matrix4f iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers, bool &bConverge);
  35. Eigen::Matrix4f GetEstimatedTransformation();
  36. Eigen::Matrix3f GetEstimatedRotation();
  37. Eigen::Vector3f GetEstimatedTranslation();
  38. float GetEstimatedScale();
  39. protected:
  40. void ComputeCentroid(Eigen::Matrix3f &P, Eigen::Matrix3f &Pr, Eigen::Vector3f &C);
  41. void ComputeSim3(Eigen::Matrix3f &P1, Eigen::Matrix3f &P2);
  42. void CheckInliers();
  43. void Project(const std::vector<Eigen::Vector3f> &vP3Dw, std::vector<Eigen::Vector2f> &vP2D, Eigen::Matrix4f Tcw, GeometricCamera* pCamera);
  44. void FromCameraToImage(const std::vector<Eigen::Vector3f> &vP3Dc, std::vector<Eigen::Vector2f> &vP2D, GeometricCamera* pCamera);
  45. protected:
  46. // KeyFrames and matches
  47. KeyFrame* mpKF1;
  48. KeyFrame* mpKF2;
  49. std::vector<Eigen::Vector3f> mvX3Dc1;
  50. std::vector<Eigen::Vector3f> mvX3Dc2;
  51. std::vector<MapPoint*> mvpMapPoints1;
  52. std::vector<MapPoint*> mvpMapPoints2;
  53. std::vector<MapPoint*> mvpMatches12;
  54. std::vector<size_t> mvnIndices1;
  55. std::vector<size_t> mvSigmaSquare1;
  56. std::vector<size_t> mvSigmaSquare2;
  57. std::vector<size_t> mvnMaxError1;
  58. std::vector<size_t> mvnMaxError2;
  59. int N;
  60. int mN1;
  61. // Current Estimation
  62. Eigen::Matrix3f mR12i;
  63. Eigen::Vector3f mt12i;
  64. float ms12i;
  65. Eigen::Matrix4f mT12i;
  66. Eigen::Matrix4f mT21i;
  67. std::vector<bool> mvbInliersi;
  68. int mnInliersi;
  69. // Current Ransac State
  70. int mnIterations;
  71. std::vector<bool> mvbBestInliers;
  72. int mnBestInliers;
  73. Eigen::Matrix4f mBestT12;
  74. Eigen::Matrix3f mBestRotation;
  75. Eigen::Vector3f mBestTranslation;
  76. float mBestScale;
  77. // Scale is fixed to 1 in the stereo/RGBD case
  78. bool mbFixScale;
  79. // Indices for random selection
  80. std::vector<size_t> mvAllIndices;
  81. // Projections
  82. std::vector<Eigen::Vector2f> mvP1im1;
  83. std::vector<Eigen::Vector2f> mvP2im2;
  84. // RANSAC probability
  85. double mRansacProb;
  86. // RANSAC min inliers
  87. int mRansacMinInliers;
  88. // RANSAC max iterations
  89. int mRansacMaxIts;
  90. // Threshold inlier/outlier. e = dist(Pi,T_ij*Pj)^2 < 5.991*mSigma2
  91. float mTh;
  92. float mSigma2;
  93. // Calibration
  94. //cv::Mat mK1;
  95. //cv::Mat mK2;
  96. GeometricCamera* pCamera1, *pCamera2;
  97. };
  98. } //namespace ORB_SLAM
  99. #endif // SIM3SOLVER_H