ORB SLA2
PnPsolver.h
1 
51 #ifndef PNPSOLVER_H
52 #define PNPSOLVER_H
53 
54 #include <opencv2/core/core.hpp>
55 #include "MapPoint.h"
56 #include "Frame.h"
57 
58 namespace ORB_SLAM2
59 {
60 
61 class PnPsolver {
62  public:
63  PnPsolver(const Frame &F, const vector<MapPoint*> &vpMapPointMatches);
64 
65  ~PnPsolver();
66 
67  void SetRansacParameters(double probability = 0.99, int minInliers = 8 , int maxIterations = 300, int minSet = 4, float epsilon = 0.4,
68  float th2 = 5.991);
69 
70  cv::Mat find(vector<bool> &vbInliers, int &nInliers);
71 
72  cv::Mat iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers);
73 
74  private:
75 
76  void CheckInliers();
77  bool Refine();
78 
79  // Functions from the original EPnP code
80  void set_maximum_number_of_correspondences(const int n);
81  void reset_correspondences(void);
82  void add_correspondence(const double X, const double Y, const double Z,
83  const double u, const double v);
84 
85  double compute_pose(double R[3][3], double T[3]);
86 
87  void relative_error(double & rot_err, double & transl_err,
88  const double Rtrue[3][3], const double ttrue[3],
89  const double Rest[3][3], const double test[3]);
90 
91  void print_pose(const double R[3][3], const double t[3]);
92  double reprojection_error(const double R[3][3], const double t[3]);
93 
94  void choose_control_points(void);
95  void compute_barycentric_coordinates(void);
96  void fill_M(CvMat * M, const int row, const double * alphas, const double u, const double v);
97  void compute_ccs(const double * betas, const double * ut);
98  void compute_pcs(void);
99 
100  void solve_for_sign(void);
101 
102  void find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho, double * betas);
103  void find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho, double * betas);
104  void find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho, double * betas);
105  void qr_solve(CvMat * A, CvMat * b, CvMat * X);
106 
107  double dot(const double * v1, const double * v2);
108  double dist2(const double * p1, const double * p2);
109 
110  void compute_rho(double * rho);
111  void compute_L_6x10(const double * ut, double * l_6x10);
112 
113  void gauss_newton(const CvMat * L_6x10, const CvMat * Rho, double current_betas[4]);
114  void compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho,
115  double cb[4], CvMat * A, CvMat * b);
116 
117  double compute_R_and_t(const double * ut, const double * betas,
118  double R[3][3], double t[3]);
119 
120  void estimate_R_and_t(double R[3][3], double t[3]);
121 
122  void copy_R_and_t(const double R_dst[3][3], const double t_dst[3],
123  double R_src[3][3], double t_src[3]);
124 
125  void mat_to_quat(const double R[3][3], double q[4]);
126 
127 
128  double uc, vc, fu, fv;
129 
130  double * pws, * us, * alphas, * pcs;
131  int maximum_number_of_correspondences;
132  int number_of_correspondences;
133 
134  double cws[4][3], ccs[4][3];
135  double cws_determinant;
136 
137  vector<MapPoint*> mvpMapPointMatches;
138 
139  // 2D Points
140  vector<cv::Point2f> mvP2D;
141  vector<float> mvSigma2;
142 
143  // 3D Points
144  vector<cv::Point3f> mvP3Dw;
145 
146  // Index in Frame
147  vector<size_t> mvKeyPointIndices;
148 
149  // Current Estimation
150  double mRi[3][3];
151  double mti[3];
152  cv::Mat mTcwi;
153  vector<bool> mvbInliersi;
154  int mnInliersi;
155 
156  // Current Ransac State
157  int mnIterations;
158  vector<bool> mvbBestInliers;
159  int mnBestInliers;
160  cv::Mat mBestTcw;
161 
162  // Refined
163  cv::Mat mRefinedTcw;
164  vector<bool> mvbRefinedInliers;
165  int mnRefinedInliers;
166 
167  // Number of Correspondences
168  int N;
169 
170  // Indices for random selection [0 .. N-1]
171  vector<size_t> mvAllIndices;
172 
173  // RANSAC probability
174  double mRansacProb;
175 
176  // RANSAC min inliers
177  int mRansacMinInliers;
178 
179  // RANSAC max iterations
180  int mRansacMaxIts;
181 
182  // RANSAC expected inliers/total ratio
183  float mRansacEpsilon;
184 
185  // RANSAC Threshold inlier/outlier. Max error e = dist(P1,T_12*P2)^2
186  float mRansacTh;
187 
188  // RANSAC Minimun Set used at each iteration
189  int mRansacMinSet;
190 
191  // Max square error associated with scale level. Max error = th*th*sigma(level)*sigma(level)
192  vector<float> mvMaxError;
193 
194 };
195 
196 } //namespace ORB_SLAM
197 
198 #endif //PNPSOLVER_H
Definition: Frame.h:43
Definition: Converter.cpp:24
Definition: PnPsolver.h:61