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 =
round(log(
float(
width/cols))/log(2.f)) + ctf_levels;
40 depth.resize(pyr_levels);
41 depth_old.resize(pyr_levels);
42 depth_inter.resize(pyr_levels);
43 depth_warped.resize(pyr_levels);
44 xx.resize(pyr_levels);
45 xx_inter.resize(pyr_levels);
46 xx_old.resize(pyr_levels);
47 xx_warped.resize(pyr_levels);
48 yy.resize(pyr_levels);
49 yy_inter.resize(pyr_levels);
50 yy_old.resize(pyr_levels);
51 yy_warped.resize(pyr_levels);
52 transformations.resize(pyr_levels);
54 for (
unsigned int i = 0; i<pyr_levels; i++)
56 unsigned int s = pow(2.f,
int(i));
58 depth[i].resize(rows_i, cols_i);
59 depth_inter[i].resize(rows_i, cols_i);
60 depth_old[i].resize(rows_i, cols_i);
61 depth[i].assign(0.0f);
62 depth_old[i].assign(0.0f);
63 xx[i].resize(rows_i, cols_i);
64 xx_inter[i].resize(rows_i, cols_i);
65 xx_old[i].resize(rows_i, cols_i);
67 xx_old[i].assign(0.0f);
68 yy[i].resize(rows_i, cols_i);
69 yy_inter[i].resize(rows_i, cols_i);
70 yy_old[i].resize(rows_i, cols_i);
72 yy_old[i].assign(0.0f);
73 transformations[i].resize(4,4);
77 depth_warped[i].resize(rows_i,cols_i);
78 xx_warped[i].resize(rows_i,cols_i);
79 yy_warped[i].resize(rows_i,cols_i);
87 previous_speed_const_weight = 0.05f;
88 previous_speed_eig_weight = 0.5f;
89 kai_loc_old.assign(0.f);
94 v_mask(0) = 1.f; v_mask(1) = 2.f; v_mask(2) = 2.f; v_mask(3) = 1.f;
95 for (
unsigned int i = 0; i<4; i++)
96 for (
unsigned int j = 0; j<4; j++)
97 f_mask(i,j) = v_mask(i)*v_mask(j)/36.f;
100 float v_mask2[5] = {1,4,6,4,1};
101 for (
unsigned int i = 0; i<5; i++)
102 for (
unsigned int j = 0; j<5; j++)
103 g_mask[i][j] = v_mask2[i]*v_mask2[j]/256.f;
108 const float max_depth_dif = 0.1f;
111 depth_old.swap(
depth);
118 unsigned int pyr_levels =
round(log(
float(
width/cols))/log(2.f)) + ctf_levels;
121 for (
unsigned int i = 0; i<pyr_levels; i++)
123 unsigned int s = pow(2.f,
int(i));
126 const int rows_i2 = 2*rows_i;
127 const int cols_i2 = 2*cols_i;
131 depth[i].swap(depth_wf);
137 for (
unsigned int u = 0; u < cols_i; u++)
138 for (
unsigned int v = 0;
v < rows_i;
v++)
145 if ((
v>0)&&(
v<rows_i-1)&&(u>0)&&(u<cols_i-1))
152 for (
int l = -2; l<3; l++)
153 for (
int k = -2; k<3; k++)
155 const float abs_dif = abs(
depth[i_1](
v2+k,
u2+l)-dcenter);
156 if (abs_dif < max_depth_dif)
158 const float aux_w = g_mask[2+k][2+l]*(max_depth_dif - abs_dif);
167 float min_depth = 10.f;
168 for (
int l = -2; l<3; l++)
169 for (
int k = -2; k<3; k++)
172 if ((d > 0.f)&&(d < min_depth))
176 if (min_depth < 10.f)
177 depth[i](
v,u) = min_depth;
191 for (
int l = -2; l<3; l++)
192 for (
int k = -2; k<3; k++)
194 const int indv =
v2+k,indu =
u2+l;
195 if ((indv>=0)&&(indv<rows_i2)&&(indu>=0)&&(indu<cols_i2))
197 const float abs_dif = abs(
depth[i_1](indv,indu)-dcenter);
198 if (abs_dif < max_depth_dif)
200 const float aux_w = g_mask[2+k][2+l]*(max_depth_dif - abs_dif);
210 float min_depth = 10.f;
211 for (
int l = -2; l<3; l++)
212 for (
int k = -2; k<3; k++)
214 const int indv =
v2+k,indu =
u2+l;
215 if ((indv>=0)&&(indv<rows_i2)&&(indu>=0)&&(indu<cols_i2))
217 const float d =
depth[i_1](indv,indu);
218 if ((d > 0.f)&&(d < min_depth))
223 if (min_depth < 10.f)
224 depth[i](
v,u) = min_depth;
233 const float inv_f_i = 2.f*tan(0.5f*fovh)/float(cols_i);
234 const float disp_u_i = 0.5f*(cols_i-1);
235 const float disp_v_i = 0.5f*(rows_i-1);
237 for (
unsigned int u = 0; u < cols_i; u++)
238 for (
unsigned int v = 0;
v < rows_i;
v++)
241 xx[i](
v,u) = (u - disp_u_i)*
depth[i](
v,u)*inv_f_i;
242 yy[i](
v,u) = (
v - disp_v_i)*
depth[i](
v,u)*inv_f_i;
254 const float max_depth_dif = 0.1f;
257 depth_old.swap(
depth);
264 unsigned int pyr_levels =
round(log(
float(
width/cols))/log(2.f)) + ctf_levels;
267 for (
unsigned int i = 0; i<pyr_levels; i++)
269 unsigned int s = pow(2.f,
int(i));
277 depth[i].swap(depth_wf);
283 for (
unsigned int u = 0; u < cols_i; u++)
284 for (
unsigned int v = 0;
v < rows_i;
v++)
290 if ((
v>0)&&(
v<rows_i-1)&&(u>0)&&(u<cols_i-1))
292 const Matrix4f d_block =
depth[i_1].block<4,4>(
v2-1,
u2-1);
293 float depths[4] = {d_block(5),d_block(6),d_block(9),d_block(10)};
297 for (
signed char k = 2; k>=0; k--)
298 if (depths[k+1] < depths[k])
299 std::swap(depths[k+1],depths[k]);
300 for (
unsigned char k = 1; k<3; k++)
301 if (depths[k] > depths[k+1])
302 std::swap(depths[k+1],depths[k]);
303 if (depths[2] < depths[1])
313 for (
unsigned char k = 0; k<16; k++)
315 const float abs_dif = abs(d_block(k) - dcenter);
316 if (abs_dif < max_depth_dif)
318 const float aux_w = f_mask(k)*(max_depth_dif - abs_dif);
320 sum += aux_w*d_block(k);
333 const Matrix2f d_block =
depth[i_1].block<2,2>(
v2,
u2);
334 const float new_d = 0.25f*d_block.sumAll();
344 const float inv_f_i = 2.f*tan(0.5f*fovh)/float(cols_i);
345 const float disp_u_i = 0.5f*(cols_i-1);
346 const float disp_v_i = 0.5f*(rows_i-1);
348 for (
unsigned int u = 0; u < cols_i; u++)
349 for (
unsigned int v = 0;
v < rows_i;
v++)
352 xx[i](
v,u) = (u - disp_u_i)*
depth[i](
v,u)*inv_f_i;
353 yy[i](
v,u) = (
v - disp_v_i)*
depth[i](
v,u)*inv_f_i;
366 const float f = float(cols_i)/(2.f*tan(0.5f*fovh));
367 const float disp_u_i = 0.5f*float(cols_i-1);
368 const float disp_v_i = 0.5f*float(rows_i-1);
372 acu_trans.setIdentity();
373 for (
unsigned int i=1; i<=
level; i++)
374 acu_trans = transformations[i-1]*acu_trans;
376 MatrixXf wacu(rows_i,cols_i);
378 depth_warped[image_level].assign(0.f);
380 const float cols_lim = float(cols_i-1);
381 const float rows_lim = float(rows_i-1);
385 for (
unsigned int j = 0; j<cols_i; j++)
386 for (
unsigned int i = 0; i<rows_i; i++)
388 const float z =
depth[image_level](i,j);
393 const float depth_w = acu_trans(0,0)*
z + acu_trans(0,1)*xx[image_level](i,j) + acu_trans(0,2)*yy[image_level](i,j) + acu_trans(0,3);
394 const float x_w = acu_trans(1,0)*
z + acu_trans(1,1)*xx[image_level](i,j) + acu_trans(1,2)*yy[image_level](i,j) + acu_trans(1,3);
395 const float y_w = acu_trans(2,0)*
z + acu_trans(2,1)*xx[image_level](i,j) + acu_trans(2,2)*yy[image_level](i,j) + acu_trans(2,3);
398 const float uwarp = f*x_w/depth_w + disp_u_i;
399 const float vwarp = f*y_w/depth_w + disp_v_i;
402 if (( uwarp >= 0.f)&&( uwarp < cols_lim)&&( vwarp >= 0.f)&&( vwarp < rows_lim))
404 const int uwarp_l = uwarp;
405 const int uwarp_r = uwarp_l + 1;
406 const int vwarp_d = vwarp;
407 const int vwarp_u = vwarp_d + 1;
408 const float delta_r = float(uwarp_r) - uwarp;
409 const float delta_l = uwarp - float(uwarp_l);
410 const float delta_u = float(vwarp_u) - vwarp;
411 const float delta_d = vwarp - float(vwarp_d);
414 if (abs(
round(uwarp) - uwarp) + abs(
round(vwarp) - vwarp) < 0.05f)
416 depth_warped[image_level](
round(vwarp),
round(uwarp)) += depth_w;
422 depth_warped[image_level](vwarp_u,uwarp_r) += w_ur*depth_w;
423 wacu(vwarp_u,uwarp_r) += w_ur;
426 depth_warped[image_level](vwarp_u,uwarp_l) += w_ul*depth_w;
427 wacu(vwarp_u,uwarp_l) += w_ul;
430 depth_warped[image_level](vwarp_d,uwarp_r) += w_dr*depth_w;
431 wacu(vwarp_d,uwarp_r) += w_dr;
434 depth_warped[image_level](vwarp_d,uwarp_l) += w_dl*depth_w;
435 wacu(vwarp_d,uwarp_l) += w_dl;
442 const float inv_f_i = 1.f/f;
443 for (
unsigned int u = 0; u<cols_i; u++)
444 for (
unsigned int v = 0;
v<rows_i;
v++)
448 depth_warped[image_level](
v,u) /= wacu(
v,u);
449 xx_warped[image_level](
v,u) = (u - disp_u_i)*depth_warped[image_level](
v,u)*inv_f_i;
450 yy_warped[image_level](
v,u) = (
v - disp_v_i)*depth_warped[image_level](
v,u)*inv_f_i;
454 depth_warped[image_level](
v,u) = 0.f;
455 xx_warped[image_level](
v,u) = 0.f;
456 yy_warped[image_level](
v,u) = 0.f;
463 null.resize(rows_i, cols_i);
465 num_valid_points = 0;
467 for (
unsigned int u = 0; u < cols_i; u++)
468 for (
unsigned int v = 0;
v < rows_i;
v++)
470 if ((depth_old[image_level](
v,u)) == 0.f || (depth_warped[image_level](
v,u) == 0.f))
472 depth_inter[image_level](
v,u) = 0.f;
473 xx_inter[image_level](
v,u) = 0.f;
474 yy_inter[image_level](
v,u) = 0.f;
479 depth_inter[image_level](
v,u) = 0.5f*(depth_old[image_level](
v,u) + depth_warped[image_level](
v,u));
480 xx_inter[image_level](
v,u) = 0.5f*(xx_old[image_level](
v,u) + xx_warped[image_level](
v,u));
481 yy_inter[image_level](
v,u) = 0.5f*(yy_old[image_level](
v,u) + yy_warped[image_level](
v,u));
483 if ((u>0)&&(
v>0)&&(u<cols_i-1)&&(
v<rows_i-1))
491 dt.resize(rows_i,cols_i); dt.assign(0.f);
492 du.resize(rows_i,cols_i); du.assign(0.f);
493 dv.resize(rows_i,cols_i); dv.assign(0.f);
496 MatrixXf rx_ninv(rows_i,cols_i);
497 MatrixXf ry_ninv(rows_i,cols_i);
498 rx_ninv.assign(1.f); ry_ninv.assign(1.f);
500 for (
unsigned int u = 0; u < cols_i-1; u++)
501 for (
unsigned int v = 0;
v < rows_i;
v++)
502 if (null(
v,u) ==
false)
504 rx_ninv(
v,u) = sqrtf(
square(xx_inter[image_level](
v,u+1) - xx_inter[image_level](
v,u))
505 +
square(depth_inter[image_level](
v,u+1) - depth_inter[image_level](
v,u)));
508 for (
unsigned int u = 0; u < cols_i; u++)
509 for (
unsigned int v = 0;
v < rows_i-1;
v++)
510 if (null(
v,u) ==
false)
512 ry_ninv(
v,u) = sqrtf(
square(yy_inter[image_level](
v+1,u) - yy_inter[image_level](
v,u))
513 +
square(depth_inter[image_level](
v+1,u) - depth_inter[image_level](
v,u)));
518 for (
unsigned int v = 0;
v < rows_i;
v++)
520 for (
unsigned int u = 1; u < cols_i-1; u++)
521 if (null(
v,u) ==
false)
522 du(
v,u) = (rx_ninv(
v,u-1)*(depth_inter[image_level](
v,u+1)-depth_inter[image_level](
v,u)) + rx_ninv(
v,u)*(depth_inter[image_level](
v,u) - depth_inter[image_level](
v,u-1)))/(rx_ninv(
v,u)+rx_ninv(
v,u-1));
525 du(
v,cols_i-1) = du(
v,cols_i-2);
528 for (
unsigned int u = 0; u < cols_i; u++)
530 for (
unsigned int v = 1;
v < rows_i-1;
v++)
531 if (null(
v,u) ==
false)
532 dv(
v,u) = (ry_ninv(
v-1,u)*(depth_inter[image_level](
v+1,u)-depth_inter[image_level](
v,u)) + ry_ninv(
v,u)*(depth_inter[image_level](
v,u) - depth_inter[image_level](
v-1,u)))/(ry_ninv(
v,u)+ry_ninv(
v-1,u));
535 dv(rows_i-1,u) = dv(rows_i-2,u);
539 for (
unsigned int u = 0; u < cols_i; u++)
540 for (
unsigned int v = 0;
v < rows_i;
v++)
541 if (null(
v,u) ==
false)
542 dt(
v,u) = fps*(depth_warped[image_level](
v,u) - depth_old[image_level](
v,u));
547 weights.resize(rows_i, cols_i);
551 Matrix<float,6,1> kai_level = kai_loc_old;
554 acu_trans.setIdentity();
555 for (
unsigned int i=0; i<
level; i++)
556 acu_trans = transformations[i]*acu_trans;
562 kai_level -= kai_level_acu.cast<
float>();
565 const float f_inv = float(cols_i)/(2.f*tan(0.5f*fovh));
566 const float kz2 = 8.122e-12f;
569 const float kduv = 20e-5f;
570 const float kdt = kduv/
square(fps);
571 const float k2dt = 5e-6f;
572 const float k2duv = 5e-6f;
574 for (
unsigned int u = 1; u < cols_i-1; u++)
575 for (
unsigned int v = 1;
v < rows_i-1;
v++)
576 if (null(
v,u) ==
false)
580 const float z = depth_inter[image_level](
v,u);
581 const float inv_d = 1.f/
z;
584 const float z2 =
z*
z;
585 const float z4 = z2*z2;
593 const float var44 = kz2*z4*
square(fps);
594 const float var55 = kz2*z4*0.25f;
595 const float var66 = var55;
602 const float j4 = 1.f;
603 const float j5 = xx_inter[image_level](
v,u)*inv_d*inv_d*f_inv*(kai_level[0] + yy_inter[image_level](
v,u)*kai_level[4] - xx_inter[image_level](
v,u)*kai_level[5])
604 + inv_d*f_inv*(-kai_level[1] -
z*kai_level[5] + yy_inter[image_level](
v,u)*kai_level[3]);
605 const float j6 = yy_inter[image_level](
v,u)*inv_d*inv_d*f_inv*(kai_level[0] + yy_inter[image_level](
v,u)*kai_level[4] - xx_inter[image_level](
v,u)*kai_level[5])
606 + inv_d*f_inv*(-kai_level[2] +
z*kai_level[4] - xx_inter[image_level](
v,u)*kai_level[3]);
611 const float error_m = j4*j4*var44 + j5*j5*var55 + j6*j6*var66;
616 const float ini_du = depth_old[image_level](
v,u+1) - depth_old[image_level](
v,u-1);
617 const float ini_dv = depth_old[image_level](
v+1,u) - depth_old[image_level](
v-1,u);
618 const float final_du = depth_warped[image_level](
v,u+1) - depth_warped[image_level](
v,u-1);
619 const float final_dv = depth_warped[image_level](
v+1,u) - depth_warped[image_level](
v-1,u);
621 const float dut = ini_du - final_du;
622 const float dvt = ini_dv - final_dv;
623 const float duu = du(
v,u+1) - du(
v,u-1);
624 const float dvv = dv(
v+1,u) - dv(
v-1,u);
625 const float dvu = dv(
v,u+1) - dv(
v,u-1);
631 weights(
v,u) = sqrt(1.f/(error_m + error_l));
635 const float inv_max = 1.f/
weights.maximum();
641 MatrixXf A(num_valid_points,6);
642 MatrixXf B(num_valid_points,1);
643 unsigned int cont = 0;
649 const float f_inv = float(cols_i)/(2.f*tan(0.5f*fovh));
651 for (
unsigned int u = 1; u < cols_i-1; u++)
652 for (
unsigned int v = 1;
v < rows_i-1;
v++)
653 if (null(
v,u) ==
false)
656 const float d = depth_inter[image_level](
v,u);
657 const float inv_d = 1.f/d;
658 const float x = xx_inter[image_level](
v,u);
659 const float y = yy_inter[image_level](
v,u);
660 const float dycomp = du(
v,u)*f_inv*inv_d;
661 const float dzcomp = dv(
v,u)*f_inv*inv_d;
665 A(cont, 0) = tw*(1.f + dycomp*
x*inv_d + dzcomp*
y*inv_d);
666 A(cont, 1) = tw*(-dycomp);
667 A(cont, 2) = tw*(-dzcomp);
668 A(cont, 3) = tw*(dycomp*
y - dzcomp*
x);
669 A(cont, 4) = tw*(
y + dycomp*inv_d*
y*
x + dzcomp*(
y*
y*inv_d + d));
670 A(cont, 5) = tw*(-
x - dycomp*(
x*
x*inv_d + d) - dzcomp*inv_d*
y*
x);
671 B(cont,0) = tw*(-dt(
v,u));
679 AtB.multiply_AtB(A,B);
680 MatrixXf Var = AtA.ldlt().solve(AtB);
684 for (
unsigned int k = 0; k<6; k++)
685 res += Var(k)*A.col(k);
687 est_cov = (1.f/float(num_valid_points-6))*AtA.inverse()*
res.squaredNorm();
700 if (fast_pyramid) buildCoordinatesPyramidFast();
701 else buildCoordinatesPyramid();
704 for (
unsigned int i=0; i<ctf_levels; i++)
707 transformations[i].setIdentity();
710 unsigned int s = pow(2.f,
int(ctf_levels-(i+1)));
711 cols_i = cols/
s; rows_i = rows/
s;
712 image_level = ctf_levels - i +
round(log(
float(
width/cols))/log(2.f)) - 1;
717 depth_warped[image_level] =
depth[image_level];
718 xx_warped[image_level] = xx[image_level];
719 yy_warped[image_level] = yy[image_level];
728 calculateDepthDerivatives();
734 if (num_valid_points > 6)
738 filterLevelSolution();
745 execution_time = 1000.f*clock.
Tac();
752 SelfAdjointEigenSolver<MatrixXf> eigensolver(est_cov);
753 if (eigensolver.info() != Success)
755 printf(
"\n Eigensolver couldn't find a solution. Pose is not updated");
761 Matrix<float,6,6> Bii;
762 Matrix<float,6,1> kai_b;
763 Bii = eigensolver.eigenvectors();
764 kai_b = Bii.colPivHouseholderQr().solve(kai_loc_level);
768 Matrix<float,6,1> kai_loc_sub = kai_loc_old;
772 acu_trans.setIdentity();
773 for (
unsigned int i=0; i<
level; i++)
774 acu_trans = transformations[i]*acu_trans;
779 kai_loc_sub -= kai_level_acu.cast<
float>();
786 Matrix<float,6,1> kai_b_old;
787 kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_sub);
791 const float cf = previous_speed_eig_weight*expf(-
int(
level)), df = previous_speed_const_weight*expf(-
int(
level));
792 Matrix<float,6,1> kai_b_fil;
793 for (
unsigned int i=0; i<6; i++)
794 kai_b_fil(i) = (kai_b(i) + (cf*eigensolver.eigenvalues()(i,0) + df)*kai_b_old(i))/(1.f + cf*eigensolver.eigenvalues()(i) + df);
797 Matrix<float, 6, 1> kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil);
803 aux2 = aux1.exp(aux_vel);
804 aux2.getHomogeneousMatrix(trans);
805 transformations[
level] = trans.cast<
float>();
813 acu_trans.setIdentity();
814 for (
unsigned int i=1; i<=ctf_levels; i++)
815 acu_trans = transformations[i-1]*acu_trans;
823 kai_loc = kai_level_acu.cast<
float>();
838 cam_pose.getRotationMatrix(inv_trans);
839 v_abs = inv_trans.cast<
float>()*kai_loc.topRows(3);
840 w_abs = inv_trans.cast<
float>()*kai_loc.bottomRows(3);
841 kai_abs.topRows<3>() = v_abs;
842 kai_abs.bottomRows<3>() = w_abs;
847 cam_oldpose = cam_pose;
850 cam_pose = cam_pose + pose_aux;
856 kai_loc_old.topRows<3>() = inv_trans.inverse().cast<
float>()*kai_abs.topRows(3);
857 kai_loc_old.bottomRows<3>() = inv_trans.inverse().cast<
float>()*kai_abs.bottomRows(3);
862 fovh =
M_PI*new_fovh/180.0;
863 fovv =
M_PI*new_fovv/180.0;
879 cur_du.resize(rows,cols);
880 cur_dv.resize(rows,cols);
881 cur_dt.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 ...