Main MRPT website > C++ reference for MRPT 1.9.9
COccupancyGridMap2D_common.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 "maps-precomp.h" // Precomp header
11 
12 // Force size_x being a multiple of 16 cells
13 //#define ROWSIZE_MULTIPLE_16
14 
17 #include <mrpt/utils/CStream.h>
18 #include <mrpt/poses/CPose3D.h>
19 
20 using namespace mrpt;
21 using namespace mrpt::math;
22 using namespace mrpt::maps;
23 using namespace mrpt::obs;
24 using namespace mrpt::utils;
25 using namespace mrpt::poses;
26 using namespace std;
27 
28 // =========== Begin of Map definition ============
30  "COccupancyGridMap2D,occupancyGrid", mrpt::maps::COccupancyGridMap2D)
31 
33  : min_x(-10.0f),
34  max_x(10.0f),
35  min_y(-10.0f),
36  max_y(10.0f),
37  resolution(0.10f)
38 {
39 }
40 
41 void COccupancyGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(
43  const std::string& sectionNamePrefix)
44 {
45  // [<sectionNamePrefix>+"_creationOpts"]
46  const std::string sSectCreation =
47  sectionNamePrefix + string("_creationOpts");
48  MRPT_LOAD_CONFIG_VAR(min_x, float, source, sSectCreation);
49  MRPT_LOAD_CONFIG_VAR(max_x, float, source, sSectCreation);
50  MRPT_LOAD_CONFIG_VAR(min_y, float, source, sSectCreation);
51  MRPT_LOAD_CONFIG_VAR(max_y, float, source, sSectCreation);
52  MRPT_LOAD_CONFIG_VAR(resolution, float, source, sSectCreation);
53 
54  // [<sectionName>+"_occupancyGrid_##_insertOpts"]
55  insertionOpts.loadFromConfigFile(
56  source, sectionNamePrefix + string("_insertOpts"));
57 
58  // [<sectionName>+"_occupancyGrid_##_likelihoodOpts"]
59  likelihoodOpts.loadFromConfigFile(
60  source, sectionNamePrefix + string("_likelihoodOpts"));
61 }
62 
63 void COccupancyGridMap2D::TMapDefinition::dumpToTextStream_map_specific(
64  mrpt::utils::CStream& out) const
65 {
66  LOADABLEOPTS_DUMP_VAR(min_x, float);
67  LOADABLEOPTS_DUMP_VAR(max_x, float);
68  LOADABLEOPTS_DUMP_VAR(min_y, float);
69  LOADABLEOPTS_DUMP_VAR(max_y, float);
70  LOADABLEOPTS_DUMP_VAR(resolution, float);
71 
72  this->insertionOpts.dumpToTextStream(out);
73  this->likelihoodOpts.dumpToTextStream(out);
74 }
75 
76 mrpt::maps::CMetricMap* COccupancyGridMap2D::internal_CreateFromMapDefinition(
78 {
80  *dynamic_cast<const COccupancyGridMap2D::TMapDefinition*>(&_def);
82  def.min_x, def.max_x, def.min_y, def.max_y, def.resolution);
83  obj->insertionOptions = def.insertionOpts;
84  obj->likelihoodOptions = def.likelihoodOpts;
85  return obj;
86 }
87 // =========== End of Map definition Block =========
88 
90 
91 std::vector<float> COccupancyGridMap2D::entropyTable;
92 
93 static const float MAX_H = 0.69314718055994531f; // ln(2)
94 
95 // Static lookup tables for log-odds
97 CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> & COccupancyGridMap2D::get_logodd_lut()
98 {
99  return logodd_lut;
100 }
101 
102 
103 /*---------------------------------------------------------------
104  Constructor
105  ---------------------------------------------------------------*/
106 COccupancyGridMap2D::COccupancyGridMap2D(
107  float min_x, float max_x, float min_y, float max_y, float resolution)
108  : map(),
109  size_x(0),
110  size_y(0),
111  x_min(),
112  x_max(),
113  y_min(),
114  y_max(),
115  resolution(),
116  precomputedLikelihood(),
117  precomputedLikelihoodToBeRecomputed(true),
118  m_basis_map(),
119  m_voronoi_diagram(),
120  m_is_empty(true),
121  voroni_free_threshold(),
122  updateInfoChangeOnly(),
123  insertionOptions(),
124  likelihoodOptions(),
125  likelihoodOutputs(),
126  CriticalPointsList()
127 {
128  MRPT_START
129  setSize(min_x, max_x, min_y, max_y, resolution, 0.5f);
130  MRPT_END
131 }
132 
133 /*---------------------------------------------------------------
134  Destructor
135  ---------------------------------------------------------------*/
138 {
139  freeMap();
141  x_min = o.x_min;
142  x_max = o.x_max;
143  y_min = o.y_min;
144  y_max = o.y_max;
145  size_x = o.size_x;
146  size_y = o.size_y;
147  map = o.map;
148 
149  m_basis_map.clear();
151 
154 }
155 
156 /*---------------------------------------------------------------
157  setSize
158  ---------------------------------------------------------------*/
160  float x_min, float x_max, float y_min, float y_max, float resolution,
161  float default_value)
162 {
163  MRPT_START
164 
165  ASSERT_(resolution > 0)
166  ASSERT_(x_max > x_min && y_max > y_min)
167  ASSERT_(default_value >= 0 && default_value <= 1)
168 
169  // Liberar primero:
170  freeMap();
171 
172  // For the precomputed likelihood trick:
174 
175  // Adjust sizes to adapt them to full sized cells acording to the
176  // resolution:
181 
182  // Set parameters:
183  this->resolution = resolution;
184  this->x_min = x_min;
185  this->x_max = x_max;
186  this->y_min = y_min;
187  this->y_max = y_max;
188 
189  // Now the number of cells should be integers:
190  size_x = round((x_max - x_min) / resolution);
191  size_y = round((y_max - y_min) / resolution);
192 
193 #ifdef ROWSIZE_MULTIPLE_16
194  // map rows must be 16 bytes aligned:
195  if (0 != (size_x % 16))
196  {
197  size_x = ((size_x >> 4) + 1) << 4;
199  }
200  size_x = round((x_max - x_min) / resolution);
201  ASSERT_(0 == (size_x % 16));
202 #endif
203 
204  // Cells memory:
205  map.resize(size_x * size_y, p2l(default_value));
206 
207  // Free these buffers also:
208  m_basis_map.clear();
210 
211  m_is_empty = true;
212 
213  MRPT_END
214 }
215 
216 /*---------------------------------------------------------------
217  ResizeGrid
218  ---------------------------------------------------------------*/
220  float new_x_min, float new_x_max, float new_y_min, float new_y_max,
221  float new_cells_default_value, bool additionalMargin) noexcept
222 {
223  unsigned int extra_x_izq = 0, extra_y_arr = 0, new_size_x = 0,
224  new_size_y = 0;
225  std::vector<cellType> new_map;
226 
227  if (new_x_min > new_x_max)
228  {
229  printf(
230  "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: "
231  "x_min=%f x_max=%f\n",
232  new_x_min, new_x_max);
233  return;
234  }
235  if (new_y_min > new_y_max)
236  {
237  printf(
238  "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: "
239  "y_min=%f y_max=%f\n",
240  new_y_min, new_y_max);
241  return;
242  }
243 
244  // Required?
245  if (new_x_min >= x_min && new_y_min >= y_min && new_x_max <= x_max &&
246  new_y_max <= y_max)
247  return;
248 
249  // For the precomputed likelihood trick:
250  precomputedLikelihoodToBeRecomputed = true;
251 
252  // Add an additional margin:
253  if (additionalMargin)
254  {
255  if (new_x_min < x_min) new_x_min = floor(new_x_min - 4);
256  if (new_x_max > x_max) new_x_max = ceil(new_x_max + 4);
257  if (new_y_min < y_min) new_y_min = floor(new_y_min - 4);
258  if (new_y_max > y_max) new_y_max = ceil(new_y_max + 4);
259  }
260 
261  // We do not support grid shrinking... at least stay the same:
262  new_x_min = min(new_x_min, x_min);
263  new_x_max = max(new_x_max, x_max);
264  new_y_min = min(new_y_min, y_min);
265  new_y_max = max(new_y_max, y_max);
266 
267  // Adjust sizes to adapt them to full sized cells acording to the
268  // resolution:
269  if (fabs(new_x_min / resolution - round(new_x_min / resolution)) > 0.05f)
270  new_x_min = resolution * round(new_x_min / resolution);
271  if (fabs(new_y_min / resolution - round(new_y_min / resolution)) > 0.05f)
272  new_y_min = resolution * round(new_y_min / resolution);
273  if (fabs(new_x_max / resolution - round(new_x_max / resolution)) > 0.05f)
274  new_x_max = resolution * round(new_x_max / resolution);
275  if (fabs(new_y_max / resolution - round(new_y_max / resolution)) > 0.05f)
276  new_y_max = resolution * round(new_y_max / resolution);
277 
278  // Change size: 4 sides extensions:
279  extra_x_izq = round((x_min - new_x_min) / resolution);
280  extra_y_arr = round((y_min - new_y_min) / resolution);
281 
282  new_size_x = round((new_x_max - new_x_min) / resolution);
283  new_size_y = round((new_y_max - new_y_min) / resolution);
284 
285  assert(new_size_x >= size_x + extra_x_izq);
286 
287 #ifdef ROWSIZE_MULTIPLE_16
288  // map rows must be 16 bytes aligned:
289  size_t old_new_size_x = new_size_x; // Debug
290  if (0 != (new_size_x % 16))
291  {
292  int size_x_incr = 16 - (new_size_x % 16);
293  // new_x_max = new_x_min + new_size_x * resolution;
294  new_x_max += size_x_incr * resolution;
295  }
296  new_size_x = round((new_x_max - new_x_min) / resolution);
297  assert(0 == (new_size_x % 16));
298 #endif
299 
300  // Reserve new mem block
301  new_map.resize(new_size_x * new_size_y, p2l(new_cells_default_value));
302 
303  // Copy all the old map rows into the new map:
304  {
305  cellType* dest_ptr = &new_map[extra_x_izq + extra_y_arr * new_size_x];
306  cellType* src_ptr = &map[0];
307  size_t row_size = size_x * sizeof(cellType);
308 
309  for (size_t y = 0; y < size_y; y++)
310  {
311 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)
312  assert(dest_ptr + row_size - 1 <= &new_map[new_map.size() - 1]);
313  assert(src_ptr + row_size - 1 <= &map[map.size() - 1]);
314 #endif
315  memcpy(dest_ptr, src_ptr, row_size);
316  dest_ptr += new_size_x;
317  src_ptr += size_x;
318  }
319  }
320 
321  // Move new values into the new map:
322  x_min = new_x_min;
323  x_max = new_x_max;
324  y_min = new_y_min;
325  y_max = new_y_max;
326 
327  size_x = new_size_x;
328  size_y = new_size_y;
329 
330  // Free old map, replace by new one:
331  map.swap(new_map);
332 
333  // Free the other buffers:
334  m_basis_map.clear();
335  m_voronoi_diagram.clear();
336 }
337 
338 /*---------------------------------------------------------------
339  freeMap
340  ---------------------------------------------------------------*/
342 {
343  MRPT_START
344 
345  // Free map and sectors
346  map.clear();
347 
348  m_basis_map.clear();
350 
351  size_x = size_y = 0;
352 
353  // For the precomputed likelihood trick:
355 
356  m_is_empty = true;
357 
358  MRPT_END
359 }
360 
361 /*---------------------------------------------------------------
362  Computes the entropy and related values of this grid map.
363  out_H The target variable for absolute entropy, computed
364  as:<br><center>H(map)=Sum<sub>x,y</sub>{ -p(x,y)ln(p(x,y))
365  -(1-p(x,y))ln(1-p(x,y)) }</center><br><br>
366  out_I The target variable for absolute "information", defining I(x) = 1 -
367  H(x)
368  out_mean_H The target variable for mean entropy, defined as entropy per
369  square meter: mean_H(map) = H(map) / (Map length x (meters))(Map length y
370  (meters))
371  out_mean_I The target variable for mean information, defined as information
372  per square meter: mean_I(map) = I(map) / (Map length x (meters))(Map length y
373  (meters))
374  ---------------------------------------------------------------*/
376 {
377  unsigned long i;
378  float h, p;
379 
380 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
381  unsigned int N = 256;
382 #else
383  unsigned int N = 65536;
384 #endif
385 
386  // Compute the entropy table: The entropy for each posible cell value
387  // ----------------------------------------------------------------------
388  if (entropyTable.size() != N)
389  {
390  entropyTable.resize(N, 0);
391  for (i = 0; i < N; i++)
392  {
393  p = l2p(static_cast<cellType>(i));
394  h = H(p) + H(1 - p);
395 
396  // Cell's probabilities rounding problem fixing:
397  if (i == 0 || i == (N - 1)) h = 0;
398  if (h > (MAX_H - 1e-4)) h = MAX_H;
399 
400  entropyTable[i] = h;
401  }
402  }
403 
404  // Initialize the global results:
405  info.H = info.I = 0;
406  info.effectiveMappedCells = 0;
407 
408  info.H = info.I = 0;
409  info.effectiveMappedCells = 0;
410  for (std::vector<cellType>::const_iterator it = map.begin();
411  it != map.end(); ++it)
412  {
413  cellTypeUnsigned i = static_cast<cellTypeUnsigned>(*it);
414  h = entropyTable[i];
415  info.H += h;
416  if (h < (MAX_H - 0.001f))
417  {
418  info.effectiveMappedCells++;
419  info.I -= h;
420  }
421  }
422 
423  // The info: (See ref. paper EMMI in IROS 2006)
424  info.I /= MAX_H;
425  info.I += info.effectiveMappedCells;
426 
427  // Mean values:
428  // ------------------------------------------
429  info.effectiveMappedArea =
431  if (info.effectiveMappedCells)
432  {
433  info.mean_H = info.H / info.effectiveMappedCells;
434  info.mean_I = info.I / info.effectiveMappedCells;
435  }
436  else
437  {
438  info.mean_H = 0;
439  info.mean_I = 0;
440  }
441 }
442 
443 /*---------------------------------------------------------------
444  Entropy aux. function
445  ---------------------------------------------------------------*/
446 double COccupancyGridMap2D::H(double p)
447 {
448  if (p == 0 || p == 1)
449  return 0;
450  else
451  return -p * log(p);
452 }
453 
454 /*---------------------------------------------------------------
455  clear
456  ---------------------------------------------------------------*/
458 {
459  setSize(-10, 10, -10, 10, getResolution());
460  // resetFeaturesCache();
461  // For the precomputed likelihood trick:
463 }
464 
465 /*---------------------------------------------------------------
466  fill
467  ---------------------------------------------------------------*/
468 void COccupancyGridMap2D::fill(float default_value)
469 {
470  cellType defValue = p2l(default_value);
471  for (std::vector<cellType>::iterator it = map.begin(); it < map.end(); ++it)
472  *it = defValue;
473  // For the precomputed likelihood trick:
475  // resetFeaturesCache();
476 }
477 
478 /*---------------------------------------------------------------
479  updateCell
480  ---------------------------------------------------------------*/
481 void COccupancyGridMap2D::updateCell(int x, int y, float v)
482 {
483  // Tip: if x<0, (unsigned)(x) will also be >>> size_x ;-)
484  if (static_cast<unsigned int>(x) >= size_x ||
485  static_cast<unsigned int>(y) >= size_y)
486  return;
487 
488  // Get the current contents of the cell:
489  cellType& theCell = map[x + y * size_x];
490 
491  // Compute the new Bayesian-fused value of the cell:
493  {
494  float old = l2p(theCell);
495  float new_v = 1 / (1 + (1 - v) * (1 - old) / (old * v));
497  updateInfoChangeOnly.I_change += 1 - (H(new_v) + H(1 - new_v)) / MAX_H;
498  }
499  else
500  {
501  cellType obs =
502  p2l(v); // The observation: will be >0 for free, <0 for occupied.
503  if (obs > 0)
504  {
505  if (theCell > (OCCGRID_CELLTYPE_MAX - obs))
506  theCell = OCCGRID_CELLTYPE_MAX; // Saturate
507  else
508  theCell += obs;
509  }
510  else
511  {
512  if (theCell < (OCCGRID_CELLTYPE_MIN - obs))
513  theCell = OCCGRID_CELLTYPE_MIN; // Saturate
514  else
515  theCell += obs;
516  }
517  }
518 }
519 
520 /*---------------------------------------------------------------
521  subSample
522  ---------------------------------------------------------------*/
524 {
525  std::vector<cellType> newMap;
526 
527  ASSERT_(downRatio > 0);
528 
529  resolution *= downRatio;
530 
531  int newSizeX = round((x_max - x_min) / resolution);
532  int newSizeY = round((y_max - y_min) / resolution);
533 
534  newMap.resize(newSizeX * newSizeY);
535 
536  for (int x = 0; x < newSizeX; x++)
537  {
538  for (int y = 0; y < newSizeY; y++)
539  {
540  float newCell = 0;
541 
542  for (int xx = 0; xx < downRatio; xx++)
543  for (int yy = 0; yy < downRatio; yy++)
544  newCell += getCell(x * downRatio + xx, y * downRatio + yy);
545 
546  newCell /= (downRatio * downRatio);
547 
548  newMap[x + y * newSizeX] = p2l(newCell);
549  }
550  }
551 
553  map = newMap;
554 }
555 
556 /*---------------------------------------------------------------
557  computeMatchingWith
558  ---------------------------------------------------------------*/
560  const mrpt::maps::CMetricMap* otherMap2, const CPose2D& otherMapPose_,
561  TMatchingPairList& correspondences, const TMatchingParams& params,
562  TMatchingExtraResults& extraResults) const
563 {
564  MRPT_START
565 
566  extraResults = TMatchingExtraResults();
567 
568  ASSERT_ABOVE_(params.decimation_other_map_points, 0)
570  params.offset_other_map_points, params.decimation_other_map_points)
571 
573  const CPointsMap* otherMap = static_cast<const CPointsMap*>(otherMap2);
574 
575  const TPose2D otherMapPose = TPose2D(otherMapPose_);
576 
577  const size_t nLocalPoints = otherMap->size();
578  std::vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
579  z_locals(nLocalPoints);
580 
581  const float sin_phi = sin(otherMapPose.phi);
582  const float cos_phi = cos(otherMapPose.phi);
583 
584  size_t nOtherMapPointsWithCorrespondence =
585  0; // Number of points with one corrs. at least
586  size_t nTotalCorrespondences = 0; // Total number of corrs
587  float _sumSqrDist = 0;
588 
589  // The number of cells to look around each point:
590  const int cellsSearchRange =
591  round(params.maxDistForCorrespondence / resolution);
592 
593  // Initially there are no correspondences:
594  correspondences.clear();
595 
596  // Hay mapa local?
597  if (!nLocalPoints) return; // No
598 
599  // Solo hacer matching si existe alguna posibilidad de que
600  // los dos mapas se toquen:
601  // -----------------------------------------------------------
602  float local_x_min = std::numeric_limits<float>::max();
603  float local_x_max = -std::numeric_limits<float>::max();
604  float local_y_min = std::numeric_limits<float>::max();
605  float local_y_max = -std::numeric_limits<float>::max();
606 
607  const std::vector<float>& otherMap_pxs = otherMap->getPointsBufferRef_x();
608  const std::vector<float>& otherMap_pys = otherMap->getPointsBufferRef_y();
609  const std::vector<float>& otherMap_pzs = otherMap->getPointsBufferRef_z();
610 
611  // Translate all local map points:
612  for (unsigned int localIdx = params.offset_other_map_points;
613  localIdx < nLocalPoints;
614  localIdx += params.decimation_other_map_points)
615  {
616  // Girar y desplazar cada uno de los puntos del local map:
617  const float xx = x_locals[localIdx] = otherMapPose.x +
618  cos_phi * otherMap_pxs[localIdx] -
619  sin_phi * otherMap_pys[localIdx];
620  const float yy = y_locals[localIdx] = otherMapPose.y +
621  sin_phi * otherMap_pxs[localIdx] +
622  cos_phi * otherMap_pys[localIdx];
623  z_locals[localIdx] = /* otherMapPose.z +*/ otherMap_pzs[localIdx];
624 
625  // mantener el max/min de los puntos:
626  local_x_min = min(local_x_min, xx);
627  local_x_max = max(local_x_max, xx);
628  local_y_min = min(local_y_min, yy);
629  local_y_max = max(local_y_max, yy);
630  }
631 
632  // If the local map is entirely out of the grid,
633  // do not even try to match them!!
634  if (local_x_min > x_max || local_x_max < x_min || local_y_min > y_max ||
635  local_y_max < y_min)
636  return; // Matching is NULL!
637 
638  const cellType thresholdCellValue = p2l(0.5f);
639 
640  // For each point in the other map:
641  for (unsigned int localIdx = params.offset_other_map_points;
642  localIdx < nLocalPoints;
643  localIdx += params.decimation_other_map_points)
644  {
645  // Starting value:
646  float maxDistForCorrespondenceSquared =
647  square(params.maxDistForCorrespondence);
648 
649  // For speed-up:
650  const float x_local = x_locals[localIdx];
651  const float y_local = y_locals[localIdx];
652  const float z_local = z_locals[localIdx];
653 
654  // Look for the occupied cell closest from the map point:
655  float min_dist = 1e6;
656  TMatchingPair closestCorr;
657 
658  // Get the indexes of cell where the point falls:
659  const int cx0 = x2idx(x_local);
660  const int cy0 = y2idx(y_local);
661 
662  // Get the rectangle to look for into:
663  const int cx_min = max(0, cx0 - cellsSearchRange);
664  const int cx_max =
665  min(static_cast<int>(size_x) - 1, cx0 + cellsSearchRange);
666  const int cy_min = max(0, cy0 - cellsSearchRange);
667  const int cy_max =
668  min(static_cast<int>(size_y) - 1, cy0 + cellsSearchRange);
669 
670  // Will be set to true if a corrs. is found:
671  bool thisLocalHasCorr = false;
672 
673  // Look in nearby cells:
674  for (int cx = cx_min; cx <= cx_max; cx++)
675  {
676  for (int cy = cy_min; cy <= cy_max; cy++)
677  {
678  // Is an occupied cell?
679  if (map[cx + cy * size_x] <
680  thresholdCellValue) // getCell(cx,cy)<0.49)
681  {
682  const float residual_x = idx2x(cx) - x_local;
683  const float residual_y = idx2y(cy) - y_local;
684 
685  // Compute max. allowed distance:
686  maxDistForCorrespondenceSquared = square(
687  params.maxAngularDistForCorrespondence *
688  params.angularDistPivotPoint.distanceTo(
689  TPoint3D(x_local, y_local, 0)) +
690  params.maxDistForCorrespondence);
691 
692  // Square distance to the point:
693  const float this_dist =
694  square(residual_x) + square(residual_y);
695 
696  if (this_dist < maxDistForCorrespondenceSquared)
697  {
698  if (!params.onlyKeepTheClosest)
699  {
700  // save the correspondence:
701  nTotalCorrespondences++;
702  TMatchingPair mp;
703  mp.this_idx = cx + cy * size_x;
704  mp.this_x = idx2x(cx);
705  mp.this_y = idx2y(cy);
706  mp.this_z = z_local;
707  mp.other_idx = localIdx;
708  mp.other_x = otherMap_pxs[localIdx];
709  mp.other_y = otherMap_pys[localIdx];
710  mp.other_z = otherMap_pzs[localIdx];
711  correspondences.push_back(mp);
712  }
713  else
714  {
715  // save the closest only:
716  if (this_dist < min_dist)
717  {
718  min_dist = this_dist;
719 
720  closestCorr.this_idx = cx + cy * size_x;
721  closestCorr.this_x = idx2x(cx);
722  closestCorr.this_y = idx2y(cy);
723  closestCorr.this_z = z_local;
724  closestCorr.other_idx = localIdx;
725  closestCorr.other_x = otherMap_pxs[localIdx];
726  closestCorr.other_y = otherMap_pys[localIdx];
727  closestCorr.other_z = otherMap_pzs[localIdx];
728  }
729  }
730 
731  // At least one:
732  thisLocalHasCorr = true;
733  }
734  }
735  }
736  } // End of find closest nearby cell
737 
738  // save the closest correspondence:
739  if (params.onlyKeepTheClosest &&
740  (min_dist < maxDistForCorrespondenceSquared))
741  {
742  nTotalCorrespondences++;
743  correspondences.push_back(closestCorr);
744  }
745 
746  // At least one corr:
747  if (thisLocalHasCorr)
748  {
749  nOtherMapPointsWithCorrespondence++;
750 
751  // Accumulate the MSE:
752  _sumSqrDist += min_dist;
753  }
754 
755  } // End "for each local point"...
756 
757  extraResults.correspondencesRatio =
758  nOtherMapPointsWithCorrespondence /
759  static_cast<float>(nLocalPoints / params.decimation_other_map_points);
760  extraResults.sumSqrDist = _sumSqrDist;
761 
762  MRPT_END
763 }
764 
765 /*---------------------------------------------------------------
766  isEmpty
767  ---------------------------------------------------------------*/
768 bool COccupancyGridMap2D::isEmpty() const { return m_is_empty; }
769 /*---------------------------------------------------------------
770  operator <
771  ---------------------------------------------------------------*/
775 {
776  return e1.first > e2.first;
777 }
778 
779 /*---------------------------------------------------------------
780  computePathCost
781  ---------------------------------------------------------------*/
783  float x1, float y1, float x2, float y2) const
784 {
785  float sumCost = 0;
786 
787  float dist = sqrt(square(x1 - x2) + square(y1 - y2));
788  int nSteps = round(1.5f * dist / resolution);
789 
790  for (int i = 0; i < nSteps; i++)
791  {
792  float x = x1 + (x2 - x1) * i / static_cast<float>(nSteps);
793  float y = y1 + (y2 - y1) * i / static_cast<float>(nSteps);
794  sumCost += getPos(x, y);
795  }
796 
797  if (nSteps)
798  return sumCost / static_cast<float>(nSteps);
799  else
800  return 0;
801 }
802 
804  const mrpt::maps::CMetricMap* otherMap,
805  const mrpt::poses::CPose3D& otherMapPose,
806  const TMatchingRatioParams& params) const
807 {
808  MRPT_UNUSED_PARAM(otherMap);
809  MRPT_UNUSED_PARAM(otherMapPose);
811  return 0;
812 }
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
Parameters for CMetricMap::compute3DMatchingRatio()
void clear()
Erase the contents of all the cells.
Definition: CDynamicGrid.h:111
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
#define min(a, b)
float getResolution() const
Returns the resolution of the grid map.
#define ASSERT_ABOVE_(__A, __B)
mrpt::maps::COccupancyGridMap2D::TInsertionOptions insertionOpts
Observations insertion options.
double x
X,Y coordinates.
mrpt::utils::CDynamicGrid< uint8_t > m_basis_map
Used for Voronoi calculation.Same struct as "map", but contains a "0" if not a basis point...
double effectiveMappedArea
The target variable for the area of cells with information, i.e.
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
static double H(double p)
Entropy computation internal function:
#define ASSERT_BELOW_(__A, __B)
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
Definition: CObject.cpp:32
Scalar * iterator
Definition: eigen_plugins.h:26
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
void updateCell(int x, int y, float v)
Performs the Bayesian fusion of a new observation of a cell.
static const float MAX_H
struct mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly updateInfoChangeOnly
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
static const cellType OCCGRID_CELLTYPE_MAX
std::pair< double, mrpt::math::TPoint2D > TPairLikelihoodIndex
Auxiliary private class.
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
void freeMap()
Frees the dynamic memory buffers of map.
std::vector< cellType > map
Store of cell occupancy values.
This class allows loading and storing values and vectors of different types from a configuration text...
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:63
double H
The target variable for absolute entropy, computed as: H(map)=Sumx,y{ -p(x,y)*ln(p(x,y)) -(1-p(x,y))*ln(1-p(x,y)) }
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Definition: CObject.h:85
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
#define MRPT_END
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
bool isEmpty() const override
Returns true upon map construction or after calling clear(), the return changes to false upon success...
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
A list of TMatchingPair.
Definition: TMatchingPair.h:93
void copyMapContentFrom(const COccupancyGridMap2D &otherMap)
copy the gridmap contents, but not all the options, from another map instance
double I
The target variable for absolute "information", defining I(x) = 1 - H(x)
This namespace contains representation of robot actions and observations.
void subSample(int downRatio)
Performs a downsampling of the gridmap, by a given factor: resolution/=ratio.
double I_change
The cummulative change in Information: This is updated only from the "updateCell" method...
static CLogOddsGridMapLUT< COccupancyGridMap2D::cellType > logodd_lut
GLsizei const GLchar ** string
Definition: glext.h:4101
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
double mean_H
The target variable for mean entropy, defined as entropy per cell: mean_H(map) = H(map) / (cells) ...
A class for storing an occupancy grid map.
#define MRPT_START
static const cellType OCCGRID_CELLTYPE_MIN
Discrete to float conversion factors: The min/max values of the integer cell type, eg.
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define MAP_DEFINITION_REGISTER(_CLASSNAME_STRINGS, _CLASSNAME_WITH_NS)
Registers one map class into TMetricMapInitializer factory.
unsigned long effectiveMappedCells
The mapped area in cells.
static cellType p2l(const float p)
Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the val...
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:55
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
int cellsUpdated
The cummulative updated cells count: This is updated only from the "updateCell" method.
static std::vector< float > entropyTable
Internally used to speed-up entropy calculation.
bool m_is_empty
True upon construction; used by isEmpty()
virtual void internal_clear() override
Clear the map: It set all cells to their default occupancy value (0.5), without changing the resoluti...
mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
Lightweight 2D pose.
float min_x
See COccupancyGridMap2D::COccupancyGridMap2D.
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
#define ASSERT_(f)
float idx2y(const size_t cy) const
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:25
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
See the base class for more details: In this class it is implemented as correspondences of the passed...
GLenum GLint GLint y
Definition: glext.h:3538
void computeEntropy(TEntropyInfo &info) const
Computes the entropy and related values of this grid map.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
See docs in base class: in this class this always returns 0.
uint32_t size_x
The size of the grid in cells.
void fill(float default_value=0.5f)
Fills all the cells with a default value.
void resizeGrid(float new_x_min, float new_x_max, float new_y_min, float new_y_max, float new_cells_default_value=0.5f, bool additionalMargin=true) noexcept
Change the size of gridmap, maintaining previous contents.
float x_min
The limits of the grid in "units" (meters)
float getPos(float x, float y) const
Read the real valued [0,1] contents of a cell, given its coordinates.
void setSize(float x_min, float x_max, float y_min, float y_max, float resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
GLenum GLint x
Definition: glext.h:3538
Lightweight 3D point.
float computePathCost(float x1, float y1, float x2, float y2) const
Compute the &#39;cost&#39; of traversing a segment of the map according to the occupancy of traversed cells...
double mean_I
The target variable for mean information, defined as information per cell: mean_I(map) = I(map) / (ce...
Parameters for the determination of matchings between point clouds, etc.
Used for returning entropy related information.
GLfloat GLfloat p
Definition: glext.h:6305
bool operator<(const COccupancyGridMap2D::TPairLikelihoodIndex &e1, const COccupancyGridMap2D::TPairLikelihoodIndex &e2)
GLenum const GLfloat * params
Definition: glext.h:3534
int16_t cellType
The type of the map cells:
int x2idx(float x) const
Transform a coordinate value into a cell index.
double phi
Orientation (rads)
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
Definition: TMatchingPair.h:31
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
static float l2p(const cellType l)
Scales an integer representation of the log-odd into a real valued probability in [0...
One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
Definition: os.cpp:355
bool enabled
If set to false (default), this struct is not used.
mrpt::utils::CDynamicGrid< uint16_t > m_voronoi_diagram
Used to store the Voronoi diagram.



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