14 #include <Eigen/Dense> 16 #include <Eigen/StdVector> 20 #include <mrpt/config.h> 21 #if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM < 0x240 22 #undef MRPT_HAS_OPENCV 23 #define MRPT_HAS_OPENCV 0 30 Eigen::MatrixXd obj_pts_, Eigen::MatrixXd img_pts_, Eigen::MatrixXd cam_,
41 Q = Eigen::MatrixXd::Ones(3,
n);
52 for (
int i = 0; i <
n; i++) sum_ +=
F[i] *
R *
P.col(i);
58 for (
int i = 0; i <
n; i++)
Q.col(i) =
R *
P.col(i) +
t;
63 Eigen::Matrix4d Q_(4, 4);
65 Q_ <<
q(0), -
q(1), -
q(2), -
q(3),
q(1),
q(0), -
q(3),
q(2),
q(2),
q(3),
q(0),
66 -
q(1),
q(3), -
q(2),
q(1),
q(0);
73 Eigen::Matrix4d Q_(4, 4);
75 Q_ <<
q(0), -
q(1), -
q(2), -
q(3),
q(1),
q(0),
q(3), -
q(2),
q(2), -
q(3),
q(0),
76 q(1),
q(3),
q(2), -
q(1),
q(0);
83 for (
int i = 0; i <
n; i++)
Q.col(i) =
F[i] *
Q.col(i);
85 Eigen::Vector3d P_bar, Q_bar;
86 P_bar =
P.rowwise().mean();
87 Q_bar =
Q.rowwise().mean();
89 for (
int i = 0; i <
n; i++)
91 P.col(i) =
P.col(i) - P_bar;
92 Q.col(i) =
Q.col(i) - Q_bar;
150 for (
int i = 0; i <
n; i++)
152 Eigen::Vector4d q1, q2;
158 Eigen::EigenSolver<Eigen::Matrix4d> es(A);
160 const Eigen::Matrix4d Ae = es.pseudoEigenvalueMatrix();
163 for (
int i = 0; i < 4; i++) D[i] = Ae(i, i);
165 Eigen::Matrix4d V_mat = es.pseudoEigenvectors();
167 Eigen::Vector4d::Index max_index;
169 D.maxCoeff(&max_index);
173 V = V_mat.col(max_index);
175 Eigen::Quaterniond
q(V(0), V(1), V(2), V(3));
177 R =
q.toRotationMatrix();
185 Eigen::Matrix3d I3 = Eigen::MatrixXd::Identity(3, 3);
187 for (
int i = 0; i <
n; i++)
189 vec = (I3 -
F[i]) *
Q.col(i);
190 err2 += vec.squaredNorm();
195 Eigen::Ref<Eigen::Matrix3d> R_, Eigen::Ref<Eigen::Vector3d> t_)
199 Eigen::VectorXd p_bar;
200 Eigen::Matrix3d sum_F, I3;
201 I3 = Eigen::MatrixXd::Identity(3, 3);
204 p_bar =
P.rowwise().mean();
206 for (i = 0; i <
n; i++)
209 F[i] =
Q.col(i) *
Q.col(i).transpose() /
Q.col(i).squaredNorm();
210 sum_F = sum_F +
F[i];
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.
GLdouble GLdouble GLdouble GLdouble q
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 .
Lu Hage Mjolsness - Iterative PnP Algorithm (Eigen Implementation.
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::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
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.