#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 61 of file PnPsolver.h.
ORB_SLAM2::PnPsolver::~PnPsolver | ( | ) |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
cv::Mat ORB_SLAM2::PnPsolver::find | ( | vector< bool > & | vbInliers, |
int & | nInliers | ||
) |
|
private |
|
private |
|
private |
|
private |
cv::Mat ORB_SLAM2::PnPsolver::iterate | ( | int | nIterations, |
bool & | bNoMore, | ||
vector< bool > & | vbInliers, | ||
int & | nInliers | ||
) |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
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 |
||
) |
|
private |
|
private |
Definition at line 130 of file PnPsolver.h.
|
private |
Definition at line 134 of file PnPsolver.h.
|
private |
Definition at line 134 of file PnPsolver.h.
|
private |
Definition at line 135 of file PnPsolver.h.
|
private |
Definition at line 128 of file PnPsolver.h.
|
private |
Definition at line 128 of file PnPsolver.h.
|
private |
Definition at line 131 of file PnPsolver.h.
|
private |
Definition at line 160 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 157 of file PnPsolver.h.
|
private |
Definition at line 165 of file PnPsolver.h.
|
private |
Definition at line 183 of file PnPsolver.h.
|
private |
Definition at line 180 of file PnPsolver.h.
|
private |
Definition at line 177 of file PnPsolver.h.
|
private |
Definition at line 189 of file PnPsolver.h.
|
private |
Definition at line 174 of file PnPsolver.h.
|
private |
Definition at line 186 of file PnPsolver.h.
|
private |
Definition at line 163 of file PnPsolver.h.
|
private |
Definition at line 150 of file PnPsolver.h.
|
private |
Definition at line 152 of file PnPsolver.h.
|
private |
Definition at line 151 of file PnPsolver.h.
|
private |
Definition at line 171 of file PnPsolver.h.
|
private |
Definition at line 158 of file PnPsolver.h.
|
private |
Definition at line 153 of file PnPsolver.h.
|
private |
Definition at line 164 of file PnPsolver.h.
|
private |
Definition at line 147 of file PnPsolver.h.
|
private |
Definition at line 192 of file PnPsolver.h.
|
private |
Definition at line 140 of file PnPsolver.h.
|
private |
Definition at line 144 of file PnPsolver.h.
|
private |
Definition at line 137 of file PnPsolver.h.
|
private |
Definition at line 141 of file PnPsolver.h.
|
private |
Definition at line 168 of file PnPsolver.h.
|
private |
Definition at line 132 of file PnPsolver.h.
|
private |
Definition at line 130 of file PnPsolver.h.
|
private |
Definition at line 130 of file PnPsolver.h.
|
private |
Definition at line 128 of file PnPsolver.h.
|
private |
Definition at line 130 of file PnPsolver.h.
|
private |
Definition at line 128 of file PnPsolver.h.