16 #include <Eigen/Dense> 23 using namespace Eigen;
31 fovh =
M_PIf * 58.6f / 180.0f;
32 fovv =
M_PIf * 45.6f / 180.0f;
36 m_width = 640 / (cam_mode * downsample);
37 m_height = 480 / (cam_mode * downsample);
41 const unsigned int pyr_levels =
42 round(log(
float(m_width / cols)) / log(2.f)) + ctf_levels;
43 depth.resize(pyr_levels);
44 depth_old.resize(pyr_levels);
45 depth_inter.resize(pyr_levels);
46 depth_warped.resize(pyr_levels);
47 xx.resize(pyr_levels);
48 xx_inter.resize(pyr_levels);
49 xx_old.resize(pyr_levels);
50 xx_warped.resize(pyr_levels);
51 yy.resize(pyr_levels);
52 yy_inter.resize(pyr_levels);
53 yy_old.resize(pyr_levels);
54 yy_warped.resize(pyr_levels);
55 transformations.resize(pyr_levels);
57 for (
unsigned int i = 0; i < pyr_levels; i++)
59 unsigned int s = pow(2.f,
int(i));
61 rows_i = m_height /
s;
62 depth[i].resize(rows_i, cols_i);
63 depth_inter[i].resize(rows_i, cols_i);
64 depth_old[i].resize(rows_i, cols_i);
66 depth_old[i].fill(0.0f);
67 xx[i].resize(rows_i, cols_i);
68 xx_inter[i].resize(rows_i, cols_i);
69 xx_old[i].resize(rows_i, cols_i);
72 yy[i].resize(rows_i, cols_i);
73 yy_inter[i].resize(rows_i, cols_i);
74 yy_old[i].resize(rows_i, cols_i);
77 transformations[i].resize(4, 4);
81 depth_warped[i].resize(rows_i, cols_i);
82 xx_warped[i].resize(rows_i, cols_i);
83 yy_warped[i].resize(rows_i, cols_i);
87 depth_wf.setSize(m_height, m_width);
91 previous_speed_const_weight = 0.05f;
92 previous_speed_eig_weight = 0.5f;
102 for (
unsigned int i = 0; i < 4; i++)
103 for (
unsigned int j = 0; j < 4; j++)
104 f_mask(i, j) = v_mask(i) * v_mask(j) / 36.f;
107 float v_mask2[5] = {1, 4, 6, 4, 1};
108 for (
unsigned int i = 0; i < 5; i++)
109 for (
unsigned int j = 0; j < 5; j++)
110 g_mask[i][j] = v_mask2[i] * v_mask2[j] / 256.f;
115 const float max_depth_dif = 0.1f;
118 depth_old.swap(
depth);
127 unsigned int pyr_levels =
128 round(log(
float(m_width / cols)) / log(2.f)) + ctf_levels;
131 for (
unsigned int i = 0; i < pyr_levels; i++)
133 unsigned int s = pow(2.f,
int(i));
134 cols_i = m_width /
s;
135 rows_i = m_height /
s;
136 const int rows_i2 = 2 * rows_i;
137 const int cols_i2 = 2 * cols_i;
138 const int i_1 = i - 1;
140 if (i == 0)
depth[i].swap(depth_wf);
146 for (
unsigned int u = 0; u < cols_i; u++)
147 for (
unsigned int v = 0;
v < rows_i;
v++)
149 const int u2 = 2 * u;
150 const int v2 = 2 *
v;
151 const float dcenter =
depth[i_1](
v2,
u2);
154 if ((
v > 0) && (
v < rows_i - 1) && (u > 0) &&
162 for (
int l = -2; l < 3; l++)
163 for (
int k = -2; k < 3; k++)
165 const float abs_dif = abs(
167 if (abs_dif < max_depth_dif)
170 g_mask[2 + k][2 + l] *
171 (max_depth_dif - abs_dif);
181 float min_depth = 10.f;
182 for (
int l = -2; l < 3; l++)
183 for (
int k = -2; k < 3; k++)
185 const float d =
depth[i_1](
v2 + k,
u2 + l);
186 if ((d > 0.f) && (d < min_depth))
190 if (min_depth < 10.f)
191 depth[i](
v, u) = min_depth;
205 for (
int l = -2; l < 3; l++)
206 for (
int k = -2; k < 3; k++)
208 const int indv =
v2 + k, indu =
u2 + l;
209 if ((indv >= 0) && (indv < rows_i2) &&
210 (indu >= 0) && (indu < cols_i2))
212 const float abs_dif = abs(
213 depth[i_1](indv, indu) - dcenter);
214 if (abs_dif < max_depth_dif)
217 g_mask[2 + k][2 + l] *
218 (max_depth_dif - abs_dif);
221 aux_w *
depth[i_1](indv, indu);
229 float min_depth = 10.f;
230 for (
int l = -2; l < 3; l++)
231 for (
int k = -2; k < 3; k++)
233 const int indv =
v2 + k, indu =
u2 + l;
234 if ((indv >= 0) && (indv < rows_i2) &&
235 (indu >= 0) && (indu < cols_i2))
237 const float d =
depth[i_1](indv, indu);
238 if ((d > 0.f) && (d < min_depth))
243 if (min_depth < 10.f)
244 depth[i](
v, u) = min_depth;
253 const float inv_f_i = 2.f * tan(0.5f * fovh) / float(cols_i);
254 const float disp_u_i = 0.5f * (cols_i - 1);
255 const float disp_v_i = 0.5f * (rows_i - 1);
257 for (
unsigned int u = 0; u < cols_i; u++)
258 for (
unsigned int v = 0;
v < rows_i;
v++)
261 xx[i](
v, u) = (u - disp_u_i) *
depth[i](
v, u) * inv_f_i;
262 yy[i](
v, u) = (
v - disp_v_i) *
depth[i](
v, u) * inv_f_i;
274 const float max_depth_dif = 0.1f;
277 depth_old.swap(
depth);
286 unsigned int pyr_levels =
287 round(log(
float(m_width / cols)) / log(2.f)) + ctf_levels;
290 for (
unsigned int i = 0; i < pyr_levels; i++)
292 unsigned int s = pow(2.f,
int(i));
293 cols_i = m_width /
s;
294 rows_i = m_height /
s;
297 const int i_1 = i - 1;
299 if (i == 0)
depth[i].swap(depth_wf);
305 for (
unsigned int u = 0; u < cols_i; u++)
306 for (
unsigned int v = 0;
v < rows_i;
v++)
308 const int u2 = 2 * u;
309 const int v2 = 2 *
v;
312 if ((
v > 0) && (
v < rows_i - 1) && (u > 0) &&
315 const Matrix4f d_block =
317 float depths[4] = {d_block(5), d_block(6), d_block(9),
323 for (
signed char k = 2; k >= 0; k--)
324 if (depths[k + 1] < depths[k])
325 std::swap(depths[k + 1], depths[k]);
326 for (
unsigned char k = 1; k < 3; k++)
327 if (depths[k] > depths[k + 1])
328 std::swap(depths[k + 1], depths[k]);
329 if (depths[2] < depths[1])
339 for (
unsigned char k = 0; k < 16; k++)
341 const float abs_dif = abs(d_block(k) - dcenter);
342 if (abs_dif < max_depth_dif)
345 f_mask[k] * (max_depth_dif - abs_dif);
347 sum += aux_w * d_block(k);
350 if (weight > 0)
depth[i](
v, u) =
sum / weight;
359 const Matrix2f d_block =
depth[i_1].block<2, 2>(
v2,
u2);
360 const float new_d = 0.25f * d_block.array().sum();
370 const float inv_f_i = 2.f * tan(0.5f * fovh) / float(cols_i);
371 const float disp_u_i = 0.5f * (cols_i - 1);
372 const float disp_v_i = 0.5f * (rows_i - 1);
374 for (
unsigned int u = 0; u < cols_i; u++)
375 for (
unsigned int v = 0;
v < rows_i;
v++)
378 xx[i](
v, u) = (u - disp_u_i) *
depth[i](
v, u) * inv_f_i;
379 yy[i](
v, u) = (
v - disp_v_i) *
depth[i](
v, u) * inv_f_i;
392 const float f = float(cols_i) / (2.f * tan(0.5f * fovh));
393 const float disp_u_i = 0.5f * float(cols_i - 1);
394 const float disp_v_i = 0.5f * float(rows_i - 1);
398 acu_trans.setIdentity();
399 for (
unsigned int i = 1; i <=
level; i++)
400 acu_trans = transformations[i - 1].asEigen() * acu_trans;
402 MatrixXf wacu(rows_i, cols_i);
404 depth_warped[image_level].fill(0.f);
406 const auto cols_lim = float(cols_i - 1);
407 const auto rows_lim = float(rows_i - 1);
411 for (
unsigned int j = 0; j < cols_i; j++)
412 for (
unsigned int i = 0; i < rows_i; i++)
414 const float z =
depth[image_level](i, j);
419 const float depth_w = acu_trans(0, 0) *
z +
420 acu_trans(0, 1) * xx[image_level](i, j) +
421 acu_trans(0, 2) * yy[image_level](i, j) +
423 const float x_w = acu_trans(1, 0) *
z +
424 acu_trans(1, 1) * xx[image_level](i, j) +
425 acu_trans(1, 2) * yy[image_level](i, j) +
427 const float y_w = acu_trans(2, 0) *
z +
428 acu_trans(2, 1) * xx[image_level](i, j) +
429 acu_trans(2, 2) * yy[image_level](i, j) +
433 const float uwarp = f * x_w / depth_w + disp_u_i;
434 const float vwarp = f * y_w / depth_w + disp_v_i;
438 if ((uwarp >= 0.f) && (uwarp < cols_lim) && (vwarp >= 0.f) &&
441 const int uwarp_l = uwarp;
442 const int uwarp_r = uwarp_l + 1;
443 const int vwarp_d = vwarp;
444 const int vwarp_u = vwarp_d + 1;
445 const float delta_r = float(uwarp_r) - uwarp;
446 const float delta_l = uwarp - float(uwarp_l);
447 const float delta_u = float(vwarp_u) - vwarp;
448 const float delta_d = vwarp - float(vwarp_d);
451 if (abs(
round(uwarp) - uwarp) + abs(
round(vwarp) - vwarp) <
454 depth_warped[image_level](
round(vwarp),
round(uwarp)) +=
461 depth_warped[image_level](vwarp_u, uwarp_r) +=
463 wacu(vwarp_u, uwarp_r) += w_ur;
466 depth_warped[image_level](vwarp_u, uwarp_l) +=
468 wacu(vwarp_u, uwarp_l) += w_ul;
471 depth_warped[image_level](vwarp_d, uwarp_r) +=
473 wacu(vwarp_d, uwarp_r) += w_dr;
476 depth_warped[image_level](vwarp_d, uwarp_l) +=
478 wacu(vwarp_d, uwarp_l) += w_dl;
485 const float inv_f_i = 1.f / f;
486 for (
unsigned int u = 0; u < cols_i; u++)
487 for (
unsigned int v = 0;
v < rows_i;
v++)
489 if (wacu(
v, u) > 0.f)
491 depth_warped[image_level](
v, u) /= wacu(
v, u);
492 xx_warped[image_level](
v, u) =
493 (u - disp_u_i) * depth_warped[image_level](
v, u) * inv_f_i;
494 yy_warped[image_level](
v, u) =
495 (
v - disp_v_i) * depth_warped[image_level](
v, u) * inv_f_i;
499 depth_warped[image_level](
v, u) = 0.f;
500 xx_warped[image_level](
v, u) = 0.f;
501 yy_warped[image_level](
v, u) = 0.f;
508 null.resize(rows_i, cols_i);
510 num_valid_points = 0;
512 for (
unsigned int u = 0; u < cols_i; u++)
513 for (
unsigned int v = 0;
v < rows_i;
v++)
515 if ((depth_old[image_level](
v, u)) == 0.f ||
516 (depth_warped[image_level](
v, u) == 0.f))
518 depth_inter[image_level](
v, u) = 0.f;
519 xx_inter[image_level](
v, u) = 0.f;
520 yy_inter[image_level](
v, u) = 0.f;
525 depth_inter[image_level](
v, u) =
526 0.5f * (depth_old[image_level](
v, u) +
527 depth_warped[image_level](
v, u));
528 xx_inter[image_level](
v, u) =
530 (xx_old[image_level](
v, u) + xx_warped[image_level](
v, u));
531 yy_inter[image_level](
v, u) =
533 (yy_old[image_level](
v, u) + yy_warped[image_level](
v, u));
535 if ((u > 0) && (
v > 0) && (u < cols_i - 1) && (
v < rows_i - 1))
543 dt.resize(rows_i, cols_i);
545 du.resize(rows_i, cols_i);
547 dv.resize(rows_i, cols_i);
551 MatrixXf rx_ninv(rows_i, cols_i);
552 MatrixXf ry_ninv(rows_i, cols_i);
556 for (
unsigned int u = 0; u < cols_i - 1; u++)
557 for (
unsigned int v = 0;
v < rows_i;
v++)
558 if (null(
v, u) ==
false)
560 rx_ninv(
v, u) = sqrtf(
562 xx_inter[image_level](
v, u + 1) -
563 xx_inter[image_level](
v, u)) +
565 depth_inter[image_level](
v, u + 1) -
566 depth_inter[image_level](
v, u)));
569 for (
unsigned int u = 0; u < cols_i; u++)
570 for (
unsigned int v = 0;
v < rows_i - 1;
v++)
571 if (null(
v, u) ==
false)
573 ry_ninv(
v, u) = sqrtf(
575 yy_inter[image_level](
v + 1, u) -
576 yy_inter[image_level](
v, u)) +
578 depth_inter[image_level](
v + 1, u) -
579 depth_inter[image_level](
v, u)));
583 for (
unsigned int v = 0;
v < rows_i;
v++)
585 for (
unsigned int u = 1; u < cols_i - 1; u++)
586 if (null(
v, u) ==
false)
588 (rx_ninv(
v, u - 1) * (depth_inter[image_level](
v, u + 1) -
589 depth_inter[image_level](
v, u)) +
590 rx_ninv(
v, u) * (depth_inter[image_level](
v, u) -
591 depth_inter[image_level](
v, u - 1))) /
592 (rx_ninv(
v, u) + rx_ninv(
v, u - 1));
595 du(
v, cols_i - 1) = du(
v, cols_i - 2);
598 for (
unsigned int u = 0; u < cols_i; u++)
600 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
601 if (null(
v, u) ==
false)
603 (ry_ninv(
v - 1, u) * (depth_inter[image_level](
v + 1, u) -
604 depth_inter[image_level](
v, u)) +
605 ry_ninv(
v, u) * (depth_inter[image_level](
v, u) -
606 depth_inter[image_level](
v - 1, u))) /
607 (ry_ninv(
v, u) + ry_ninv(
v - 1, u));
610 dv(rows_i - 1, u) = dv(rows_i - 2, u);
614 for (
unsigned int u = 0; u < cols_i; u++)
615 for (
unsigned int v = 0;
v < rows_i;
v++)
616 if (null(
v, u) ==
false)
617 dt(
v, u) = fps * (depth_warped[image_level](
v, u) -
618 depth_old[image_level](
v, u));
623 weights.resize(rows_i, cols_i);
632 acu_trans.setIdentity();
633 for (
unsigned int i = 0; i <
level; i++)
634 acu_trans = transformations[i].asEigen() * acu_trans;
646 const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
647 const float kz2 = 8.122e-12f;
650 const float kduv = 20e-5f;
651 const float kdt = kduv /
square(fps);
652 const float k2dt = 5e-6f;
653 const float k2duv = 5e-6f;
655 for (
unsigned int u = 1; u < cols_i - 1; u++)
656 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
657 if (null(
v, u) ==
false)
661 const float z = depth_inter[image_level](
v, u);
662 const float inv_d = 1.f /
z;
665 const float z2 =
z *
z;
666 const float z4 = z2 * z2;
679 const float var44 = kz2 * z4 *
square(fps);
680 const float var55 = kz2 * z4 * 0.25f;
681 const float var66 = var55;
701 const float j4 = 1.f;
703 xx_inter[image_level](
v, u) * inv_d * inv_d * f_inv *
705 yy_inter[image_level](
v, u) * kai_level[4] -
706 xx_inter[image_level](
v, u) * kai_level[5]) +
708 (-kai_level[1] -
z * kai_level[5] +
709 yy_inter[image_level](
v, u) * kai_level[3]);
711 yy_inter[image_level](
v, u) * inv_d * inv_d * f_inv *
713 yy_inter[image_level](
v, u) * kai_level[4] -
714 xx_inter[image_level](
v, u) * kai_level[5]) +
716 (-kai_level[2] +
z * kai_level[4] -
717 xx_inter[image_level](
v, u) * kai_level[3]);
726 const float error_m =
727 j4 * j4 * var44 + j5 * j5 * var55 + j6 * j6 * var66;
731 const float ini_du = depth_old[image_level](
v, u + 1) -
732 depth_old[image_level](
v, u - 1);
733 const float ini_dv = depth_old[image_level](
v + 1, u) -
734 depth_old[image_level](
v - 1, u);
735 const float final_du = depth_warped[image_level](
v, u + 1) -
736 depth_warped[image_level](
v, u - 1);
737 const float final_dv = depth_warped[image_level](
v + 1, u) -
738 depth_warped[image_level](
v - 1, u);
740 const float dut = ini_du - final_du;
741 const float dvt = ini_dv - final_dv;
742 const float duu = du(
v, u + 1) - du(
v, u - 1);
743 const float dvv = dv(
v + 1, u) - dv(
v - 1, u);
748 const float error_l =
755 weights(
v, u) = sqrt(1.f / (error_m + error_l));
759 const float inv_max = 1.f /
weights.maxCoeff();
765 MatrixXf
A(num_valid_points, 6);
766 MatrixXf B(num_valid_points, 1);
767 unsigned int cont = 0;
774 const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
776 for (
unsigned int u = 1; u < cols_i - 1; u++)
777 for (
unsigned int v = 1;
v < rows_i - 1;
v++)
778 if (null(
v, u) ==
false)
781 const float d = depth_inter[image_level](
v, u);
782 const float inv_d = 1.f / d;
783 const float x = xx_inter[image_level](
v, u);
784 const float y = yy_inter[image_level](
v, u);
785 const float dycomp = du(
v, u) * f_inv * inv_d;
786 const float dzcomp = dv(
v, u) * f_inv * inv_d;
791 tw * (1.f + dycomp *
x * inv_d + dzcomp *
y * inv_d);
792 A(cont, 1) = tw * (-dycomp);
793 A(cont, 2) = tw * (-dzcomp);
794 A(cont, 3) = tw * (dycomp *
y - dzcomp *
x);
795 A(cont, 4) = tw * (
y + dycomp * inv_d *
y *
x +
796 dzcomp * (
y *
y * inv_d + d));
797 A(cont, 5) = tw * (-
x - dycomp * (
x *
x * inv_d + d) -
798 dzcomp * inv_d *
y *
x);
799 B(cont, 0) = tw * (-dt(
v, u));
805 const MatrixXf AtA =
A.transpose() *
A;
806 const MatrixXf AtB =
A.transpose() * B;
807 VectorXf Var = AtA.ldlt().solve(AtB);
811 for (
unsigned int k = 0; k < 6; k++)
res += Var(k) *
A.col(k);
814 (1.f / float(num_valid_points - 6)) * AtA.inverse() *
res.squaredNorm();
818 kai_loc_level.fromVector(Var);
829 buildCoordinatesPyramidFast();
831 buildCoordinatesPyramid();
834 for (
unsigned int i = 0; i < ctf_levels; i++)
837 transformations[i].setIdentity();
840 unsigned int s = pow(2.f,
int(ctf_levels - (i + 1)));
844 ctf_levels - i +
round(log(
float(m_width / cols)) / log(2.f)) - 1;
849 depth_warped[image_level] =
depth[image_level];
850 xx_warped[image_level] = xx[image_level];
851 yy_warped[image_level] = yy[image_level];
860 calculateDepthDerivatives();
866 if (num_valid_points > 6) solveOneLevel();
869 filterLevelSolution();
876 execution_time = 1000.f * clock.
Tac();
884 std::vector<float> eigenVals;
886 if (est_cov.eig_symmetric(Bii, eigenVals))
889 <<
"\n Eigensolver couldn't find a solution. Pose is not updated\n";
907 acu_trans.setIdentity();
908 for (
unsigned int i = 0; i <
level; i++)
909 acu_trans = transformations[i].asEigen() * acu_trans;
913 acu_trans_vec *= fps;
916 kai_loc_sub -= kai_level_acu.
asEigen().cast<
float>();
926 Bii.
asEigen().colPivHouseholderQr().solve(kai_loc_sub);
930 const float cf = previous_speed_eig_weight * expf(-
int(
level)),
931 df = previous_speed_const_weight * expf(-
int(
level));
933 for (
unsigned int i = 0; i < 6; i++)
935 (kai_b.asEigen()(i) + (cf * eigenVals[i] + df) * kai_b_old(i)) /
936 (1.f + cf * eigenVals[i] + df);
940 Bii.
asEigen().inverse().colPivHouseholderQr().solve(kai_b_fil);
957 acu_trans.setIdentity();
958 for (
unsigned int i = 1; i <= ctf_levels; i++)
959 acu_trans = transformations[i - 1].asEigen() * acu_trans;
965 acu_trans_vec *= fps;
967 kai_loc.fromVector(kai_level_acu.
cast_float());
984 cam_pose.getRotationMatrix(inv_trans);
993 kai_abs.vx = v_abs.x();
994 kai_abs.vy = v_abs.y();
995 kai_abs.vz = v_abs.z();
997 kai_abs.wx = w_abs.x();
998 kai_abs.wy = w_abs.y();
999 kai_abs.wz = w_abs.z();
1003 cam_oldpose = cam_pose;
1005 cam_pose = cam_pose + pose_aux;
1010 cam_pose.getRotationMatrix(inv_trans);
1011 const auto old_vtrans =
1012 (inv_trans.
asEigen().inverse() *
1016 (inv_trans.
asEigen().inverse() *
1020 kai_loc_old.vx = old_vtrans.x();
1021 kai_loc_old.vy = old_vtrans.y();
1022 kai_loc_old.vz = old_vtrans.z();
1024 kai_loc_old.wx = old_w.x();
1025 kai_loc_old.wy = old_w.y();
1026 kai_loc_old.wz = old_w.z();
1031 fovh =
M_PI * new_fovh / 180.0;
1032 fovv =
M_PI * new_fovv / 180.0;
1037 x.resize(rows, cols);
1038 y.resize(rows, cols);
1039 z.resize(rows, cols);
1049 cur_du.
resize(rows, cols);
1050 cur_dv.
resize(rows, cols);
1051 cur_dt.
resize(rows, cols);
1060 w.resize(rows, cols);
double Tac() noexcept
Stops the stopwatch.
A compile-time fixed-size numeric matrix container.
void resize(size_t row, size_t col)
void getPointsCoord(mrpt::math::CMatrixFloat &x, mrpt::math::CMatrixFloat &y, mrpt::math::CMatrixFloat &z)
Get the coordinates of the points considered by the visual odometry method.
void getWeights(mrpt::math::CMatrixFloat &we)
Get the matrix of weights.
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)
A high-performance stopwatch, with typical resolution of nanoseconds.
GLint GLint GLsizei GLsizei GLsizei depth
void computeWeights()
This method computes the weighting fuction associated to measurement and linearization errors...
GLubyte GLubyte GLubyte GLubyte w
void solveOneLevel()
The Solver.
3D twist: 3D velocity vector (vx,vy,vz) + angular velocity (wx,wy,wz)
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...
This base provides a set of functions for maths stuff.
void setFromMatrixLike(const MAT &m)
void getDepthDerivatives(mrpt::math::CMatrixFloat &cur_du, mrpt::math::CMatrixFloat &cur_dv, mrpt::math::CMatrixFloat &cur_dt)
Get the depth derivatives (last level) respect to u,v and t respectively.
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.
Traits for SE(n), rigid-body transformations in R^n space.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CMatrixFixed< float, ROWS, COLS > cast_float() const
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
GLfloat GLfloat GLfloat v2
void Tic() noexcept
Starts the stopwatch.
CMatrixFixed< double, 4, 4 > CMatrixDouble44
This template class provides the basic functionality for a general 2D any-size, resizable container o...
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
void buildCoordinatesPyramidFast()
void performWarping()
Warp the second depth image against the first one according to the 3D transformations accumulated up ...
int round(const T value)
Returns the closer integer (int) to x.