18 #include <Eigen/Dense> 20 #include <Eigen/StdVector> 22 #define TOL_LHM 0.00001 23 #define EPSILON_LHM 0.00000001 51 std::vector<Eigen::Matrix3d>
F;
59 lhm(Eigen::MatrixXd obj_pts_, Eigen::MatrixXd img_pts_,
60 Eigen::MatrixXd cam_,
int n0);
70 Eigen::Ref<Eigen::Matrix3d> R_, Eigen::Ref<Eigen::Vector3d> t_);
94 Eigen::Matrix4d
qMatQ(Eigen::VectorXd q);
101 Eigen::Matrix4d
qMatW(Eigen::VectorXd q);
Eigen::MatrixXd img_pts
Object points in Camera Co-ordinate system.
void xform()
Transform object points in Body frame (Landmark Frame) to estimated Camera Frame. ...
Eigen::MatrixXd P
Camera intrinsic matrix.
double err2
Error variable for convergence selection.
void estimate_t()
Function to estimate translation given an estimated rotation matrix.
Eigen::Matrix4d qMatW(Eigen::VectorXd q)
Iternal Function of quaternion.
Eigen::Matrix3d G
Matrix for internal computations.
Perspective n Point (PnP) Algorithms toolkit for MRPT mrpt_vision_grp.
int n
Error variable for convergence selection.
void absKernel()
Function to compute pose during an iteration.
double err
Storage matrix for each point.
Eigen::MatrixXd Q
Trnaspose of Object points .
std::vector< Eigen::Matrix3d > F
Translation Vector.
lhm(Eigen::MatrixXd obj_pts_, Eigen::MatrixXd img_pts_, Eigen::MatrixXd cam_, int n0)
Number of 2d/3d correspondences.
Eigen::Matrix3d R
Transpose of Image points .
Eigen::Vector3d t
Rotation Matrix.
Eigen::MatrixXd cam_intrinsic
Image points in pixel co-ordinates.
bool compute_pose(Eigen::Ref< Eigen::Matrix3d > R_, Eigen::Ref< Eigen::Vector3d > t_)
Function to compute pose using LHM PnP algorithm.
Eigen::Matrix4d qMatQ(Eigen::VectorXd q)
Iternal Function of quaternion.