21 using namespace Eigen;
29 fovh =
M_PIf * 58.6f / 180.0f;
30 fovv =
M_PIf * 45.6f / 180.0f;
34 width = 640 / (cam_mode * downsample);
35 height = 480 / (cam_mode * downsample);
39 const unsigned int pyr_levels =
40 round(log(
float(
width / cols)) / log(2.f)) + ctf_levels;
41 depth.resize(pyr_levels);
42 depth_old.resize(pyr_levels);
43 depth_inter.resize(pyr_levels);
44 depth_warped.resize(pyr_levels);
45 xx.resize(pyr_levels);
46 xx_inter.resize(pyr_levels);
47 xx_old.resize(pyr_levels);
48 xx_warped.resize(pyr_levels);
49 yy.resize(pyr_levels);
50 yy_inter.resize(pyr_levels);
51 yy_old.resize(pyr_levels);
52 yy_warped.resize(pyr_levels);
53 transformations.resize(pyr_levels);
55 for (
unsigned int i = 0; i < pyr_levels; i++)
57 unsigned int s = pow(2.f,
int(i));
60 depth[i].resize(rows_i, cols_i);
61 depth_inter[i].resize(rows_i, cols_i);
62 depth_old[i].resize(rows_i, cols_i);
63 depth[i].assign(0.0f);
64 depth_old[i].assign(0.0f);
65 xx[i].resize(rows_i, cols_i);
66 xx_inter[i].resize(rows_i, cols_i);
67 xx_old[i].resize(rows_i, cols_i);
69 xx_old[i].assign(0.0f);
70 yy[i].resize(rows_i, cols_i);
71 yy_inter[i].resize(rows_i, cols_i);
72 yy_old[i].resize(rows_i, cols_i);
74 yy_old[i].assign(0.0f);
75 transformations[i].resize(4, 4);
79 depth_warped[i].resize(rows_i, cols_i);
80 xx_warped[i].resize(rows_i, cols_i);
81 yy_warped[i].resize(rows_i, cols_i);
89 previous_speed_const_weight = 0.05f;
90 previous_speed_eig_weight = 0.5f;
91 kai_loc_old.assign(0.f);
100 for (
unsigned int i = 0; i < 4; i++)
101 for (
unsigned int j = 0; j < 4; j++)
102 f_mask(i, j) = v_mask(i) * v_mask(j) / 36.f;
105 float v_mask2[5] = {1, 4, 6, 4, 1};
106 for (
unsigned int i = 0; i < 5; i++)
107 for (
unsigned int j = 0; j < 5; j++)
108 g_mask[i][j] = v_mask2[i] * v_mask2[j] / 256.f;
113 const float max_depth_dif = 0.1f;
116 depth_old.swap(
depth);
125 unsigned int pyr_levels =
126 round(log(
float(
width / cols)) / log(2.f)) + ctf_levels;
129 for (
unsigned int i = 0; i < pyr_levels; i++)
131 unsigned int s = pow(2.f,
int(i));
134 const int rows_i2 = 2 * rows_i;
135 const int cols_i2 = 2 * cols_i;
136 const int i_1 = i - 1;
138 if (i == 0)
depth[i].swap(depth_wf);
144 for (
unsigned int u = 0; u < cols_i; u++)
145 for (
unsigned int v = 0;
v < rows_i;
v++)
147 const int u2 = 2 * u;
148 const int v2 = 2 *
v;
149 const float dcenter =
depth[i_1](
v2,
u2);
152 if ((
v > 0) && (
v < rows_i - 1) && (u > 0) &&
160 for (
int l = -2; l < 3; l++)
161 for (
int k = -2; k < 3; k++)
163 const float abs_dif = abs(
165 if (abs_dif < max_depth_dif)
168 g_mask[2 + k][2 + l] *
169 (max_depth_dif - abs_dif);
179 float min_depth = 10.f;
180 for (
int l = -2; l < 3; l++)
181 for (
int k = -2; k < 3; k++)
183 const float d =
depth[i_1](
v2 + k,
u2 + l);
184 if ((d > 0.f) && (d < min_depth))
188 if (min_depth < 10.f)
189 depth[i](
v, u) = min_depth;
203 for (
int l = -2; l < 3; l++)
204 for (
int k = -2; k < 3; k++)
206 const int indv =
v2 + k, indu =
u2 + l;
207 if ((indv >= 0) && (indv < rows_i2) &&
208 (indu >= 0) && (indu < cols_i2))
210 const float abs_dif = abs(
211 depth[i_1](indv, indu) - dcenter);
212 if (abs_dif < max_depth_dif)
215 g_mask[2 + k][2 + l] *
216 (max_depth_dif - abs_dif);
219 aux_w *
depth[i_1](indv, indu);
227 float min_depth = 10.f;
228 for (
int l = -2; l < 3; l++)
229 for (
int k = -2; k < 3; k++)
231 const int indv =
v2 + k, indu =
u2 + l;
232 if ((indv >= 0) && (indv < rows_i2) &&
233 (indu >= 0) && (indu < cols_i2))
235 const float d =
depth[i_1](indv, indu);
236 if ((d > 0.f) && (d < min_depth))
241 if (min_depth < 10.f)
242 depth[i](
v, u) = min_depth;
251 const float inv_f_i = 2.f * tan(0.5f * fovh) / float(cols_i);
252 const float disp_u_i = 0.5f * (cols_i - 1);
253 const float disp_v_i = 0.5f * (rows_i - 1);
255 for (
unsigned int u = 0; u < cols_i; u++)
256 for (
unsigned int v = 0;
v < rows_i;
v++)
259 xx[i](
v, u) = (u - disp_u_i) *
depth[i](
v, u) * inv_f_i;
260 yy[i](
v, u) = (
v - disp_v_i) *
depth[i](
v, u) * inv_f_i;
272 const float max_depth_dif = 0.1f;
275 depth_old.swap(
depth);
284 unsigned int pyr_levels =
285 round(log(
float(
width / cols)) / log(2.f)) + ctf_levels;
288 for (
unsigned int i = 0; i < pyr_levels; i++)
290 unsigned int s = pow(2.f,
int(i));
295 const int i_1 = i - 1;
297 if (i == 0)
depth[i].swap(depth_wf);
303 for (
unsigned int u = 0; u < cols_i; u++)
304 for (
unsigned int v = 0;
v < rows_i;
v++)
306 const int u2 = 2 * u;
307 const int v2 = 2 *
v;
310 if ((
v > 0) && (
v < rows_i - 1) && (u > 0) &&
313 const Matrix4f d_block =
315 float depths[4] = {d_block(5), d_block(6), d_block(9),
321 for (
signed char k = 2; k >= 0; k--)
322 if (depths[k + 1] < depths[k])
323 std::swap(depths[k + 1], depths[k]);
324 for (
unsigned char k = 1; k < 3; k++)
325 if (depths[k] > depths[k + 1])
326 std::swap(depths[k + 1], depths[k]);
327 if (depths[2] < depths[1])
337 for (
unsigned char k = 0; k < 16; k++)
339 const float abs_dif = abs(d_block(k) - dcenter);
340 if (abs_dif < max_depth_dif)
343 f_mask(k) * (max_depth_dif - abs_dif);
345 sum += aux_w * d_block(k);
357 const Matrix2f d_block =
depth[i_1].block<2, 2>(
v2,
u2);
358 const float new_d = 0.25f * d_block.sumAll();
368 const float inv_f_i = 2.f * tan(0.5f * fovh) / float(cols_i);
369 const float disp_u_i = 0.5f * (cols_i - 1);
370 const float disp_v_i = 0.5f * (rows_i - 1);
372 for (
unsigned int u = 0; u < cols_i; u++)
373 for (
unsigned int v = 0;
v < rows_i;
v++)
376 xx[i](
v, u) = (u - disp_u_i) *
depth[i](
v, u) * inv_f_i;
377 yy[i](
v, u) = (
v - disp_v_i) *
depth[i](
v, u) * inv_f_i;
390 const float f = float(cols_i) / (2.f * tan(0.5f * fovh));
391 const float disp_u_i = 0.5f * float(cols_i - 1);
392 const float disp_v_i = 0.5f * float(rows_i - 1);
396 acu_trans.setIdentity();
397 for (
unsigned int i = 1; i <=
level; i++)
398 acu_trans = transformations[i - 1] * acu_trans;
400 MatrixXf wacu(rows_i, cols_i);
402 depth_warped[image_level].assign(0.f);
404 const float cols_lim = float(cols_i - 1);
405 const float rows_lim = float(rows_i - 1);
409 for (
unsigned int j = 0; j < cols_i; j++)
410 for (
unsigned int i = 0; i < rows_i; i++)
412 const float z =
depth[image_level](i, j);
417 const float depth_w = acu_trans(0, 0) *
z +
418 acu_trans(0, 1) * xx[image_level](i, j) +
419 acu_trans(0, 2) * yy[image_level](i, j) +
421 const float x_w = acu_trans(1, 0) *
z +
422 acu_trans(1, 1) * xx[image_level](i, j) +
423 acu_trans(1, 2) * yy[image_level](i, j) +
425 const float y_w = acu_trans(2, 0) *
z +
426 acu_trans(2, 1) * xx[image_level](i, j) +
427 acu_trans(2, 2) * yy[image_level](i, j) +
431 const float uwarp = f * x_w / depth_w + disp_u_i;
432 const float vwarp = f * y_w / depth_w + disp_v_i;
436 if ((uwarp >= 0.f) && (uwarp < cols_lim) && (vwarp >= 0.f) &&
439 const int uwarp_l = uwarp;
440 const int uwarp_r = uwarp_l + 1;
441 const int vwarp_d = vwarp;
442 const int vwarp_u = vwarp_d + 1;
443 const float delta_r = float(uwarp_r) - uwarp;
444 const float delta_l = uwarp - float(uwarp_l);
445 const float delta_u = float(vwarp_u) - vwarp;
446 const float delta_d = vwarp - float(vwarp_d);
449 if (abs(
round(uwarp) - uwarp) + abs(
round(vwarp) - vwarp) <
452 depth_warped[image_level](
round(vwarp),
round(uwarp)) +=
459 depth_warped[image_level](vwarp_u, uwarp_r) +=
461 wacu(vwarp_u, uwarp_r) += w_ur;
464 depth_warped[image_level](vwarp_u, uwarp_l) +=
466 wacu(vwarp_u, uwarp_l) += w_ul;
469 depth_warped[image_level](vwarp_d, uwarp_r) +=
471 wacu(vwarp_d, uwarp_r) += w_dr;
474 depth_warped[image_level](vwarp_d, uwarp_l) +=
476 wacu(vwarp_d, uwarp_l) += w_dl;
483 const float inv_f_i = 1.f / f;
484 for (
unsigned int u = 0; u < cols_i; u++)
485 for (
unsigned int v = 0;
v < rows_i;
v++)
487 if (wacu(
v, u) > 0.f)
489 depth_warped[image_level](
v, u) /= wacu(
v, u);
490 xx_warped[image_level](
v, u) =
491 (u - disp_u_i) * depth_warped[image_level](
v, u) * inv_f_i;
492 yy_warped[image_level](
v, u) =
493 (
v - disp_v_i) * depth_warped[image_level](
v, u) * inv_f_i;
497 depth_warped[image_level](
v, u) = 0.f;
498 xx_warped[image_level](
v, u) = 0.f;
499 yy_warped[image_level](
v, u) = 0.f;
506 null.resize(rows_i, cols_i);
508 num_valid_points = 0;
510 for (
unsigned int u = 0; u < cols_i; u++)
511 for (
unsigned int v = 0;
v < rows_i;
v++)
513 if ((depth_old[image_level](
v, u)) == 0.f ||
514 (depth_warped[image_level](
v, u) == 0.f))
516 depth_inter[image_level](
v, u) = 0.f;
517 xx_inter[image_level](
v, u) = 0.f;
518 yy_inter[image_level](
v, u) = 0.f;
523 depth_inter[image_level](
v, u) =
524 0.5f * (depth_old[image_level](
v, u) +
525 depth_warped[image_level](
v, u));
526 xx_inter[image_level](
v, u) =
528 (xx_old[image_level](
v, u) + xx_warped[image_level](
v, u));
529 yy_inter[image_level](
v, u) =
531 (yy_old[image_level](
v, u) + yy_warped[image_level](
v, u));
533 if ((u > 0) && (
v > 0) && (u < cols_i - 1) && (
v < rows_i - 1))
541 dt.resize(rows_i, cols_i);
543 du.resize(rows_i, cols_i);
545 dv.resize(rows_i, cols_i);
549 MatrixXf rx_ninv(rows_i, cols_i);
550 MatrixXf ry_ninv(rows_i, cols_i);
554 for (
unsigned int u = 0; u < cols_i - 1; u++)
555 for (
unsigned int v = 0;
v < rows_i;
v++)
556 if (null(
v, u) ==
false)
558 rx_ninv(
v, u) = sqrtf(
560 xx_inter[image_level](
v, u + 1) -
561 xx_inter[image_level](
v, u)) +
563 depth_inter[image_level](
v, u + 1) -
564 depth_inter[image_level](
v, u)));
567 for (
unsigned int u = 0; u < cols_i; u++)
568 for (
unsigned int v = 0;
v < rows_i - 1;
v++)
569 if (null(
v, u) ==
false)
571 ry_ninv(
v, u) = sqrtf(
573 yy_inter[image_level](
v + 1, u) -
574 yy_inter[image_level](
v, u)) +
576 depth_inter[image_level](
v + 1, u) -
577 depth_inter[image_level](
v, u)));
581 for (
unsigned int v = 0;
v < rows_i;
v++)
583 for (
unsigned int u = 1; u < cols_i - 1; u++)
584 if (null(
v, u) ==
false)
586 (rx_ninv(
v, u - 1) * (depth_inter[image_level](
v, u + 1) -
587 depth_inter[image_level](
v, u)) +
588 rx_ninv(
v, u) * (depth_inter[image_level](
v, u) -
589 depth_inter[image_level](
v, u - 1))) /
590 (rx_ninv(
v, u) + rx_ninv(
v, u - 1));
593 du(
v, cols_i - 1) = du(
v, cols_i - 2);
596 for (
unsigned int u = 0; u < cols_i; u++)
598 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
599 if (null(
v, u) ==
false)
601 (ry_ninv(
v - 1, u) * (depth_inter[image_level](
v + 1, u) -
602 depth_inter[image_level](
v, u)) +
603 ry_ninv(
v, u) * (depth_inter[image_level](
v, u) -
604 depth_inter[image_level](
v - 1, u))) /
605 (ry_ninv(
v, u) + ry_ninv(
v - 1, u));
608 dv(rows_i - 1, u) = dv(rows_i - 2, u);
612 for (
unsigned int u = 0; u < cols_i; u++)
613 for (
unsigned int v = 0;
v < rows_i;
v++)
614 if (null(
v, u) ==
false)
615 dt(
v, u) = fps * (depth_warped[image_level](
v, u) -
616 depth_old[image_level](
v, u));
621 weights.resize(rows_i, cols_i);
626 Matrix<float, 6, 1> kai_level = kai_loc_old;
629 acu_trans.setIdentity();
630 for (
unsigned int i = 0; i <
level; i++)
631 acu_trans = transformations[i] * acu_trans;
637 kai_level -= kai_level_acu.cast<
float>();
640 const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
641 const float kz2 = 8.122e-12f;
644 const float kduv = 20e-5f;
645 const float kdt = kduv /
square(fps);
646 const float k2dt = 5e-6f;
647 const float k2duv = 5e-6f;
649 for (
unsigned int u = 1; u < cols_i - 1; u++)
650 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
651 if (null(
v, u) ==
false)
655 const float z = depth_inter[image_level](
v, u);
656 const float inv_d = 1.f /
z;
659 const float z2 =
z *
z;
673 const float var44 = kz2 *
z4 *
square(fps);
674 const float var55 = kz2 *
z4 * 0.25f;
675 const float var66 = var55;
695 const float j4 = 1.f;
697 xx_inter[image_level](
v, u) * inv_d * inv_d * f_inv *
699 yy_inter[image_level](
v, u) * kai_level[4] -
700 xx_inter[image_level](
v, u) * kai_level[5]) +
702 (-kai_level[1] -
z * kai_level[5] +
703 yy_inter[image_level](
v, u) * kai_level[3]);
705 yy_inter[image_level](
v, u) * inv_d * inv_d * f_inv *
707 yy_inter[image_level](
v, u) * kai_level[4] -
708 xx_inter[image_level](
v, u) * kai_level[5]) +
710 (-kai_level[2] +
z * kai_level[4] -
711 xx_inter[image_level](
v, u) * kai_level[3]);
720 const float error_m =
721 j4 * j4 * var44 + j5 * j5 * var55 + j6 * j6 * var66;
725 const float ini_du = depth_old[image_level](
v, u + 1) -
726 depth_old[image_level](
v, u - 1);
727 const float ini_dv = depth_old[image_level](
v + 1, u) -
728 depth_old[image_level](
v - 1, u);
729 const float final_du = depth_warped[image_level](
v, u + 1) -
730 depth_warped[image_level](
v, u - 1);
731 const float final_dv = depth_warped[image_level](
v + 1, u) -
732 depth_warped[image_level](
v - 1, u);
734 const float dut = ini_du - final_du;
735 const float dvt = ini_dv - final_dv;
736 const float duu = du(
v, u + 1) - du(
v, u - 1);
737 const float dvv = dv(
v + 1, u) - dv(
v - 1, u);
742 const float error_l =
749 weights(
v, u) = sqrt(1.f / (error_m + error_l));
753 const float inv_max = 1.f /
weights.maximum();
759 MatrixXf A(num_valid_points, 6);
760 MatrixXf B(num_valid_points, 1);
761 unsigned int cont = 0;
768 const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
770 for (
unsigned int u = 1; u < cols_i - 1; u++)
771 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
772 if (null(
v, u) ==
false)
775 const float d = depth_inter[image_level](
v, u);
776 const float inv_d = 1.f / d;
777 const float x = xx_inter[image_level](
v, u);
778 const float y = yy_inter[image_level](
v, u);
779 const float dycomp = du(
v, u) * f_inv * inv_d;
780 const float dzcomp = dv(
v, u) * f_inv * inv_d;
785 tw * (1.f + dycomp *
x * inv_d + dzcomp *
y * inv_d);
786 A(cont, 1) = tw * (-dycomp);
787 A(cont, 2) = tw * (-dzcomp);
788 A(cont, 3) = tw * (dycomp *
y - dzcomp *
x);
789 A(cont, 4) = tw * (
y + dycomp * inv_d *
y *
x +
790 dzcomp * (
y *
y * inv_d + d));
791 A(cont, 5) = tw * (-
x - dycomp * (
x *
x * inv_d + d) -
792 dzcomp * inv_d *
y *
x);
793 B(cont, 0) = tw * (-dt(
v, u));
801 AtB.multiply_AtB(A, B);
802 MatrixXf Var = AtA.ldlt().solve(AtB);
806 for (
unsigned int k = 0; k < 6; k++)
res += Var(k) * A.col(k);
809 (1.f / float(num_valid_points - 6)) * AtA.inverse() *
res.squaredNorm();
823 buildCoordinatesPyramidFast();
825 buildCoordinatesPyramid();
828 for (
unsigned int i = 0; i < ctf_levels; i++)
831 transformations[i].setIdentity();
834 unsigned int s = pow(2.f,
int(ctf_levels - (i + 1)));
838 ctf_levels - i +
round(log(
float(
width / cols)) / log(2.f)) - 1;
843 depth_warped[image_level] =
depth[image_level];
844 xx_warped[image_level] = xx[image_level];
845 yy_warped[image_level] = yy[image_level];
854 calculateDepthDerivatives();
860 if (num_valid_points > 6) solveOneLevel();
863 filterLevelSolution();
870 execution_time = 1000.f * clock.
Tac();
877 SelfAdjointEigenSolver<MatrixXf> eigensolver(est_cov);
878 if (eigensolver.info() != Success)
880 printf(
"\n Eigensolver couldn't find a solution. Pose is not updated");
887 Matrix<float, 6, 6> Bii;
888 Matrix<float, 6, 1> kai_b;
889 Bii = eigensolver.eigenvectors();
890 kai_b = Bii.colPivHouseholderQr().solve(kai_loc_level);
895 Matrix<float, 6, 1> kai_loc_sub = kai_loc_old;
900 acu_trans.setIdentity();
901 for (
unsigned int i = 0; i <
level; i++)
902 acu_trans = transformations[i] * acu_trans;
907 kai_loc_sub -= kai_level_acu.cast<
float>();
916 Matrix<float, 6, 1> kai_b_old;
917 kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_sub);
921 const float cf = previous_speed_eig_weight * expf(-
int(
level)),
922 df = previous_speed_const_weight * expf(-
int(
level));
923 Matrix<float, 6, 1> kai_b_fil;
924 for (
unsigned int i = 0; i < 6; i++)
927 (cf * eigensolver.eigenvalues()(i, 0) + df) * kai_b_old(i)) /
928 (1.f + cf * eigensolver.eigenvalues()(i) + df);
931 Matrix<float, 6, 1> kai_loc_fil =
932 Bii.inverse().colPivHouseholderQr().solve(kai_b_fil);
938 aux2 = aux1.exp(aux_vel);
939 aux2.getHomogeneousMatrix(trans);
940 transformations[
level] = trans.cast<
float>();
948 acu_trans.setIdentity();
949 for (
unsigned int i = 1; i <= ctf_levels; i++)
950 acu_trans = transformations[i - 1] * acu_trans;
957 kai_loc = kai_level_acu.cast<
float>();
975 cam_pose.getRotationMatrix(inv_trans);
976 v_abs = inv_trans.cast<
float>() * kai_loc.topRows(3);
977 w_abs = inv_trans.cast<
float>() * kai_loc.bottomRows(3);
978 kai_abs.topRows<3>() = v_abs;
979 kai_abs.bottomRows<3>() = w_abs;
983 cam_oldpose = cam_pose;
986 cam_pose = cam_pose + pose_aux;
992 kai_loc_old.topRows<3>() =
993 inv_trans.inverse().cast<
float>() * kai_abs.topRows(3);
994 kai_loc_old.bottomRows<3>() =
995 inv_trans.inverse().cast<
float>() * kai_abs.bottomRows(3);
1000 fovh =
M_PI * new_fovh / 180.0;
1001 fovv =
M_PI * new_fovv / 180.0;
1006 x.resize(rows, cols);
1007 y.resize(rows, cols);
1008 z.resize(rows, cols);
1016 MatrixXf& cur_du, MatrixXf& cur_dv, MatrixXf& cur_dt)
1018 cur_du.resize(rows, cols);
1019 cur_dv.resize(rows, cols);
1020 cur_dt.resize(rows, cols);
1029 w.resize(rows, cols);
void buildCoordinatesPyramid()
Create the gaussian image pyramid according to the number of coarse-to-fine levels.
void calculateDepthDerivatives()
Calculates the depth derivatives respect to u,v (rows and cols) and t (time)
GLint GLint GLsizei GLsizei GLsizei depth
void Tic()
Starts the stopwatch.
void computeWeights()
This method computes the weighting fuction associated to measurement and linearization errors...
GLubyte GLubyte GLubyte GLubyte w
void solveOneLevel()
The Solver.
T square(const T x)
Inline function for the square of a number.
void setFOV(float new_fovh, float new_fovv)
Set the horizontal and vertical field of vision (in degrees)
void odometryCalculation()
This method performs all the necessary steps to estimate the camera velocity once the new image is re...
void calculateCoord()
Calculate the "average" coordinates of the points observed by the camera between two consecutive fram...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
void getDepthDerivatives(Eigen::MatrixXf &cur_du, Eigen::MatrixXf &cur_dv, Eigen::MatrixXf &cur_dt)
Get the depth derivatives (last level) respect to u,v and t respectively.
void getWeights(Eigen::MatrixXf &we)
Get the matrix of weights.
This class implements a high-performance stopwatch.
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
Classes for computer vision, detectors, features, etc.
void filterLevelSolution()
Method to filter the velocity at each level of the pyramid.
void poseUpdate()
Update camera pose and the velocities for the filter.
void getPointsCoord(Eigen::MatrixXf &x, Eigen::MatrixXf &y, Eigen::MatrixXf &z)
Get the coordinates of the points considered by the visual odometry method.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
T square(const T x)
Inline function for the square of a number.
double Tac()
Stops the stopwatch.
A partial specialization of CArrayNumeric for double numbers.
int round(const T value)
Returns the closer integer (int) to x.
GLfloat GLfloat GLfloat v2
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
GLenum GLsizei GLsizei height
void buildCoordinatesPyramidFast()
void performWarping()
Warp the second depth image against the first one according to the 3D transformations accumulated up ...