#include <PnPsolver.h>
Public Member Functions | |
| cv::Mat | find (vector< bool > &vbInliers, int &nInliers) |
| cv::Mat | iterate (int nIterations, bool &bNoMore, vector< bool > &vbInliers, int &nInliers) |
| PnPsolver (const Frame &F, const vector< MapPoint * > &vpMapPointMatches) | |
| void | SetRansacParameters (double probability=0.99, int minInliers=8, int maxIterations=300, int minSet=4, float epsilon=0.4, float th2=5.991) |
| ~PnPsolver () | |
Private Member Functions | |
| void | add_correspondence (const double X, const double Y, const double Z, const double u, const double v) |
| void | CheckInliers () |
| void | choose_control_points (void) |
| void | compute_A_and_b_gauss_newton (const double *l_6x10, const double *rho, double cb[4], CvMat *A, CvMat *b) |
| void | compute_barycentric_coordinates (void) |
| void | compute_ccs (const double *betas, const double *ut) |
| void | compute_L_6x10 (const double *ut, double *l_6x10) |
| void | compute_pcs (void) |
| double | compute_pose (double R[3][3], double T[3]) |
| double | compute_R_and_t (const double *ut, const double *betas, double R[3][3], double t[3]) |
| void | compute_rho (double *rho) |
| void | copy_R_and_t (const double R_dst[3][3], const double t_dst[3], double R_src[3][3], double t_src[3]) |
| double | dist2 (const double *p1, const double *p2) |
| double | dot (const double *v1, const double *v2) |
| void | estimate_R_and_t (double R[3][3], double t[3]) |
| void | fill_M (CvMat *M, const int row, const double *alphas, const double u, const double v) |
| void | find_betas_approx_1 (const CvMat *L_6x10, const CvMat *Rho, double *betas) |
| void | find_betas_approx_2 (const CvMat *L_6x10, const CvMat *Rho, double *betas) |
| void | find_betas_approx_3 (const CvMat *L_6x10, const CvMat *Rho, double *betas) |
| void | gauss_newton (const CvMat *L_6x10, const CvMat *Rho, double current_betas[4]) |
| void | mat_to_quat (const double R[3][3], double q[4]) |
| void | print_pose (const double R[3][3], const double t[3]) |
| void | qr_solve (CvMat *A, CvMat *b, CvMat *X) |
| bool | Refine () |
| void | relative_error (double &rot_err, double &transl_err, const double Rtrue[3][3], const double ttrue[3], const double Rest[3][3], const double test[3]) |
| double | reprojection_error (const double R[3][3], const double t[3]) |
| void | reset_correspondences (void) |
| void | set_maximum_number_of_correspondences (const int n) |
| void | solve_for_sign (void) |
Private Attributes | |
| double * | alphas |
| double | ccs [4][3] |
| double | cws [4][3] |
| double | cws_determinant |
| double | fu |
| double | fv |
| int | maximum_number_of_correspondences |
| cv::Mat | mBestTcw |
| int | mnBestInliers |
| int | mnInliersi |
| int | mnIterations |
| int | mnRefinedInliers |
| float | mRansacEpsilon |
| int | mRansacMaxIts |
| int | mRansacMinInliers |
| int | mRansacMinSet |
| double | mRansacProb |
| float | mRansacTh |
| cv::Mat | mRefinedTcw |
| double | mRi [3][3] |
| cv::Mat | mTcwi |
| double | mti [3] |
| vector< size_t > | mvAllIndices |
| vector< bool > | mvbBestInliers |
| vector< bool > | mvbInliersi |
| vector< bool > | mvbRefinedInliers |
| vector< size_t > | mvKeyPointIndices |
| vector< float > | mvMaxError |
| vector< cv::Point2f > | mvP2D |
| vector< cv::Point3f > | mvP3Dw |
| vector< MapPoint * > | mvpMapPointMatches |
| vector< float > | mvSigma2 |
| int | N |
| int | number_of_correspondences |
| double * | pcs |
| double * | pws |
| double | uc |
| double * | us |
| double | vc |
Definition at line 62 of file PnPsolver.h.
Definition at line 67 of file PnPsolver.cc.
| ORB_SLAM2::PnPsolver::~PnPsolver | ( | ) |
Definition at line 112 of file PnPsolver.cc.
|
private |
Definition at line 363 of file PnPsolver.cc.
|
private |
Definition at line 308 of file PnPsolver.cc.
|
private |
Definition at line 375 of file PnPsolver.cc.
|
private |
Definition at line 812 of file PnPsolver.cc.
|
private |
Definition at line 411 of file PnPsolver.cc.
|
private |
Definition at line 453 of file PnPsolver.cc.
|
private |
Definition at line 760 of file PnPsolver.cc.
|
private |
Definition at line 466 of file PnPsolver.cc.
|
private |
Definition at line 477 of file PnPsolver.cc.
|
private |
Definition at line 651 of file PnPsolver.cc.
|
private |
Definition at line 802 of file PnPsolver.cc.
|
private |
Definition at line 527 of file PnPsolver.cc.
|
private |
Definition at line 537 of file PnPsolver.cc.
|
private |
Definition at line 545 of file PnPsolver.cc.
|
private |
Definition at line 569 of file PnPsolver.cc.
|
private |
Definition at line 436 of file PnPsolver.cc.
| cv::Mat ORB_SLAM2::PnPsolver::find | ( | vector< bool > & | vbInliers, |
| int & | nInliers | ||
| ) |
Definition at line 159 of file PnPsolver.cc.
|
private |
Definition at line 667 of file PnPsolver.cc.
|
private |
Definition at line 699 of file PnPsolver.cc.
|
private |
Definition at line 731 of file PnPsolver.cc.
|
private |
Definition at line 840 of file PnPsolver.cc.
| cv::Mat ORB_SLAM2::PnPsolver::iterate | ( | int | nIterations, |
| bool & | bNoMore, | ||
| vector< bool > & | vbInliers, | ||
| int & | nInliers | ||
| ) |
Definition at line 165 of file PnPsolver.cc.
|
private |
Definition at line 984 of file PnPsolver.cc.
|
private |
Definition at line 629 of file PnPsolver.cc.
|
private |
Definition at line 860 of file PnPsolver.cc.
|
private |
Definition at line 260 of file PnPsolver.cc.
|
private |
Definition at line 954 of file PnPsolver.cc.
|
private |
Definition at line 550 of file PnPsolver.cc.
|
private |
Definition at line 358 of file PnPsolver.cc.
|
private |
Definition at line 342 of file PnPsolver.cc.
| void ORB_SLAM2::PnPsolver::SetRansacParameters | ( | double | probability = 0.99, |
| int | minInliers = 8, |
||
| int | maxIterations = 300, |
||
| int | minSet = 4, |
||
| float | epsilon = 0.4, |
||
| float | th2 = 5.991 |
||
| ) |
Definition at line 121 of file PnPsolver.cc.
|
private |
Definition at line 636 of file PnPsolver.cc.
|
private |
Definition at line 131 of file PnPsolver.h.
|
private |
Definition at line 135 of file PnPsolver.h.
|
private |
Definition at line 135 of file PnPsolver.h.
|
private |
Definition at line 136 of file PnPsolver.h.
|
private |
Definition at line 129 of file PnPsolver.h.
|
private |
Definition at line 129 of file PnPsolver.h.
|
private |
Definition at line 132 of file PnPsolver.h.
|
private |
Definition at line 161 of file PnPsolver.h.
|
private |
Definition at line 160 of file PnPsolver.h.
|
private |
Definition at line 155 of file PnPsolver.h.
|
private |
Definition at line 158 of file PnPsolver.h.
|
private |
Definition at line 166 of file PnPsolver.h.
|
private |
Definition at line 184 of file PnPsolver.h.
|
private |
Definition at line 181 of file PnPsolver.h.
|
private |
Definition at line 178 of file PnPsolver.h.
|
private |
Definition at line 190 of file PnPsolver.h.
|
private |
Definition at line 175 of file PnPsolver.h.
|
private |
Definition at line 187 of file PnPsolver.h.
|
private |
Definition at line 164 of file PnPsolver.h.
|
private |
Definition at line 151 of file PnPsolver.h.
|
private |
Definition at line 153 of file PnPsolver.h.
|
private |
Definition at line 152 of file PnPsolver.h.
|
private |
Definition at line 172 of file PnPsolver.h.
|
private |
Definition at line 159 of file PnPsolver.h.
|
private |
Definition at line 154 of file PnPsolver.h.
|
private |
Definition at line 165 of file PnPsolver.h.
|
private |
Definition at line 148 of file PnPsolver.h.
|
private |
Definition at line 193 of file PnPsolver.h.
|
private |
Definition at line 141 of file PnPsolver.h.
|
private |
Definition at line 145 of file PnPsolver.h.
|
private |
Definition at line 138 of file PnPsolver.h.
|
private |
Definition at line 142 of file PnPsolver.h.
|
private |
Definition at line 169 of file PnPsolver.h.
|
private |
Definition at line 133 of file PnPsolver.h.
|
private |
Definition at line 131 of file PnPsolver.h.
|
private |
Definition at line 131 of file PnPsolver.h.
|
private |
Definition at line 129 of file PnPsolver.h.
|
private |
Definition at line 131 of file PnPsolver.h.
|
private |
Definition at line 129 of file PnPsolver.h.