ORB SLA2
Sim3Solver.h
1 
22 #ifndef SIM3SOLVER_H
23 #define SIM3SOLVER_H
24 
25 #include <opencv2/opencv.hpp>
26 #include <vector>
27 
28 #include "KeyFrame.h"
29 
30 
31 
32 namespace ORB_SLAM2
33 {
34 
36 {
37 public:
38 
39  Sim3Solver(KeyFrame* pKF1, KeyFrame* pKF2, const std::vector<MapPoint*> &vpMatched12, const bool bFixScale = true);
40 
41  void SetRansacParameters(double probability = 0.99, int minInliers = 6 , int maxIterations = 300);
42 
43  cv::Mat find(std::vector<bool> &vbInliers12, int &nInliers);
44 
45  cv::Mat iterate(int nIterations, bool &bNoMore, std::vector<bool> &vbInliers, int &nInliers);
46 
47  cv::Mat GetEstimatedRotation();
48  cv::Mat GetEstimatedTranslation();
49  float GetEstimatedScale();
50 
51 
52 protected:
53 
54  void ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C);
55 
56  void ComputeSim3(cv::Mat &P1, cv::Mat &P2);
57 
58  void CheckInliers();
59 
60  void Project(const std::vector<cv::Mat> &vP3Dw, std::vector<cv::Mat> &vP2D, cv::Mat Tcw, cv::Mat K);
61  void FromCameraToImage(const std::vector<cv::Mat> &vP3Dc, std::vector<cv::Mat> &vP2D, cv::Mat K);
62 
63 
64 protected:
65 
66  // KeyFrames and matches
67  KeyFrame* mpKF1;
68  KeyFrame* mpKF2;
69 
70  std::vector<cv::Mat> mvX3Dc1;
71  std::vector<cv::Mat> mvX3Dc2;
72  std::vector<MapPoint*> mvpMapPoints1;
73  std::vector<MapPoint*> mvpMapPoints2;
74  std::vector<MapPoint*> mvpMatches12;
75  std::vector<size_t> mvnIndices1;
76  std::vector<size_t> mvSigmaSquare1;
77  std::vector<size_t> mvSigmaSquare2;
78  std::vector<size_t> mvnMaxError1;
79  std::vector<size_t> mvnMaxError2;
80 
81  int N;
82  int mN1;
83 
84  // Current Estimation
85  cv::Mat mR12i;
86  cv::Mat mt12i;
87  float ms12i;
88  cv::Mat mT12i;
89  cv::Mat mT21i;
90  std::vector<bool> mvbInliersi;
91  int mnInliersi;
92 
93  // Current Ransac State
94  int mnIterations;
95  std::vector<bool> mvbBestInliers;
96  int mnBestInliers;
97  cv::Mat mBestT12;
98  cv::Mat mBestRotation;
99  cv::Mat mBestTranslation;
100  float mBestScale;
101 
102  // Scale is fixed to 1 in the stereo/RGBD case
103  bool mbFixScale;
104 
105  // Indices for random selection
106  std::vector<size_t> mvAllIndices;
107 
108  // Projections
109  std::vector<cv::Mat> mvP1im1;
110  std::vector<cv::Mat> mvP2im2;
111 
112  // RANSAC probability
113  double mRansacProb;
114 
115  // RANSAC min inliers
116  int mRansacMinInliers;
117 
118  // RANSAC max iterations
119  int mRansacMaxIts;
120 
121  // Threshold inlier/outlier. e = dist(Pi,T_ij*Pj)^2 < 5.991*mSigma2
122  float mTh;
123  float mSigma2;
124 
125  // Calibration
126  cv::Mat mK1;
127  cv::Mat mK2;
128 
129 };
130 
131 } //namespace ORB_SLAM
132 
133 #endif // SIM3SOLVER_H
Definition: KeyFrame.h:43
Definition: Sim3Solver.h:35
Definition: Converter.cpp:24