44 Eigen::MatrixXd obj_pts_, Eigen::MatrixXd img_pts_,
45 Eigen::MatrixXd cam_,
int n0);
54 Eigen::Ref<Eigen::Matrix3d> R_, Eigen::Ref<Eigen::Vector3d> t_);
69 double l1,
double l2,
double A5,
double C1,
double C2,
double D1,
70 double D2,
double D3);
77 Eigen::VectorXd
getpoly7(
const Eigen::VectorXd& vin);
87 Eigen::MatrixXd& XXc, Eigen::MatrixXd& XXw, Eigen::Matrix3d& R2,
Eigen::MatrixXd P
Camera Intrinsic Matrix.
void calcampose(Eigen::MatrixXd &XXc, Eigen::MatrixXd &XXw, Eigen::Matrix3d &R2, Eigen::Vector3d &t2)
Function to calculate final pose.
Eigen::MatrixXd cam_intrinsic
Image Points (n X 3) in Camera Co-ordinate system.
Eigen::Vector3d t
Rotation matrix.
Perspective n Point (PnP) Algorithms toolkit for MRPT mrpt_vision_grp.
rpnp(Eigen::MatrixXd obj_pts_, Eigen::MatrixXd img_pts_, Eigen::MatrixXd cam_, int n0)
Number of 2D/3D correspondences.
Eigen::VectorXd getp3p(double l1, double l2, double A5, double C1, double C2, double D1, double D2, double D3)
Function to compute pose using P3P.
Eigen::MatrixXd img_pts
Object Points (n X 3) in Camera Co-ordinate system.
bool compute_pose(Eigen::Ref< Eigen::Matrix3d > R_, Eigen::Ref< Eigen::Vector3d > t_)
Function to compute pose.
Eigen::MatrixXd Q
Transposed Object Points (3 X n) for computations.
Eigen::Matrix3d R
Transposed Image Points (3 X n) for computations.
Eigen::VectorXd getpoly7(const Eigen::VectorXd &vin)
Get Polynomial from input vector.