17 #include <mrpt/config.h> 18 #if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM < 0x240 19 #undef MRPT_HAS_OPENCV 20 #define MRPT_HAS_OPENCV 0 36 fx = cam_intrinsic(0, 0);
37 fy = cam_intrinsic(1, 1);
38 cx = cam_intrinsic(0, 2);
39 cy = cam_intrinsic(1, 2);
40 init_inverse_parameters();
49 init_inverse_parameters();
55 if (cameraMatrix.depth() == CV_32F)
56 init_camera_parameters<float>(cameraMatrix);
58 init_camera_parameters<double>(cameraMatrix);
59 init_inverse_parameters();
63 cv::Mat&
R, cv::Mat& tvec,
const cv::Mat& opoints,
const cv::Mat& ipoints)
65 double rotation_matrix[3][3], translation[3];
66 std::vector<double>
points;
67 if (opoints.depth() == ipoints.depth())
69 if (opoints.depth() == CV_32F)
70 extract_points<cv::Point3f, cv::Point2f>(opoints, ipoints,
points);
72 extract_points<cv::Point3d, cv::Point2d>(opoints, ipoints,
points);
74 else if (opoints.depth() == CV_32F)
75 extract_points<cv::Point3f, cv::Point2d>(opoints, ipoints,
points);
77 extract_points<cv::Point3d, cv::Point2f>(opoints, ipoints,
points);
84 cv::Mat(3, 1, CV_64F, translation).copyTo(tvec);
85 cv::Mat(3, 3, CV_64F, rotation_matrix).copyTo(
R);
92 Eigen::Ref<Eigen::Matrix3d>
R, Eigen::Ref<Eigen::Vector3d>
t,
93 Eigen::MatrixXd obj_pts, Eigen::MatrixXd img_pts)
95 double rotation_matrix[3][3], translation[3];
96 std::vector<double>
points;
97 extract_points(obj_pts, img_pts,
points);
103 R = Eigen::Map<Eigen::Matrix3d>((
double*)rotation_matrix);
104 t = Eigen::Map<Eigen::Vector3d>(translation);
109 double R[3][3],
double t[3],
double mu0,
double mv0,
double X0,
double Y0,
110 double Z0,
double mu1,
double mv1,
double X1,
double Y1,
double Z1,
111 double mu2,
double mv2,
double X2,
double Y2,
double Z2,
double mu3,
112 double mv3,
double X3,
double Y3,
double Z3)
114 double Rs[4][3][3], ts[4][3];
117 Rs, ts, mu0, mv0, X0, Y0, Z0, mu1, mv1, X1, Y1, Z1, mu2, mv2, X2, Y2,
120 if (
n == 0)
return false;
123 double min_reproj = 0;
124 for (
int i = 0; i <
n; i++)
127 Rs[i][0][0] * X3 + Rs[i][0][1] * Y3 + Rs[i][0][2] * Z3 + ts[i][0];
129 Rs[i][1][0] * X3 + Rs[i][1][1] * Y3 + Rs[i][1][2] * Z3 + ts[i][1];
131 Rs[i][2][0] * X3 + Rs[i][2][1] * Y3 + Rs[i][2][2] * Z3 + ts[i][2];
132 double mu3p = cx + fx * X3p / Z3p;
133 double mv3p = cy + fy * Y3p / Z3p;
135 (mu3p - mu3) * (mu3p - mu3) + (mv3p - mv3) * (mv3p - mv3);
136 if (i == 0 || min_reproj > reproj)
143 for (
int i = 0; i < 3; i++)
145 for (
int j = 0; j < 3; j++)
R[i][j] = Rs[ns][i][j];
153 double R[4][3][3],
double t[4][3],
double mu0,
double mv0,
double X0,
154 double Y0,
double Z0,
double mu1,
double mv1,
double X1,
double Y1,
155 double Z1,
double mu2,
double mv2,
double X2,
double Y2,
double Z2)
157 double mk0, mk1, mk2;
160 mu0 = inv_fx * mu0 - cx_fx;
161 mv0 = inv_fy * mv0 - cy_fy;
162 norm = sqrt(mu0 * mu0 + mv0 * mv0 + 1);
167 mu1 = inv_fx * mu1 - cx_fx;
168 mv1 = inv_fy * mv1 - cy_fy;
169 norm = sqrt(mu1 * mu1 + mv1 * mv1 + 1);
174 mu2 = inv_fx * mu2 - cx_fx;
175 mv2 = inv_fy * mv2 - cy_fy;
176 norm = sqrt(mu2 * mu2 + mv2 * mv2 + 1);
183 (X1 - X2) * (X1 - X2) + (Y1 - Y2) * (Y1 - Y2) + (Z1 - Z2) * (Z1 - Z2));
185 (X0 - X2) * (X0 - X2) + (Y0 - Y2) * (Y0 - Y2) + (Z0 - Z2) * (Z0 - Z2));
187 (X0 - X1) * (X0 - X1) + (Y0 - Y1) * (Y0 - Y1) + (Z0 - Z1) * (Z0 - Z1));
191 cosines[0] = mu1 * mu2 + mv1 * mv2 + mk1 * mk2;
192 cosines[1] = mu0 * mu2 + mv0 * mv2 + mk0 * mk2;
193 cosines[2] = mu0 * mu1 + mv0 * mv1 + mk0 * mk1;
195 double lengths[4][3];
196 int n = solve_for_lengths(lengths, distances, cosines);
198 int nb_solutions = 0;
199 for (
int i = 0; i <
n; i++)
203 M_orig[0][0] = lengths[i][0] * mu0;
204 M_orig[0][1] = lengths[i][0] * mv0;
205 M_orig[0][2] = lengths[i][0] * mk0;
207 M_orig[1][0] = lengths[i][1] * mu1;
208 M_orig[1][1] = lengths[i][1] * mv1;
209 M_orig[1][2] = lengths[i][1] * mk1;
211 M_orig[2][0] = lengths[i][2] * mu2;
212 M_orig[2][1] = lengths[i][2] * mv2;
213 M_orig[2][2] = lengths[i][2] * mk2;
216 M_orig, X0, Y0, Z0, X1, Y1, Z1, X2, Y2, Z2,
R[nb_solutions],
242 double lengths[4][3],
double distances[3],
double cosines[3])
244 double p = cosines[0] * 2;
245 double q = cosines[1] * 2;
246 double r = cosines[2] * 2;
248 double inv_d22 = 1. / (distances[2] * distances[2]);
249 double a = inv_d22 * (distances[0] * distances[0]);
250 double b = inv_d22 * (distances[1] * distances[1]);
252 double a2 =
a *
a,
b2 =
b *
b, p2 =
p *
p, q2 =
q *
q, r2 =
r *
r;
253 double pr =
p *
r, pqr =
q * pr;
256 if (p2 + q2 + r2 - pqr - 1 == 0)
return 0;
258 double ab =
a *
b, a_2 = 2 *
a;
260 double A = -2 *
b +
b2 +
a2 + 1 + ab * (2 - r2) - a_2;
263 if (A == 0)
return 0;
268 q * (-2 * (ab +
a2 + 1 -
b) + r2 * ab + a_4) + pr * (
b -
b2 + ab);
269 double C = q2 +
b2 * (r2 + p2 - 2) -
b * (p2 + pqr) - ab * (r2 + pqr) +
270 (
a2 - a_2) * (2 + q2) + 2;
272 pr * (ab -
b2 +
b) +
q * ((p2 - 2) *
b + 2 * (ab -
a2) + a_4 - 2);
273 double E = 1 + 2 * (
b -
a - ab) +
b2 -
b * p2 +
a2;
275 double temp = (p2 * (
a - 1 +
b) + r2 * (
a - 1 -
b) + pqr -
a * pqr);
276 double b0 =
b * temp * temp;
278 if (
b0 == 0)
return 0;
280 double real_roots[4];
282 A, B, C, D, E, real_roots[0], real_roots[1], real_roots[2],
285 if (
n == 0)
return 0;
287 int nb_solutions = 0;
288 double r3 = r2 *
r, pr2 =
p * r2, r3q = r3 *
q;
289 double inv_b0 = 1. /
b0;
292 for (
int i = 0; i <
n; i++)
294 double x = real_roots[i];
297 if (
x <= 0)
continue;
302 ((1 -
a -
b) * x2 + (
q *
a -
q) *
x + 1 -
a +
b) *
303 (((r3 * (
a2 + ab * (2 - r2) - a_2 +
b2 - 2 *
b + 1)) *
x +
305 (r3q * (2 * (
b -
a2) + a_4 + ab * (r2 - 2) - 2) +
306 pr2 * (1 +
a2 + 2 * (ab -
a -
b) + r2 * (
b -
b2) +
b2))) *
309 (r3 * (q2 * (1 - 2 *
a +
a2) + r2 * (
b2 - ab) - a_4 +
311 r * p2 * (
b2 + 2 * (ab -
b -
a) + 1 +
a2) +
312 pr2 *
q * (a_4 + 2 * (
b - ab -
a2) - 2 - r2 *
b)) *
315 2 * r3q * (a_2 -
b -
a2 + ab - 1) +
316 pr2 * (q2 - a_4 + 2 * (
a2 -
b2) + r2 *
b + q2 * (
a2 - a_2) + 2) +
317 p2 * (
p * (2 * (ab -
a -
b) +
a2 +
b2 + 1) +
318 2 *
q *
r * (
b + a_2 -
a2 - ab - 1)));
321 if (
b1 <= 0)
continue;
323 double y = inv_b0 *
b1;
324 double v = x2 +
y *
y -
x *
y *
r;
326 if (
v <= 0)
continue;
328 double Z = distances[2] / sqrt(
v);
332 lengths[nb_solutions][0] = X;
333 lengths[nb_solutions][1] = Y;
334 lengths[nb_solutions][2] = Z;
343 double M_end[3][3],
double X0,
double Y0,
double Z0,
double X1,
double Y1,
344 double Z1,
double X2,
double Y2,
double Z2,
double R[3][3],
double T[3])
347 double C_start[3], C_end[3];
348 for (
int i = 0; i < 3; i++)
349 C_end[i] = (M_end[0][i] + M_end[1][i] + M_end[2][i]) / 3;
350 C_start[0] = (X0 + X1 + X2) / 3;
351 C_start[1] = (Y0 + Y1 + Y2) / 3;
352 C_start[2] = (Z0 + Z1 + Z2) / 3;
356 for (
int j = 0; j < 3; j++)
359 (X0 * M_end[0][j] + X1 * M_end[1][j] + X2 * M_end[2][j]) / 3 -
360 C_end[j] * C_start[0];
362 (Y0 * M_end[0][j] + Y1 * M_end[1][j] + Y2 * M_end[2][j]) / 3 -
363 C_end[j] * C_start[1];
365 (Z0 * M_end[0][j] + Z1 * M_end[1][j] + Z2 * M_end[2][j]) / 3 -
366 C_end[j] * C_start[2];
369 double Qs[16], evs[4], U[16];
371 Qs[0 * 4 + 0] =
s[0 * 3 + 0] +
s[1 * 3 + 1] +
s[2 * 3 + 2];
372 Qs[1 * 4 + 1] =
s[0 * 3 + 0] -
s[1 * 3 + 1] -
s[2 * 3 + 2];
373 Qs[2 * 4 + 2] =
s[1 * 3 + 1] -
s[2 * 3 + 2] -
s[0 * 3 + 0];
374 Qs[3 * 4 + 3] =
s[2 * 3 + 2] -
s[0 * 3 + 0] -
s[1 * 3 + 1];
376 Qs[1 * 4 + 0] = Qs[0 * 4 + 1] =
s[1 * 3 + 2] -
s[2 * 3 + 1];
377 Qs[2 * 4 + 0] = Qs[0 * 4 + 2] =
s[2 * 3 + 0] -
s[0 * 3 + 2];
378 Qs[3 * 4 + 0] = Qs[0 * 4 + 3] =
s[0 * 3 + 1] -
s[1 * 3 + 0];
379 Qs[2 * 4 + 1] = Qs[1 * 4 + 2] =
s[1 * 3 + 0] +
s[0 * 3 + 1];
380 Qs[3 * 4 + 1] = Qs[1 * 4 + 3] =
s[2 * 3 + 0] +
s[0 * 3 + 2];
381 Qs[3 * 4 + 2] = Qs[2 * 4 + 3] =
s[2 * 3 + 1] +
s[1 * 3 + 2];
383 jacobi_4x4(Qs, evs, U);
387 double ev_max = evs[i_ev];
388 for (
int i = 1; i < 4; i++)
389 if (evs[i] > ev_max) ev_max = evs[i_ev = i];
393 for (
int i = 0; i < 4; i++)
q[i] = U[i * 4 + i_ev];
395 double q02 =
q[0] *
q[0], q12 =
q[1] *
q[1], q22 =
q[2] *
q[2],
397 double q0_1 =
q[0] *
q[1], q0_2 =
q[0] *
q[2], q0_3 =
q[0] *
q[3];
398 double q1_2 =
q[1] *
q[2], q1_3 =
q[1] *
q[3];
399 double q2_3 =
q[2] *
q[3];
401 R[0][0] = q02 + q12 - q22 - q32;
402 R[0][1] = 2. * (q1_2 - q0_3);
403 R[0][2] = 2. * (q1_3 + q0_2);
405 R[1][0] = 2. * (q1_2 + q0_3);
406 R[1][1] = q02 + q22 - q12 - q32;
407 R[1][2] = 2. * (q2_3 - q0_1);
409 R[2][0] = 2. * (q1_3 - q0_2);
410 R[2][1] = 2. * (q2_3 + q0_1);
411 R[2][2] = q02 + q32 - q12 - q22;
413 for (
int i = 0; i < 3; i++)
414 T[i] = C_end[i] - (
R[i][0] * C_start[0] +
R[i][1] * C_start[1] +
415 R[i][2] * C_start[2]);
423 double Id[16] = {1., 0., 0., 0., 0., 1., 0., 0.,
424 0., 0., 1., 0., 0., 0., 0., 1.};
426 memcpy(U, Id, 16 *
sizeof(
double));
432 memcpy(D, B, 4 *
sizeof(
double));
433 memset(Z, 0, 4 *
sizeof(
double));
435 for (
int iter = 0; iter < 50; iter++)
437 double sum = fabs(A[1]) + fabs(A[2]) + fabs(A[3]) + fabs(A[6]) +
438 fabs(A[7]) + fabs(A[11]);
440 if (
sum == 0.0)
return true;
442 double tresh = (iter < 3) ? 0.2 *
sum / 16. : 0.0;
443 for (
int i = 0; i < 3; i++)
445 double* pAij = A + 5 * i + 1;
446 for (
int j = i + 1; j < 4; j++)
449 double eps_machine = 100.0 * fabs(Aij);
451 if (iter > 3 && fabs(D[i]) + eps_machine == fabs(D[i]) &&
452 fabs(D[j]) + eps_machine == fabs(D[j]))
454 else if (fabs(Aij) > tresh)
456 double hh = D[j] - D[i],
t;
457 if (fabs(hh) + eps_machine == fabs(hh))
461 double theta = 0.5 * hh / Aij;
462 t = 1.0 / (fabs(theta) + sqrt(1.0 + theta * theta));
463 if (theta < 0.0)
t = -
t;
473 double c = 1.0 / sqrt(1 +
t *
t);
475 double tau =
s / (1.0 +
c);
476 for (
int k = 0; k <= i - 1; k++)
478 double g = A[k * 4 + i], h = A[k * 4 + j];
479 A[k * 4 + i] =
g -
s * (h +
g * tau);
480 A[k * 4 + j] = h +
s * (
g - h * tau);
482 for (
int k = i + 1; k <= j - 1; k++)
484 double g = A[i * 4 + k], h = A[k * 4 + j];
485 A[i * 4 + k] =
g -
s * (h +
g * tau);
486 A[k * 4 + j] = h +
s * (
g - h * tau);
488 for (
int k = j + 1; k < 4; k++)
490 double g = A[i * 4 + k], h = A[j * 4 + k];
491 A[i * 4 + k] =
g -
s * (h +
g * tau);
492 A[j * 4 + k] = h +
s * (
g - h * tau);
494 for (
int k = 0; k < 4; k++)
496 double g = U[k * 4 + i], h = U[k * 4 + j];
497 U[k * 4 + i] =
g -
s * (h +
g * tau);
498 U[k * 4 + j] = h +
s * (
g - h * tau);
505 for (
int i = 0; i < 4; i++) B[i] += Z[i];
506 memcpy(D, B, 4 *
sizeof(
double));
507 memset(Z, 0, 4 *
sizeof(
double));
GLdouble GLdouble GLdouble GLdouble q
bool jacobi_4x4(double *A, double *D, double *U)
Function used to compute the SVD.
GLsizei const GLfloat * points
double inv_fy
Inverse of focal length x.
bool align(double M_start[3][3], double X0, double Y0, double Z0, double X1, double Y1, double Z1, double X2, double Y2, double Z2, double R[3][3], double T[3])
int solve_for_lengths(double lengths[4][3], double distances[3], double cosines[3])
Helper function to solve()
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
double cy_fy
Inverse of image center point x.
int solve_deg4(double a, double b, double c, double d, double e, double &x0, double &x1, double &x2, double &x3)
Reference : Eric W.
void init_inverse_parameters()
Function to compute inverse parameters of camera intrinsic matrix.
bool solve(Eigen::Ref< Eigen::Matrix3d > R, Eigen::Ref< Eigen::Vector3d > t, Eigen::MatrixXd obj_pts, Eigen::MatrixXd img_pts)
p3p(double fx, double fy, double cx, double cy)
Constructor for p3p class using C.
GLdouble GLdouble GLdouble r
double cx_fx
Inverse of focal length y.
GLubyte GLubyte GLubyte a
double inv_fx
Image center y.
CONTAINER::Scalar norm(const CONTAINER &v)
P3P Pose estimation Algorithm - Eigen Implementation.
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".