41 Eigen::Vector3d LiftImagePoint(
const Eigen::Vector2d& point) {
42 return point.homogeneous() / std::sqrt(point.squaredNorm() + 1);
48 const std::vector<X_t>& points2D,
const std::vector<Y_t>& points3D) {
49 CHECK_EQ(points2D.size(), 3);
50 CHECK_EQ(points3D.size(), 3);
52 Eigen::Matrix3d points3D_world;
53 points3D_world.col(0) = points3D[0];
54 points3D_world.col(1) = points3D[1];
55 points3D_world.col(2) = points3D[2];
57 const Eigen::Vector3d u = LiftImagePoint(points2D[0]);
58 const Eigen::Vector3d v = LiftImagePoint(points2D[1]);
59 const Eigen::Vector3d w = LiftImagePoint(points2D[2]);
62 const double cos_uv = u.transpose() * v;
63 const double cos_uw = u.transpose() * w;
64 const double cos_vw = v.transpose() * w;
67 const double dist_AB_2 = (points3D[0] - points3D[1]).squaredNorm();
68 const double dist_AC_2 = (points3D[0] - points3D[2]).squaredNorm();
69 const double dist_BC_2 = (points3D[1] - points3D[2]).squaredNorm();
71 const double dist_AB = std::sqrt(dist_AB_2);
73 const double a = dist_BC_2 / dist_AB_2;
74 const double b = dist_AC_2 / dist_AB_2;
77 const double a2 =
a *
a;
78 const double b2 = b * b;
79 const double p = 2 * cos_vw;
80 const double q = 2 * cos_uw;
81 const double r = 2 * cos_uv;
82 const double p2 = p * p;
83 const double p3 = p2 * p;
84 const double q2 = q * q;
85 const double r2 = r * r;
86 const double r3 = r2 * r;
87 const double r4 = r3 * r;
88 const double r5 = r4 * r;
91 Eigen::Matrix<double, 5, 1>
coeffs;
92 coeffs(0) = -2 * b + b2 + a2 + 1 +
a * b * (2 - r2) - 2 *
a;
93 coeffs(1) = -2 * q * a2 - r * p * b2 + 4 * q *
a + (2 * q + p * r) * b +
94 (r2 * q - 2 * q + r * p) *
a * b - 2 * q;
95 coeffs(2) = (2 + q2) * a2 + (p2 + r2 - 2) * b2 - (4 + 2 * q2) *
a -
96 (p * q * r + p2) * b - (p * q * r + r2) *
a * b + q2 + 2;
97 coeffs(3) = -2 * q * a2 - r * p * b2 + 4 * q *
a +
98 (p * r + q * p2 - 2 * q) * b + (r * p + 2 * q) *
a * b - 2 * q;
99 coeffs(4) = a2 + b2 - 2 *
a + (2 - p2) * b - 2 *
a * b + 1;
101 Eigen::VectorXd roots_real;
102 Eigen::VectorXd roots_imag;
104 return std::vector<P3PEstimator::M_t>({});
107 std::vector<M_t> models;
108 models.reserve(roots_real.size());
111 const double kMaxRootImag = 1
e-10;
112 if (std::abs(roots_imag(i)) > kMaxRootImag) {
116 const double x = roots_real(i);
121 const double x2 =
x *
x;
122 const double x3 = x2 *
x;
126 (p2 - p * q * r + r2) *
a + (p2 - r2) * b - p2 + p * q * r - r2;
127 const double b1 = b * bb1 * bb1;
129 ((1 -
a - b) * x2 + (
a - 1) * q *
x -
a + b + 1) *
130 (r3 * (a2 + b2 - 2 *
a - 2 * b + (2 - r2) *
a * b + 1) * x3 +
132 (p + p * a2 - 2 * r * q *
a * b + 2 * r * q * b - 2 * r * q -
133 2 * p *
a - 2 * p * b + p * r2 * b + 4 * r * q *
a +
134 q * r3 *
a * b - 2 * r * q * a2 + 2 * p *
a * b + p * b2 -
137 (r5 * (b2 -
a * b) - r4 * p * q * b +
138 r3 * (q2 - 4 *
a - 2 * q2 *
a + q2 * a2 + 2 * a2 - 2 * b2 + 2) +
139 r2 * (4 * p * q *
a - 2 * p * q *
a * b + 2 * p * q * b - 2 * p * q -
141 r * (p2 * b2 - 2 * p2 * b + 2 * p2 *
a * b - 2 * p2 *
a + p2 +
144 (2 * p * r2 - 2 * r3 * q + p3 - 2 * p2 * q * r + p * q2 * r2) * a2 +
145 (p3 - 2 * p * r2) * b2 +
146 (4 * q * r3 - 4 * p * r2 - 2 * p3 + 4 * p2 * q * r - 2 * p * q2 * r2) *
148 (-2 * q * r3 + p * r4 + 2 * p2 * q * r - 2 * p3) * b +
149 (2 * p3 + 2 * q * r3 - 2 * p2 * q * r) *
a * b + p * q2 * r2 -
150 2 * p2 * q * r + 2 * p * r2 + p3 - 2 * r3 * q);
153 const double y = b0 / b1;
154 const double y2 =
y *
y;
156 const double nu = x2 + y2 - 2 *
x *
y * cos_uv;
158 const double dist_PC = dist_AB / std::sqrt(nu);
159 const double dist_PB =
y * dist_PC;
160 const double dist_PA =
x * dist_PC;
162 Eigen::Matrix3d points3D_camera;
163 points3D_camera.col(0) = u * dist_PA;
164 points3D_camera.col(1) = v * dist_PB;
165 points3D_camera.col(2) = w * dist_PC;
168 const Eigen::Matrix4d transform =
169 Eigen::umeyama(points3D_world, points3D_camera,
false);
170 models.push_back(transform.topLeftCorner<3, 4>());
177 const std::vector<Y_t>& points3D,
178 const M_t& proj_matrix,
179 std::vector<double>* residuals) {
184 const std::vector<X_t>& points2D,
const std::vector<Y_t>& points3D) {
185 CHECK_GE(points2D.size(), 4);
186 CHECK_EQ(points2D.size(), points3D.size());
190 if (!epnp.ComputePose(points2D, points3D, &proj_matrix)) {
191 return std::vector<EPNPEstimator::M_t>({});
194 return std::vector<EPNPEstimator::M_t>({proj_matrix});
198 const std::vector<Y_t>& points3D,
199 const M_t& proj_matrix,
200 std::vector<double>* residuals) {
204 bool EPNPEstimator::ComputePose(
const std::vector<Eigen::Vector2d>& points2D,
205 const std::vector<Eigen::Vector3d>& points3D,
207 points2D_ = &points2D;
208 points3D_ = &points3D;
210 ChooseControlPoints();
212 if (!ComputeBarycentricCoordinates()) {
216 const Eigen::Matrix<double, Eigen::Dynamic, 12> M = ComputeM();
217 const Eigen::Matrix<double, 12, 12> MtM = M.transpose() * M;
219 Eigen::JacobiSVD<Eigen::Matrix<double, 12, 12>> svd(
220 MtM, Eigen::ComputeFullV | Eigen::ComputeFullU);
221 const Eigen::Matrix<double, 12, 12> Ut = svd.matrixU().transpose();
223 const Eigen::Matrix<double, 6, 10> L6x10 = ComputeL6x10(Ut);
224 const Eigen::Matrix<double, 6, 1> rho = ComputeRho();
226 Eigen::Vector4d betas[4];
227 std::array<double, 4> reproj_errors;
228 std::array<Eigen::Matrix3d, 4> Rs;
229 std::array<Eigen::Vector3d, 4> ts;
231 FindBetasApprox1(L6x10, rho, &betas[1]);
232 RunGaussNewton(L6x10, rho, &betas[1]);
233 reproj_errors[1] = ComputeRT(Ut, betas[1], &Rs[1], &ts[1]);
235 FindBetasApprox2(L6x10, rho, &betas[2]);
236 RunGaussNewton(L6x10, rho, &betas[2]);
237 reproj_errors[2] = ComputeRT(Ut, betas[2], &Rs[2], &ts[2]);
239 FindBetasApprox3(L6x10, rho, &betas[3]);
240 RunGaussNewton(L6x10, rho, &betas[3]);
241 reproj_errors[3] = ComputeRT(Ut, betas[3], &Rs[3], &ts[3]);
244 if (reproj_errors[2] < reproj_errors[1]) {
247 if (reproj_errors[3] < reproj_errors[best_idx]) {
251 proj_matrix->leftCols<3>() = Rs[best_idx];
252 proj_matrix->rightCols<1>() = ts[best_idx];
257 void EPNPEstimator::ChooseControlPoints() {
260 for (
size_t i = 0; i < points3D_->size(); ++i) {
261 cws_[0] += (*points3D_)[i];
263 cws_[0] /= points3D_->size();
265 Eigen::Matrix<double, Eigen::Dynamic, 3> PW0(points3D_->size(), 3);
266 for (
size_t i = 0; i < points3D_->size(); ++i) {
267 PW0.row(i) = (*points3D_)[i] - cws_[0];
270 const Eigen::Matrix3d PW0tPW0 = PW0.transpose() * PW0;
271 Eigen::JacobiSVD<Eigen::Matrix3d> svd(
272 PW0tPW0, Eigen::ComputeFullV | Eigen::ComputeFullU);
273 const Eigen::Vector3d D = svd.singularValues();
274 const Eigen::Matrix3d Ut = svd.matrixU().transpose();
276 for (
int i = 1; i < 4; ++i) {
277 const double k = std::sqrt(D(i - 1) / points3D_->size());
278 cws_[i] = cws_[0] + k * Ut.row(i - 1).transpose();
282 bool EPNPEstimator::ComputeBarycentricCoordinates() {
284 for (
int i = 0; i < 3; ++i) {
285 for (
int j = 1; j < 4; ++j) {
286 CC(i, j - 1) = cws_[j][i] - cws_[0][i];
290 if (CC.colPivHouseholderQr().rank() < 3) {
294 const Eigen::Matrix3d CC_inv = CC.inverse();
296 alphas_.resize(points2D_->size());
297 for (
size_t i = 0; i < points3D_->size(); ++i) {
298 for (
int j = 0; j < 3; ++j) {
299 alphas_[i][1 + j] = CC_inv(j, 0) * ((*points3D_)[i][0] - cws_[0][0]) +
300 CC_inv(j, 1) * ((*points3D_)[i][1] - cws_[0][1]) +
301 CC_inv(j, 2) * ((*points3D_)[i][2] - cws_[0][2]);
303 alphas_[i][0] = 1.0 - alphas_[i][1] - alphas_[i][2] - alphas_[i][3];
309 Eigen::Matrix<double, Eigen::Dynamic, 12> EPNPEstimator::ComputeM() {
310 Eigen::Matrix<double, Eigen::Dynamic, 12> M(2 * points2D_->size(), 12);
311 for (
size_t i = 0; i < points3D_->size(); ++i) {
312 for (
size_t j = 0; j < 4; ++j) {
313 M(2 * i, 3 * j) = alphas_[i][j];
314 M(2 * i, 3 * j + 1) = 0.0;
315 M(2 * i, 3 * j + 2) = -alphas_[i][j] * (*points2D_)[i].x();
317 M(2 * i + 1, 3 * j) = 0.0;
318 M(2 * i + 1, 3 * j + 1) = alphas_[i][j];
319 M(2 * i + 1, 3 * j + 2) = -alphas_[i][j] * (*points2D_)[i].y();
325 Eigen::Matrix<double, 6, 10> EPNPEstimator::ComputeL6x10(
326 const Eigen::Matrix<double, 12, 12>& Ut) {
327 Eigen::Matrix<double, 6, 10> L6x10;
329 std::array<std::array<Eigen::Vector3d, 6>, 4> dv;
330 for (
int i = 0; i < 4; ++i) {
332 for (
int j = 0; j < 6; ++j) {
333 dv[i][j][0] = Ut(11 - i, 3 *
a) - Ut(11 - i, 3 * b);
334 dv[i][j][1] = Ut(11 - i, 3 *
a + 1) - Ut(11 - i, 3 * b + 1);
335 dv[i][j][2] = Ut(11 - i, 3 *
a + 2) - Ut(11 - i, 3 * b + 2);
345 for (
int i = 0; i < 6; ++i) {
346 L6x10(i, 0) = dv[0][i].transpose() * dv[0][i];
347 L6x10(i, 1) = 2.0 * dv[0][i].transpose() * dv[1][i];
348 L6x10(i, 2) = dv[1][i].transpose() * dv[1][i];
349 L6x10(i, 3) = 2.0 * dv[0][i].transpose() * dv[2][i];
350 L6x10(i, 4) = 2.0 * dv[1][i].transpose() * dv[2][i];
351 L6x10(i, 5) = dv[2][i].transpose() * dv[2][i];
352 L6x10(i, 6) = 2.0 * dv[0][i].transpose() * dv[3][i];
353 L6x10(i, 7) = 2.0 * dv[1][i].transpose() * dv[3][i];
354 L6x10(i, 8) = 2.0 * dv[2][i].transpose() * dv[3][i];
355 L6x10(i, 9) = dv[3][i].transpose() * dv[3][i];
361 Eigen::Matrix<double, 6, 1> EPNPEstimator::ComputeRho() {
362 Eigen::Matrix<double, 6, 1> rho;
363 rho[0] = (cws_[0] - cws_[1]).squaredNorm();
364 rho[1] = (cws_[0] - cws_[2]).squaredNorm();
365 rho[2] = (cws_[0] - cws_[3]).squaredNorm();
366 rho[3] = (cws_[1] - cws_[2]).squaredNorm();
367 rho[4] = (cws_[1] - cws_[3]).squaredNorm();
368 rho[5] = (cws_[2] - cws_[3]).squaredNorm();
375 void EPNPEstimator::FindBetasApprox1(
const Eigen::Matrix<double, 6, 10>& L6x10,
376 const Eigen::Matrix<double, 6, 1>& rho,
377 Eigen::Vector4d* betas) {
378 Eigen::Matrix<double, 6, 4> L_6x4;
379 for (
int i = 0; i < 6; ++i) {
380 L_6x4(i, 0) = L6x10(i, 0);
381 L_6x4(i, 1) = L6x10(i, 1);
382 L_6x4(i, 2) = L6x10(i, 3);
383 L_6x4(i, 3) = L6x10(i, 6);
386 Eigen::JacobiSVD<Eigen::Matrix<double, 6, 4>> svd(
387 L_6x4, Eigen::ComputeFullV | Eigen::ComputeFullU);
388 Eigen::Matrix<double, 6, 1> Rho_temp = rho;
389 const Eigen::Matrix<double, 4, 1> b4 = svd.solve(Rho_temp);
392 (*betas)[0] = std::sqrt(-b4[0]);
393 (*betas)[1] = -b4[1] / (*betas)[0];
394 (*betas)[2] = -b4[2] / (*betas)[0];
395 (*betas)[3] = -b4[3] / (*betas)[0];
397 (*betas)[0] = std::sqrt(b4[0]);
398 (*betas)[1] = b4[1] / (*betas)[0];
399 (*betas)[2] = b4[2] / (*betas)[0];
400 (*betas)[3] = b4[3] / (*betas)[0];
407 void EPNPEstimator::FindBetasApprox2(
const Eigen::Matrix<double, 6, 10>& L6x10,
408 const Eigen::Matrix<double, 6, 1>& rho,
409 Eigen::Vector4d* betas) {
410 Eigen::Matrix<double, 6, 3> L_6x3(6, 3);
412 for (
int i = 0; i < 6; ++i) {
413 L_6x3(i, 0) = L6x10(i, 0);
414 L_6x3(i, 1) = L6x10(i, 1);
415 L_6x3(i, 2) = L6x10(i, 2);
418 Eigen::JacobiSVD<Eigen::Matrix<double, 6, 3>> svd(
419 L_6x3, Eigen::ComputeFullV | Eigen::ComputeFullU);
420 Eigen::Matrix<double, 6, 1> Rho_temp = rho;
421 const Eigen::Matrix<double, 3, 1> b3 = svd.solve(Rho_temp);
424 (*betas)[0] = std::sqrt(-b3[0]);
425 (*betas)[1] = (b3[2] < 0) ? std::sqrt(-b3[2]) : 0.0;
427 (*betas)[0] = std::sqrt(b3[0]);
428 (*betas)[1] = (b3[2] > 0) ? std::sqrt(b3[2]) : 0.0;
432 (*betas)[0] = -(*betas)[0];
442 void EPNPEstimator::FindBetasApprox3(
const Eigen::Matrix<double, 6, 10>& L6x10,
443 const Eigen::Matrix<double, 6, 1>& rho,
444 Eigen::Vector4d* betas) {
445 Eigen::JacobiSVD<Eigen::Matrix<double, 6, 5>> svd(
446 L6x10.leftCols<5>(), Eigen::ComputeFullV | Eigen::ComputeFullU);
447 Eigen::Matrix<double, 6, 1> Rho_temp = rho;
448 const Eigen::Matrix<double, 5, 1> b5 = svd.solve(Rho_temp);
451 (*betas)[0] = std::sqrt(-b5[0]);
452 (*betas)[1] = (b5[2] < 0) ? std::sqrt(-b5[2]) : 0.0;
454 (*betas)[0] = std::sqrt(b5[0]);
455 (*betas)[1] = (b5[2] > 0) ? std::sqrt(b5[2]) : 0.0;
458 (*betas)[0] = -(*betas)[0];
460 (*betas)[2] = b5[3] / (*betas)[0];
464 void EPNPEstimator::RunGaussNewton(
const Eigen::Matrix<double, 6, 10>& L6x10,
465 const Eigen::Matrix<double, 6, 1>& rho,
466 Eigen::Vector4d* betas) {
467 Eigen::Matrix<double, 6, 4> A;
468 Eigen::Matrix<double, 6, 1> b;
470 const int kNumIterations = 5;
471 for (
int k = 0; k < kNumIterations; ++k) {
472 for (
int i = 0; i < 6; ++i) {
473 A(i, 0) = 2 * L6x10(i, 0) * (*betas)[0] + L6x10(i, 1) * (*betas)[1] +
474 L6x10(i, 3) * (*betas)[2] + L6x10(i, 6) * (*betas)[3];
475 A(i, 1) = L6x10(i, 1) * (*betas)[0] + 2 * L6x10(i, 2) * (*betas)[1] +
476 L6x10(i, 4) * (*betas)[2] + L6x10(i, 7) * (*betas)[3];
477 A(i, 2) = L6x10(i, 3) * (*betas)[0] + L6x10(i, 4) * (*betas)[1] +
478 2 * L6x10(i, 5) * (*betas)[2] + L6x10(i, 8) * (*betas)[3];
479 A(i, 3) = L6x10(i, 6) * (*betas)[0] + L6x10(i, 7) * (*betas)[1] +
480 L6x10(i, 8) * (*betas)[2] + 2 * L6x10(i, 9) * (*betas)[3];
482 b(i) = rho[i] - (L6x10(i, 0) * (*betas)[0] * (*betas)[0] +
483 L6x10(i, 1) * (*betas)[0] * (*betas)[1] +
484 L6x10(i, 2) * (*betas)[1] * (*betas)[1] +
485 L6x10(i, 3) * (*betas)[0] * (*betas)[2] +
486 L6x10(i, 4) * (*betas)[1] * (*betas)[2] +
487 L6x10(i, 5) * (*betas)[2] * (*betas)[2] +
488 L6x10(i, 6) * (*betas)[0] * (*betas)[3] +
489 L6x10(i, 7) * (*betas)[1] * (*betas)[3] +
490 L6x10(i, 8) * (*betas)[2] * (*betas)[3] +
491 L6x10(i, 9) * (*betas)[3] * (*betas)[3]);
494 const Eigen::Vector4d
x = A.colPivHouseholderQr().solve(b);
500 double EPNPEstimator::ComputeRT(
const Eigen::Matrix<double, 12, 12>& Ut,
501 const Eigen::Vector4d& betas,
502 Eigen::Matrix3d* R, Eigen::Vector3d* t) {
503 ComputeCcs(betas, Ut);
510 return ComputeTotalReprojectionError(*R, *t);
513 void EPNPEstimator::ComputeCcs(
const Eigen::Vector4d& betas,
514 const Eigen::Matrix<double, 12, 12>& Ut) {
515 for (
int i = 0; i < 4; ++i) {
516 ccs_[i][0] = ccs_[i][1] = ccs_[i][2] = 0.0;
519 for (
int i = 0; i < 4; ++i) {
520 for (
int j = 0; j < 4; ++j) {
521 for (
int k = 0; k < 3; ++k) {
522 ccs_[j][k] += betas[i] * Ut(11 - i, 3 * j + k);
528 void EPNPEstimator::ComputePcs() {
529 pcs_.resize(points2D_->size());
530 for (
size_t i = 0; i < points3D_->size(); ++i) {
531 for (
int j = 0; j < 3; ++j) {
532 pcs_[i][j] = alphas_[i][0] * ccs_[0][j] + alphas_[i][1] * ccs_[1][j] +
533 alphas_[i][2] * ccs_[2][j] + alphas_[i][3] * ccs_[3][j];
538 void EPNPEstimator::SolveForSign() {
539 if (pcs_[0][2] < 0.0) {
540 for (
int i = 0; i < 4; ++i) {
543 for (
size_t i = 0; i < points3D_->size(); ++i) {
549 void EPNPEstimator::EstimateRT(Eigen::Matrix3d* R, Eigen::Vector3d* t) {
550 Eigen::Vector3d pc0 = Eigen::Vector3d::Zero();
551 Eigen::Vector3d pw0 = Eigen::Vector3d::Zero();
553 for (
size_t i = 0; i < points3D_->size(); ++i) {
555 pw0 += (*points3D_)[i];
557 pc0 /= points3D_->size();
558 pw0 /= points3D_->size();
560 Eigen::Matrix3d abt = Eigen::Matrix3d::Zero();
561 for (
size_t i = 0; i < points3D_->size(); ++i) {
562 for (
int j = 0; j < 3; ++j) {
563 abt(j, 0) += (pcs_[i][j] - pc0[j]) * ((*points3D_)[i][0] - pw0[0]);
564 abt(j, 1) += (pcs_[i][j] - pc0[j]) * ((*points3D_)[i][1] - pw0[1]);
565 abt(j, 2) += (pcs_[i][j] - pc0[j]) * ((*points3D_)[i][2] - pw0[2]);
569 Eigen::JacobiSVD<Eigen::Matrix3d> svd(
570 abt, Eigen::ComputeFullV | Eigen::ComputeFullU);
571 const Eigen::Matrix3d abt_U = svd.matrixU();
572 const Eigen::Matrix3d abt_V = svd.matrixV();
574 for (
int i = 0; i < 3; ++i) {
575 for (
int j = 0; j < 3; ++j) {
576 (*R)(i, j) = abt_U.row(i) * abt_V.row(j).transpose();
580 if (R->determinant() < 0) {
581 Eigen::Matrix3d Abt_v_prime = abt_V;
582 Abt_v_prime.col(2) = -abt_V.col(2);
583 for (
int i = 0; i < 3; ++i) {
584 for (
int j = 0; j < 3; ++j) {
585 (*R)(i, j) = abt_U.row(i) * Abt_v_prime.row(j).transpose();
593 double EPNPEstimator::ComputeTotalReprojectionError(
const Eigen::Matrix3d& R,
594 const Eigen::Vector3d& t) {
596 proj_matrix.leftCols<3>() = R;
597 proj_matrix.rightCols<1>() = t;
599 std::vector<double> residuals;
603 double reproj_error = 0.0;
604 for (
const double residual : residuals) {
605 reproj_error += std::sqrt(residual);
static void Residuals(const std::vector< X_t > &points2D, const std::vector< Y_t > &points3D, const M_t &proj_matrix, std::vector< double > *residuals)
static std::vector< M_t > Estimate(const std::vector< X_t > &points2D, const std::vector< Y_t > &points3D)
static std::vector< M_t > Estimate(const std::vector< X_t > &points2D, const std::vector< Y_t > &points3D)
static void Residuals(const std::vector< X_t > &points2D, const std::vector< Y_t > &points3D, const M_t &proj_matrix, std::vector< double > *residuals)
Matrix< double, 3, 4 > Matrix3x4d
bool FindPolynomialRootsCompanionMatrix(const Eigen::VectorXd &coeffs_all, Eigen::VectorXd *real, Eigen::VectorXd *imag)
void ComputeSquaredReprojectionError(const std::vector< Eigen::Vector2d > &points2D, const std::vector< Eigen::Vector3d > &points3D, const Eigen::Matrix3x4d &proj_matrix, std::vector< double > *residuals)
Eigen::MatrixXd::Index Index