123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135 |
- #ifndef SIM3SOLVER_H
- #define SIM3SOLVER_H
- #include <opencv2/opencv.hpp>
- #include <vector>
- #include "KeyFrame.h"
- namespace ORB_SLAM3
- {
- class Sim3Solver
- {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- Sim3Solver(KeyFrame* pKF1, KeyFrame* pKF2, const std::vector<MapPoint*> &vpMatched12, const bool bFixScale = true,
- const vector<KeyFrame*> vpKeyFrameMatchedMP = vector<KeyFrame*>());
- void SetRansacParameters(double probability = 0.99, int minInliers = 6 , int maxIterations = 300);
- Eigen::Matrix4f find(std::vector<bool> &vbInliers12, int &nInliers);
- Eigen::Matrix4f iterate(int nIterations, bool &bNoMore, std::vector<bool> &vbInliers, int &nInliers);
- Eigen::Matrix4f iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers, bool &bConverge);
- Eigen::Matrix4f GetEstimatedTransformation();
- Eigen::Matrix3f GetEstimatedRotation();
- Eigen::Vector3f GetEstimatedTranslation();
- float GetEstimatedScale();
- protected:
- void ComputeCentroid(Eigen::Matrix3f &P, Eigen::Matrix3f &Pr, Eigen::Vector3f &C);
- void ComputeSim3(Eigen::Matrix3f &P1, Eigen::Matrix3f &P2);
- void CheckInliers();
- void Project(const std::vector<Eigen::Vector3f> &vP3Dw, std::vector<Eigen::Vector2f> &vP2D, Eigen::Matrix4f Tcw, GeometricCamera* pCamera);
- void FromCameraToImage(const std::vector<Eigen::Vector3f> &vP3Dc, std::vector<Eigen::Vector2f> &vP2D, GeometricCamera* pCamera);
- protected:
-
- KeyFrame* mpKF1;
- KeyFrame* mpKF2;
- std::vector<Eigen::Vector3f> mvX3Dc1;
- std::vector<Eigen::Vector3f> mvX3Dc2;
- std::vector<MapPoint*> mvpMapPoints1;
- std::vector<MapPoint*> mvpMapPoints2;
- std::vector<MapPoint*> mvpMatches12;
- std::vector<size_t> mvnIndices1;
- std::vector<size_t> mvSigmaSquare1;
- std::vector<size_t> mvSigmaSquare2;
- std::vector<size_t> mvnMaxError1;
- std::vector<size_t> mvnMaxError2;
- int N;
- int mN1;
-
- Eigen::Matrix3f mR12i;
- Eigen::Vector3f mt12i;
- float ms12i;
- Eigen::Matrix4f mT12i;
- Eigen::Matrix4f mT21i;
- std::vector<bool> mvbInliersi;
- int mnInliersi;
-
- int mnIterations;
- std::vector<bool> mvbBestInliers;
- int mnBestInliers;
- Eigen::Matrix4f mBestT12;
- Eigen::Matrix3f mBestRotation;
- Eigen::Vector3f mBestTranslation;
- float mBestScale;
-
- bool mbFixScale;
-
- std::vector<size_t> mvAllIndices;
-
- std::vector<Eigen::Vector2f> mvP1im1;
- std::vector<Eigen::Vector2f> mvP2im2;
-
- double mRansacProb;
-
- int mRansacMinInliers;
-
- int mRansacMaxIts;
-
- float mTh;
- float mSigma2;
-
-
-
- GeometricCamera* pCamera1, *pCamera2;
- };
- }
- #endif
|