Main MRPT website > C++ reference for MRPT 1.9.9
CDifodo.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "vision-precomp.h" // Precompiled headers
11 
12 #include <mrpt/vision/CDifodo.h>
13 #include <mrpt/utils/utils_defs.h>
14 #include <mrpt/utils/CTicTac.h>
15 #include <mrpt/utils/round.h>
16 
17 using namespace mrpt;
18 using namespace mrpt::vision;
19 using namespace mrpt::math;
20 using namespace std;
21 using namespace Eigen;
22 using mrpt::utils::round;
23 using mrpt::math::square;
24 
26 {
27  rows = 60;
28  cols = 80;
29  fovh = M_PIf * 58.6f / 180.0f;
30  fovv = M_PIf * 45.6f / 180.0f;
31  cam_mode = 1; // (1 - 640 x 480, 2 - 320 x 240, 4 - 160 x 120)
32  downsample = 1;
33  ctf_levels = 1;
34  width = 640 / (cam_mode * downsample);
35  height = 480 / (cam_mode * downsample);
36  fast_pyramid = true;
37 
38  // Resize pyramid
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);
54 
55  for (unsigned int i = 0; i < pyr_levels; i++)
56  {
57  unsigned int s = pow(2.f, int(i));
58  cols_i = width / s;
59  rows_i = height / s;
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);
68  xx[i].assign(0.0f);
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);
73  yy[i].assign(0.0f);
74  yy_old[i].assign(0.0f);
75  transformations[i].resize(4, 4);
76 
77  if (cols_i <= cols)
78  {
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);
82  }
83  }
84 
85  depth_wf.setSize(height, width);
86 
87  fps = 30.f; // In Hz
88 
89  previous_speed_const_weight = 0.05f;
90  previous_speed_eig_weight = 0.5f;
91  kai_loc_old.assign(0.f);
92  num_valid_points = 0;
93 
94  // Compute gaussian mask
95  VectorXf v_mask(4);
96  v_mask(0) = 1.f;
97  v_mask(1) = 2.f;
98  v_mask(2) = 2.f;
99  v_mask(3) = 1.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;
103 
104  // Compute gaussian mask
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;
109 }
110 
112 {
113  const float max_depth_dif = 0.1f;
114 
115  // Push coordinates back
116  depth_old.swap(depth);
117  xx_old.swap(xx);
118  yy_old.swap(yy);
119 
120  // The number of levels of the pyramid does not match the number of levels
121  // used
122  // in the odometry computation (because we might want to finish with lower
123  // resolutions)
124 
125  unsigned int pyr_levels =
126  round(log(float(width / cols)) / log(2.f)) + ctf_levels;
127 
128  // Generate levels
129  for (unsigned int i = 0; i < pyr_levels; i++)
130  {
131  unsigned int s = pow(2.f, int(i));
132  cols_i = width / s;
133  rows_i = height / s;
134  const int rows_i2 = 2 * rows_i;
135  const int cols_i2 = 2 * cols_i;
136  const int i_1 = i - 1;
137 
138  if (i == 0) depth[i].swap(depth_wf);
139 
140  // Downsampling
141  //-----------------------------------------------------------------------------
142  else
143  {
144  for (unsigned int u = 0; u < cols_i; u++)
145  for (unsigned int v = 0; v < rows_i; v++)
146  {
147  const int u2 = 2 * u;
148  const int v2 = 2 * v;
149  const float dcenter = depth[i_1](v2, u2);
150 
151  // Inner pixels
152  if ((v > 0) && (v < rows_i - 1) && (u > 0) &&
153  (u < cols_i - 1))
154  {
155  if (dcenter > 0.f)
156  {
157  float sum = 0.f;
158  float weight = 0.f;
159 
160  for (int l = -2; l < 3; l++)
161  for (int k = -2; k < 3; k++)
162  {
163  const float abs_dif = abs(
164  depth[i_1](v2 + k, u2 + l) - dcenter);
165  if (abs_dif < max_depth_dif)
166  {
167  const float aux_w =
168  g_mask[2 + k][2 + l] *
169  (max_depth_dif - abs_dif);
170  weight += aux_w;
171  sum +=
172  aux_w * depth[i_1](v2 + k, u2 + l);
173  }
174  }
175  depth[i](v, u) = sum / weight;
176  }
177  else
178  {
179  float min_depth = 10.f;
180  for (int l = -2; l < 3; l++)
181  for (int k = -2; k < 3; k++)
182  {
183  const float d = depth[i_1](v2 + k, u2 + l);
184  if ((d > 0.f) && (d < min_depth))
185  min_depth = d;
186  }
187 
188  if (min_depth < 10.f)
189  depth[i](v, u) = min_depth;
190  else
191  depth[i](v, u) = 0.f;
192  }
193  }
194 
195  // Boundary
196  else
197  {
198  if (dcenter > 0.f)
199  {
200  float sum = 0.f;
201  float weight = 0.f;
202 
203  for (int l = -2; l < 3; l++)
204  for (int k = -2; k < 3; k++)
205  {
206  const int indv = v2 + k, indu = u2 + l;
207  if ((indv >= 0) && (indv < rows_i2) &&
208  (indu >= 0) && (indu < cols_i2))
209  {
210  const float abs_dif = abs(
211  depth[i_1](indv, indu) - dcenter);
212  if (abs_dif < max_depth_dif)
213  {
214  const float aux_w =
215  g_mask[2 + k][2 + l] *
216  (max_depth_dif - abs_dif);
217  weight += aux_w;
218  sum +=
219  aux_w * depth[i_1](indv, indu);
220  }
221  }
222  }
223  depth[i](v, u) = sum / weight;
224  }
225  else
226  {
227  float min_depth = 10.f;
228  for (int l = -2; l < 3; l++)
229  for (int k = -2; k < 3; k++)
230  {
231  const int indv = v2 + k, indu = u2 + l;
232  if ((indv >= 0) && (indv < rows_i2) &&
233  (indu >= 0) && (indu < cols_i2))
234  {
235  const float d = depth[i_1](indv, indu);
236  if ((d > 0.f) && (d < min_depth))
237  min_depth = d;
238  }
239  }
240 
241  if (min_depth < 10.f)
242  depth[i](v, u) = min_depth;
243  else
244  depth[i](v, u) = 0.f;
245  }
246  }
247  }
248  }
249 
250  // Calculate coordinates "xy" of the points
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);
254 
255  for (unsigned int u = 0; u < cols_i; u++)
256  for (unsigned int v = 0; v < rows_i; v++)
257  if (depth[i](v, u) > 0.f)
258  {
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;
261  }
262  else
263  {
264  xx[i](v, u) = 0.f;
265  yy[i](v, u) = 0.f;
266  }
267  }
268 }
269 
271 {
272  const float max_depth_dif = 0.1f;
273 
274  // Push coordinates back
275  depth_old.swap(depth);
276  xx_old.swap(xx);
277  yy_old.swap(yy);
278 
279  // The number of levels of the pyramid does not match the number of levels
280  // used
281  // in the odometry computation (because we might want to finish with lower
282  // resolutions)
283 
284  unsigned int pyr_levels =
285  round(log(float(width / cols)) / log(2.f)) + ctf_levels;
286 
287  // Generate levels
288  for (unsigned int i = 0; i < pyr_levels; i++)
289  {
290  unsigned int s = pow(2.f, int(i));
291  cols_i = width / s;
292  rows_i = height / s;
293  // const int rows_i2 = 2*rows_i;
294  // const int cols_i2 = 2*cols_i;
295  const int i_1 = i - 1;
296 
297  if (i == 0) depth[i].swap(depth_wf);
298 
299  // Downsampling
300  //-----------------------------------------------------------------------------
301  else
302  {
303  for (unsigned int u = 0; u < cols_i; u++)
304  for (unsigned int v = 0; v < rows_i; v++)
305  {
306  const int u2 = 2 * u;
307  const int v2 = 2 * v;
308 
309  // Inner pixels
310  if ((v > 0) && (v < rows_i - 1) && (u > 0) &&
311  (u < cols_i - 1))
312  {
313  const Matrix4f d_block =
314  depth[i_1].block<4, 4>(v2 - 1, u2 - 1);
315  float depths[4] = {d_block(5), d_block(6), d_block(9),
316  d_block(10)};
317  float dcenter;
318 
319  // Sort the array (try to find a good/representative
320  // value)
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])
328  dcenter = depths[1];
329  else
330  dcenter = depths[2];
331 
332  if (dcenter > 0.f)
333  {
334  float sum = 0.f;
335  float weight = 0.f;
336 
337  for (unsigned char k = 0; k < 16; k++)
338  {
339  const float abs_dif = abs(d_block(k) - dcenter);
340  if (abs_dif < max_depth_dif)
341  {
342  const float aux_w =
343  f_mask(k) * (max_depth_dif - abs_dif);
344  weight += aux_w;
345  sum += aux_w * d_block(k);
346  }
347  }
348  depth[i](v, u) = sum / weight;
349  }
350  else
351  depth[i](v, u) = 0.f;
352  }
353 
354  // Boundary
355  else
356  {
357  const Matrix2f d_block = depth[i_1].block<2, 2>(v2, u2);
358  const float new_d = 0.25f * d_block.sumAll();
359  if (new_d < 0.4f)
360  depth[i](v, u) = 0.f;
361  else
362  depth[i](v, u) = new_d;
363  }
364  }
365  }
366 
367  // Calculate coordinates "xy" of the points
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);
371 
372  for (unsigned int u = 0; u < cols_i; u++)
373  for (unsigned int v = 0; v < rows_i; v++)
374  if (depth[i](v, u) > 0.f)
375  {
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;
378  }
379  else
380  {
381  xx[i](v, u) = 0.f;
382  yy[i](v, u) = 0.f;
383  }
384  }
385 }
386 
388 {
389  // Camera parameters (which also depend on the level resolution)
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);
393 
394  // Rigid transformation estimated up to the present level
395  Matrix4f acu_trans;
396  acu_trans.setIdentity();
397  for (unsigned int i = 1; i <= level; i++)
398  acu_trans = transformations[i - 1] * acu_trans;
399 
400  MatrixXf wacu(rows_i, cols_i);
401  wacu.assign(0.f);
402  depth_warped[image_level].assign(0.f);
403 
404  const float cols_lim = float(cols_i - 1);
405  const float rows_lim = float(rows_i - 1);
406 
407  // Warping loop
408  //---------------------------------------------------------
409  for (unsigned int j = 0; j < cols_i; j++)
410  for (unsigned int i = 0; i < rows_i; i++)
411  {
412  const float z = depth[image_level](i, j);
413 
414  if (z > 0.f)
415  {
416  // Transform point to the warped reference frame
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) +
420  acu_trans(0, 3);
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) +
424  acu_trans(1, 3);
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) +
428  acu_trans(2, 3);
429 
430  // Calculate warping
431  const float uwarp = f * x_w / depth_w + disp_u_i;
432  const float vwarp = f * y_w / depth_w + disp_v_i;
433 
434  // The warped pixel (which is not integer in general)
435  // contributes to all the surrounding ones
436  if ((uwarp >= 0.f) && (uwarp < cols_lim) && (vwarp >= 0.f) &&
437  (vwarp < rows_lim))
438  {
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);
447 
448  // Warped pixel very close to an integer value
449  if (abs(round(uwarp) - uwarp) + abs(round(vwarp) - vwarp) <
450  0.05f)
451  {
452  depth_warped[image_level](round(vwarp), round(uwarp)) +=
453  depth_w;
454  wacu(round(vwarp), round(uwarp)) += 1.f;
455  }
456  else
457  {
458  const float w_ur = square(delta_l) + square(delta_d);
459  depth_warped[image_level](vwarp_u, uwarp_r) +=
460  w_ur * depth_w;
461  wacu(vwarp_u, uwarp_r) += w_ur;
462 
463  const float w_ul = square(delta_r) + square(delta_d);
464  depth_warped[image_level](vwarp_u, uwarp_l) +=
465  w_ul * depth_w;
466  wacu(vwarp_u, uwarp_l) += w_ul;
467 
468  const float w_dr = square(delta_l) + square(delta_u);
469  depth_warped[image_level](vwarp_d, uwarp_r) +=
470  w_dr * depth_w;
471  wacu(vwarp_d, uwarp_r) += w_dr;
472 
473  const float w_dl = square(delta_r) + square(delta_u);
474  depth_warped[image_level](vwarp_d, uwarp_l) +=
475  w_dl * depth_w;
476  wacu(vwarp_d, uwarp_l) += w_dl;
477  }
478  }
479  }
480  }
481 
482  // Scale the averaged depth and compute spatial coordinates
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++)
486  {
487  if (wacu(v, u) > 0.f)
488  {
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;
494  }
495  else
496  {
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;
500  }
501  }
502 }
503 
505 {
506  null.resize(rows_i, cols_i);
507  null.assign(false);
508  num_valid_points = 0;
509 
510  for (unsigned int u = 0; u < cols_i; u++)
511  for (unsigned int v = 0; v < rows_i; v++)
512  {
513  if ((depth_old[image_level](v, u)) == 0.f ||
514  (depth_warped[image_level](v, u) == 0.f))
515  {
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;
519  null(v, u) = true;
520  }
521  else
522  {
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) =
527  0.5f *
528  (xx_old[image_level](v, u) + xx_warped[image_level](v, u));
529  yy_inter[image_level](v, u) =
530  0.5f *
531  (yy_old[image_level](v, u) + yy_warped[image_level](v, u));
532  null(v, u) = false;
533  if ((u > 0) && (v > 0) && (u < cols_i - 1) && (v < rows_i - 1))
534  num_valid_points++;
535  }
536  }
537 }
538 
540 {
541  dt.resize(rows_i, cols_i);
542  dt.assign(0.f);
543  du.resize(rows_i, cols_i);
544  du.assign(0.f);
545  dv.resize(rows_i, cols_i);
546  dv.assign(0.f);
547 
548  // Compute connectivity
549  MatrixXf rx_ninv(rows_i, cols_i);
550  MatrixXf ry_ninv(rows_i, cols_i);
551  rx_ninv.assign(1.f);
552  ry_ninv.assign(1.f);
553 
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)
557  {
558  rx_ninv(v, u) = sqrtf(
559  square(
560  xx_inter[image_level](v, u + 1) -
561  xx_inter[image_level](v, u)) +
562  square(
563  depth_inter[image_level](v, u + 1) -
564  depth_inter[image_level](v, u)));
565  }
566 
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)
570  {
571  ry_ninv(v, u) = sqrtf(
572  square(
573  yy_inter[image_level](v + 1, u) -
574  yy_inter[image_level](v, u)) +
575  square(
576  depth_inter[image_level](v + 1, u) -
577  depth_inter[image_level](v, u)));
578  }
579 
580  // Spatial derivatives
581  for (unsigned int v = 0; v < rows_i; v++)
582  {
583  for (unsigned int u = 1; u < cols_i - 1; u++)
584  if (null(v, u) == false)
585  du(v, u) =
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));
591 
592  du(v, 0) = du(v, 1);
593  du(v, cols_i - 1) = du(v, cols_i - 2);
594  }
595 
596  for (unsigned int u = 0; u < cols_i; u++)
597  {
598  for (unsigned int v = 1; v < rows_i - 1; v++)
599  if (null(v, u) == false)
600  dv(v, u) =
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));
606 
607  dv(0, u) = dv(1, u);
608  dv(rows_i - 1, u) = dv(rows_i - 2, u);
609  }
610 
611  // Temporal derivative
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));
617 }
618 
620 {
621  weights.resize(rows_i, cols_i);
622  weights.assign(0.f);
623 
624  // Obtain the velocity associated to the rigid transformation estimated up
625  // to the present level
626  Matrix<float, 6, 1> kai_level = kai_loc_old;
627 
628  Matrix4f acu_trans;
629  acu_trans.setIdentity();
630  for (unsigned int i = 0; i < level; i++)
631  acu_trans = transformations[i] * acu_trans;
632 
633  // Alternative way to compute the log
634  CMatrixDouble44 mat_aux = acu_trans.cast<double>();
635  poses::CPose3D aux(mat_aux);
636  CArrayDouble<6> kai_level_acu = aux.ln() * fps;
637  kai_level -= kai_level_acu.cast<float>();
638 
639  // Parameters for the measurement error
640  const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
641  const float kz2 = 8.122e-12f; // square(1.425e-5) / 25
642 
643  // Parameters for linearization error
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;
648 
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)
652  {
653  // Compute measurment error (simplified)
654  //-----------------------------------------------------------------------
655  const float z = depth_inter[image_level](v, u);
656  const float inv_d = 1.f / z;
657  // const float dycomp = du2(v,u)*f_inv_y*inv_d;
658  // const float dzcomp = dv2(v,u)*f_inv_z*inv_d;
659  const float z2 = z * z;
660  const float z4 = z2 * z2;
661 
662  // const float var11 = kz2*z4;
663  // const float var12 =
664  // kz2*xx_inter[image_level](v,u)*z2*depth_inter[image_level](v,u);
665  // const float var13 =
666  // kz2*yy_inter[image_level](v,u)*z2*depth_inter[image_level](v,u);
667  // const float var22 =
668  // kz2*square(xx_inter[image_level](v,u))*z2;
669  // const float var23 =
670  // kz2*xx_inter[image_level](v,u)*yy_inter[image_level](v,u)*z2;
671  // const float var33 =
672  // kz2*square(yy_inter[image_level](v,u))*z2;
673  const float var44 = kz2 * z4 * square(fps);
674  const float var55 = kz2 * z4 * 0.25f;
675  const float var66 = var55;
676 
677  // const float j1 =
678  // -2.f*inv_d*inv_d*(xx_inter[image_level](v,u)*dycomp +
679  // yy_inter[image_level](v,u)*dzcomp)*(kai_level[0] +
680  // yy_inter[image_level](v,u)*kai_level[4] -
681  // xx_inter[image_level](v,u)*kai_level[5])
682  // + inv_d*dycomp*(kai_level[1] -
683  // yy_inter[image_level](v,u)*kai_level[3]) +
684  // inv_d*dzcomp*(kai_level[2] +
685  // xx_inter[image_level](v,u)*kai_level[3]);
686  // const float j2 = inv_d*dycomp*(kai_level[0] +
687  // yy_inter[image_level](v,u)*kai_level[4] -
688  // 2.f*xx_inter[image_level](v,u)*kai_level[5]) -
689  // dzcomp*kai_level[3];
690  // const float j3 = inv_d*dzcomp*(kai_level[0] +
691  // 2.f*yy_inter[image_level](v,u)*kai_level[4] -
692  // xx_inter[image_level](v,u)*kai_level[5]) +
693  // dycomp*kai_level[3];
694 
695  const float j4 = 1.f;
696  const float j5 =
697  xx_inter[image_level](v, u) * inv_d * inv_d * f_inv *
698  (kai_level[0] +
699  yy_inter[image_level](v, u) * kai_level[4] -
700  xx_inter[image_level](v, u) * kai_level[5]) +
701  inv_d * f_inv *
702  (-kai_level[1] - z * kai_level[5] +
703  yy_inter[image_level](v, u) * kai_level[3]);
704  const float j6 =
705  yy_inter[image_level](v, u) * inv_d * inv_d * f_inv *
706  (kai_level[0] +
707  yy_inter[image_level](v, u) * kai_level[4] -
708  xx_inter[image_level](v, u) * kai_level[5]) +
709  inv_d * f_inv *
710  (-kai_level[2] + z * kai_level[4] -
711  xx_inter[image_level](v, u) * kai_level[3]);
712 
713  // error_measurement(v,u) = j1*(j1*var11+j2*var12+j3*var13) +
714  // j2*(j1*var12+j2*var22+j3*var23)
715  // +j3*(j1*var13+j2*var23+j3*var33) +
716  // j4*j4*var44
717  //+
718  // j5*j5*var55 + j6*j6*var66;
719 
720  const float error_m =
721  j4 * j4 * var44 + j5 * j5 * var55 + j6 * j6 * var66;
722 
723  // Compute linearization error
724  //-----------------------------------------------------------------------
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);
733 
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);
738  const float dvu =
739  dv(v, u + 1) -
740  dv(v, u - 1); // Completely equivalent to compute duv
741 
742  const float error_l =
743  kdt * square(dt(v, u)) +
744  kduv * (square(du(v, u)) + square(dv(v, u))) +
745  k2dt * (square(dut) + square(dvt)) +
746  k2duv * (square(duu) + square(dvv) + square(dvu));
747 
748  // Weight
749  weights(v, u) = sqrt(1.f / (error_m + error_l));
750  }
751 
752  // Normalize weights in the range [0,1]
753  const float inv_max = 1.f / weights.maximum();
754  weights = inv_max * weights;
755 }
756 
758 {
759  MatrixXf A(num_valid_points, 6);
760  MatrixXf B(num_valid_points, 1);
761  unsigned int cont = 0;
762 
763  // Fill the matrix A and the vector B
764  // The order of the unknowns is (vz, vx, vy, wz, wx, wy)
765  // The points order will be (1,1), (1,2)...(1,cols-1), (2,1),
766  // (2,2)...(row-1,cols-1).
767 
768  const float f_inv = float(cols_i) / (2.f * tan(0.5f * fovh));
769 
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)
773  {
774  // Precomputed expressions
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;
781  const float tw = weights(v, u);
782 
783  // Fill the matrix A
784  A(cont, 0) =
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));
794 
795  cont++;
796  }
797 
798  // Solve the linear system of equations using weighted least squares
799  MatrixXf AtA, AtB;
800  AtA.multiply_AtA(A);
801  AtB.multiply_AtB(A, B);
802  MatrixXf Var = AtA.ldlt().solve(AtB);
803 
804  // Covariance matrix calculation
805  MatrixXf res = -B;
806  for (unsigned int k = 0; k < 6; k++) res += Var(k) * A.col(k);
807 
808  est_cov =
809  (1.f / float(num_valid_points - 6)) * AtA.inverse() * res.squaredNorm();
810 
811  // Update last velocity in local coordinates
812  kai_loc_level = Var;
813 }
814 
816 {
817  // Clock to measure the runtime
818  utils::CTicTac clock;
819  clock.Tic();
820 
821  // Build the gaussian pyramid
822  if (fast_pyramid)
823  buildCoordinatesPyramidFast();
824  else
825  buildCoordinatesPyramid();
826 
827  // Coarse-to-fines scheme
828  for (unsigned int i = 0; i < ctf_levels; i++)
829  {
830  // Previous computations
831  transformations[i].setIdentity();
832 
833  level = i;
834  unsigned int s = pow(2.f, int(ctf_levels - (i + 1)));
835  cols_i = cols / s;
836  rows_i = rows / s;
837  image_level =
838  ctf_levels - i + round(log(float(width / cols)) / log(2.f)) - 1;
839 
840  // 1. Perform warping
841  if (i == 0)
842  {
843  depth_warped[image_level] = depth[image_level];
844  xx_warped[image_level] = xx[image_level];
845  yy_warped[image_level] = yy[image_level];
846  }
847  else
848  performWarping();
849 
850  // 2. Calculate inter coords and find null measurements
851  calculateCoord();
852 
853  // 3. Compute derivatives
854  calculateDepthDerivatives();
855 
856  // 4. Compute weights
857  computeWeights();
858 
859  // 5. Solve odometry
860  if (num_valid_points > 6) solveOneLevel();
861 
862  // 6. Filter solution
863  filterLevelSolution();
864  }
865 
866  // Update poses
867  poseUpdate();
868 
869  // Save runtime
870  execution_time = 1000.f * clock.Tac();
871 }
872 
874 {
875  // Calculate Eigenvalues and Eigenvectors
876  //----------------------------------------------------------
877  SelfAdjointEigenSolver<MatrixXf> eigensolver(est_cov);
878  if (eigensolver.info() != Success)
879  {
880  printf("\n Eigensolver couldn't find a solution. Pose is not updated");
881  return;
882  }
883 
884  // First, we have to describe both the new linear and angular velocities in
885  // the "eigenvector" basis
886  //-------------------------------------------------------------------------------------------------
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);
891 
892  // Second, we have to describe both the old linear and angular velocities in
893  // the "eigenvector" basis
894  //-------------------------------------------------------------------------------------------------
895  Matrix<float, 6, 1> kai_loc_sub = kai_loc_old;
896 
897  // Important: we have to substract the previous levels' solutions from the
898  // old velocity.
899  Matrix4f acu_trans;
900  acu_trans.setIdentity();
901  for (unsigned int i = 0; i < level; i++)
902  acu_trans = transformations[i] * acu_trans;
903 
904  CMatrixDouble44 mat_aux = acu_trans.cast<double>();
905  poses::CPose3D aux(mat_aux);
906  CArrayDouble<6> kai_level_acu = aux.ln() * fps;
907  kai_loc_sub -= kai_level_acu.cast<float>();
908 
909  // Matrix<float, 4, 4> log_trans = fps*acu_trans.log();
910  // kai_loc_sub(0) -= log_trans(0,3); kai_loc_sub(1) -= log_trans(1,3);
911  // kai_loc_sub(2) -= log_trans(2,3);
912  // kai_loc_sub(3) += log_trans(1,2); kai_loc_sub(4) -= log_trans(0,2);
913  // kai_loc_sub(5) += log_trans(0,1);
914 
915  // Transform that local representation to the "eigenvector" basis
916  Matrix<float, 6, 1> kai_b_old;
917  kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_sub);
918 
919  // Filter velocity
920  //--------------------------------------------------------------------------------
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++)
925  kai_b_fil(i) =
926  (kai_b(i) +
927  (cf * eigensolver.eigenvalues()(i, 0) + df) * kai_b_old(i)) /
928  (1.f + cf * eigensolver.eigenvalues()(i) + df);
929 
930  // Transform filtered velocity to the local reference frame
931  Matrix<float, 6, 1> kai_loc_fil =
932  Bii.inverse().colPivHouseholderQr().solve(kai_b_fil);
933 
934  // Compute the rigid transformation
935  mrpt::math::CArrayDouble<6> aux_vel = kai_loc_fil.cast<double>() / fps;
936  poses::CPose3D aux1, aux2;
937  CMatrixDouble44 trans;
938  aux2 = aux1.exp(aux_vel);
939  aux2.getHomogeneousMatrix(trans);
940  transformations[level] = trans.cast<float>();
941 }
942 
944 {
945  // First, compute the overall transformation
946  //---------------------------------------------------
947  Matrix4f acu_trans;
948  acu_trans.setIdentity();
949  for (unsigned int i = 1; i <= ctf_levels; i++)
950  acu_trans = transformations[i - 1] * acu_trans;
951 
952  // Compute the new estimates in the local and absolutes reference frames
953  //---------------------------------------------------------------------
954  CMatrixDouble44 mat_aux = acu_trans.cast<double>();
955  poses::CPose3D aux(mat_aux);
956  CArrayDouble<6> kai_level_acu = aux.ln() * fps;
957  kai_loc = kai_level_acu.cast<float>();
958 
959  //---------------------------------------------------------------------------------------------
960  // Directly from Eigen:
961  //- Eigen 3.1.0 needed for Matrix::log()
962  //- The line "#include <unsupported/Eigen/MatrixFunctions>" should be
963  // uncommented (CDifodo.h)
964  //
965  // Matrix<float, 4, 4> log_trans = fps*acu_trans.log();
966  // kai_loc(0) = log_trans(0,3); kai_loc(1) = log_trans(1,3); kai_loc(2) =
967  // log_trans(2,3);
968  // kai_loc(3) = -log_trans(1,2); kai_loc(4) = log_trans(0,2); kai_loc(5) =
969  // -log_trans(0,1);
970  //---------------------------------------------------------------------------------------------
971 
972  CMatrixDouble33 inv_trans;
973  CMatrixFloat31 v_abs, w_abs;
974 
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;
980 
981  // Update poses
982  //-------------------------------------------------------
983  cam_oldpose = cam_pose;
984  CMatrixDouble44 aux_acu = acu_trans;
985  poses::CPose3D pose_aux(aux_acu);
986  cam_pose = cam_pose + pose_aux;
987 
988  // Compute the velocity estimate in the new ref frame (to be used by the
989  // filter in the next iteration)
990  //---------------------------------------------------------------------------------------------------
991  cam_pose.getRotationMatrix(inv_trans);
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);
996 }
997 
998 void CDifodo::setFOV(float new_fovh, float new_fovv)
999 {
1000  fovh = M_PI * new_fovh / 180.0;
1001  fovv = M_PI * new_fovv / 180.0;
1002 }
1003 
1004 void CDifodo::getPointsCoord(MatrixXf& x, MatrixXf& y, MatrixXf& z)
1005 {
1006  x.resize(rows, cols);
1007  y.resize(rows, cols);
1008  z.resize(rows, cols);
1009 
1010  z = depth_inter[0];
1011  x = xx_inter[0];
1012  y = yy_inter[0];
1013 }
1014 
1016  MatrixXf& cur_du, MatrixXf& cur_dv, MatrixXf& cur_dt)
1017 {
1018  cur_du.resize(rows, cols);
1019  cur_dv.resize(rows, cols);
1020  cur_dt.resize(rows, cols);
1021 
1022  cur_du = du;
1023  cur_dv = dv;
1024  cur_dt = dt;
1025 }
1026 
1027 void CDifodo::getWeights(MatrixXf& w)
1028 {
1029  w.resize(rows, cols);
1030  w = weights;
1031 }
GLdouble GLdouble u2
Definition: glext.h:5566
const GLbyte * weights
Definition: glext.h:4450
GLdouble GLdouble z
Definition: glext.h:3872
INT32 z2
Definition: jidctint.cpp:130
void buildCoordinatesPyramid()
Create the gaussian image pyramid according to the number of coarse-to-fine levels.
Definition: CDifodo.cpp:111
void calculateDepthDerivatives()
Calculates the depth derivatives respect to u,v (rows and cols) and t (time)
Definition: CDifodo.cpp:539
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:3600
STL namespace.
#define M_PI
Definition: bits.h:92
GLdouble s
Definition: glext.h:3676
void Tic()
Starts the stopwatch.
Definition: CTicTac.cpp:82
GLenum GLsizei width
Definition: glext.h:3531
void computeWeights()
This method computes the weighting fuction associated to measurement and linearization errors...
Definition: CDifodo.cpp:619
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
void solveOneLevel()
The Solver.
Definition: CDifodo.cpp:757
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
void setFOV(float new_fovh, float new_fovv)
Set the horizontal and vertical field of vision (in degrees)
Definition: CDifodo.cpp:998
void odometryCalculation()
This method performs all the necessary steps to estimate the camera velocity once the new image is re...
Definition: CDifodo.cpp:815
void calculateCoord()
Calculate the "average" coordinates of the points observed by the camera between two consecutive fram...
Definition: CDifodo.cpp:504
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
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.
Definition: CDifodo.cpp:1015
#define M_PIf
INT32 z4
Definition: jidctint.cpp:130
void getWeights(Eigen::MatrixXf &we)
Get the matrix of weights.
Definition: CDifodo.cpp:1027
This class implements a high-performance stopwatch.
Definition: CTicTac.h:23
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.
Definition: CDifodo.cpp:873
void poseUpdate()
Update camera pose and the velocities for the filter.
Definition: CDifodo.cpp:943
void getPointsCoord(Eigen::MatrixXf &x, Eigen::MatrixXf &y, Eigen::MatrixXf &z)
Get the coordinates of the points considered by the visual odometry method.
Definition: CDifodo.cpp:1004
const GLdouble * v
Definition: glext.h:3678
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).
Definition: CPose3D.h:88
T square(const T x)
Inline function for the square of a number.
GLint level
Definition: glext.h:3600
double Tac()
Stops the stopwatch.
Definition: CTicTac.cpp:97
A partial specialization of CArrayNumeric for double numbers.
Definition: CArrayNumeric.h:87
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:25
GLenum GLint GLint y
Definition: glext.h:3538
GLfloat GLfloat GLfloat v2
Definition: glext.h:4107
GLuint res
Definition: glext.h:7268
GLenum GLint x
Definition: glext.h:3538
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Definition: CPose3D.h:237
GLenum GLsizei GLsizei height
Definition: glext.h:3554
void buildCoordinatesPyramidFast()
Definition: CDifodo.cpp:270
void performWarping()
Warp the second depth image against the first one according to the 3D transformations accumulated up ...
Definition: CDifodo.cpp:387



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019