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



Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020