MRPT  1.9.9
COccupancyGridMap2D.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, 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 #pragma once
10 
13 #include <mrpt/img/CImage.h>
15 #include <mrpt/maps/CMetricMap.h>
19 #include <mrpt/poses/poses_frwds.h>
22 #include <mrpt/obs/obs_frwds.h>
24 
25 #include <mrpt/config.h>
26 #if ( \
27  !defined(OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS) && \
28  !defined(OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS)) || \
29  (defined(OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS) && \
30  defined(OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS))
31 #error One of OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS or OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS must be defined.
32 #endif
33 
34 namespace mrpt::maps
35 {
36 /** A class for storing an occupancy grid map.
37  * COccupancyGridMap2D is a class for storing a metric map
38  * representation in the form of a probabilistic occupancy
39  * grid map: value of 0 means certainly occupied, 1 means
40  * a certainly empty cell. Initially 0.5 means uncertainty.
41  *
42  * The cells keep the log-odd representation of probabilities instead of the
43  *probabilities themselves.
44  * More details can be found at http://www.mrpt.org/Occupancy_Grids
45  *
46  * The algorithm for updating the grid from a laser scanner can optionally take
47  *into account the progressive widening of the beams, as
48  * described in [this page](http://www.mrpt.org/Occupancy_Grids)
49  *
50  * Some implemented methods are:
51  * - Update of individual cells
52  * - Insertion of observations
53  * - Voronoi diagram and critical points (\a buildVoronoiDiagram)
54  * - Saving and loading from/to a bitmap
55  * - Laser scans simulation for the map contents
56  * - Entropy and information methods (See computeEntropy)
57  *
58  * \ingroup mrpt_maps_grp
59  **/
61 // Inherit from the corresponding specialization of CLogOddsGridMap2D<>:
62 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
63  public CLogOddsGridMap2D<int8_t>
64 #else
65  public CLogOddsGridMap2D<int16_t>
66 #endif
67 {
69  public:
70 /** The type of the map cells: */
71 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
72  using cellType = int8_t;
73  using cellTypeUnsigned = uint8_t;
74 #else
75  using cellType = int16_t;
77 #endif
78 
79  /** Discrete to float conversion factors: The min/max values of the integer
80  * cell type, eg.[0,255] or [0,65535] */
87 
88  /** (Default:1.0) Can be set to <1 if a more fine raytracing is needed in
89  * sonarSimulator() and laserScanSimulator(), or >1 to speed it up. */
91 
92  protected:
93  friend class CMultiMetricMap;
94  friend class CMultiMetricMapPDF;
95 
96  /** Frees the dynamic memory buffers of map. */
97  void freeMap();
98  /** Lookup tables for log-odds */
100 
101  /** Store of cell occupancy values. Order: row by row, from left to right */
102  std::vector<cellType> map;
103  /** The size of the grid in cells */
105  /** The limits of the grid in "units" (meters) */
106  float x_min, x_max, y_min, y_max;
107  /** Cell size, i.e. resolution of the grid map. */
108  float resolution;
109 
110  /** Auxiliary variables to speed up the computation of observation
111  * likelihood values for LF method among others, at a high cost in memory
112  * (see TLikelihoodOptions::enableLikelihoodCache). */
113  std::vector<double> precomputedLikelihood;
115 
116  /** Used for Voronoi calculation.Same struct as "map", but contains a "0" if
117  * not a basis point. */
119 
120  /** Used to store the Voronoi diagram.
121  * Contains the distance of each cell to its closer obstacles
122  * in 1/100th distance units (i.e. in centimeters), or 0 if not into the
123  * Voronoi diagram */
125 
126  /** True upon construction; used by isEmpty() */
128 
129  /** See base class */
130  virtual void OnPostSuccesfulInsertObs(
131  const mrpt::obs::CObservation*) override;
132 
133  /** The free-cells threshold used to compute the Voronoi diagram. */
135 
136  /** Entropy computation internal function: */
137  static double H(double p);
138  /** Internally used to speed-up entropy calculation */
139  static std::vector<float> entropyTable;
140 
141  /** Change the contents [0,1] of a cell, given its index */
142  inline void setCell_nocheck(int x, int y, float value)
143  {
144  map[x + y * size_x] = p2l(value);
145  }
146 
147  /** Read the real valued [0,1] contents of a cell, given its index */
148  inline float getCell_nocheck(int x, int y) const
149  {
150  return l2p(map[x + y * size_x]);
151  }
152  /** Changes a cell by its absolute index (Do not use it normally) */
153  inline void setRawCell(unsigned int cellIndex, cellType b)
154  {
155  if (cellIndex < size_x * size_y) map[cellIndex] = b;
156  }
157 
158  /** One of the methods that can be selected for implementing
159  * "computeObservationLikelihood" (This method is the Range-Scan Likelihood
160  * Consensus for gridmaps, see the ICRA2007 paper by Blanco et al.) */
162  const mrpt::obs::CObservation* obs,
163  const mrpt::poses::CPose2D& takenFrom);
164  /** One of the methods that can be selected for implementing
165  * "computeObservationLikelihood". TODO: This method is described in.... */
167  const mrpt::obs::CObservation* obs,
168  const mrpt::poses::CPose2D& takenFrom);
169  /** One of the methods that can be selected for implementing
170  * "computeObservationLikelihood" */
172  const mrpt::obs::CObservation* obs,
173  const mrpt::poses::CPose2D& takenFrom);
174  /** One of the methods that can be selected for implementing
175  * "computeObservationLikelihood" */
177  const mrpt::obs::CObservation* obs,
178  const mrpt::poses::CPose2D& takenFrom);
179  /** One of the methods that can be selected for implementing
180  * "computeObservationLikelihood" */
182  const mrpt::obs::CObservation* obs,
183  const mrpt::poses::CPose2D& takenFrom);
184  /** One of the methods that can be selected for implementing
185  * "computeObservationLikelihood".*/
187  const mrpt::obs::CObservation* obs,
188  const mrpt::poses::CPose2D& takenFrom);
189  /** One of the methods that can be selected for implementing
190  * "computeObservationLikelihood". */
192  const mrpt::obs::CObservation* obs,
193  const mrpt::poses::CPose2D& takenFrom);
194 
195  /** Clear the map: It set all cells to their default occupancy value (0.5),
196  * without changing the resolution (the grid extension is reset to the
197  * default values). */
198  virtual void internal_clear() override;
199 
200  /** Insert the observation information into this map.
201  *
202  * \param obs The observation
203  * \param robotPose The 3D pose of the robot mobile base in the map
204  * reference system, or nullptr (default) if you want to use
205  * CPose2D(0,0,deg)
206  *
207  * After successfull execution, "lastObservationInsertionInfo" is updated.
208  *
209  * \sa insertionOptions, CObservation::insertObservationInto
210  */
211  virtual bool internal_insertObservation(
212  const mrpt::obs::CObservation* obs,
213  const mrpt::poses::CPose3D* robotPose = nullptr) override;
214 
215  public:
216  /** Read-only access to the raw cell contents (cells are in log-odd units)
217  */
218  const std::vector<cellType>& getRawMap() const { return this->map; }
219  /** Performs the Bayesian fusion of a new observation of a cell \sa
220  * updateInfoChangeOnly, updateCell_fast_occupied, updateCell_fast_free */
221  void updateCell(int x, int y, float v);
222 
223  /** An internal structure for storing data related to counting the new
224  * information apported by some observation */
226  {
228  bool enabled_ = false, double I_change_ = 0, int cellsUpdated_ = 0)
229  : enabled(enabled_),
230  I_change(I_change_),
231  cellsUpdated(cellsUpdated_),
232  laserRaysSkip(1)
233  {
234  }
235  /** If set to false (default), this struct is not used. Set to true only
236  * when measuring the info of an observation. */
237  bool enabled;
238  /** The cummulative change in Information: This is updated only from the
239  * "updateCell" method. */
240  double I_change;
241  /** The cummulative updated cells count: This is updated only from the
242  * "updateCell" method. */
244  /** In this mode, some laser rays can be skips to speep-up */
247 
248  /** Fills all the cells with a default value. */
249  void fill(float default_value = 0.5f);
250 
251  /** Constructor */
253  float min_x = -20.0f, float max_x = 20.0f, float min_y = -20.0f,
254  float max_y = 20.0f, float resolution = 0.05f);
255  /** Destructor */
256  virtual ~COccupancyGridMap2D();
257 
258  /** Change the size of gridmap, erasing all its previous contents.
259  * \param x_min The "x" coordinates of left most side of grid.
260  * \param x_max The "x" coordinates of right most side of grid.
261  * \param y_min The "y" coordinates of top most side of grid.
262  * \param y_max The "y" coordinates of bottom most side of grid.
263  * \param resolution The new size of cells.
264  * \param default_value The value of cells, tipically 0.5.
265  * \sa ResizeGrid
266  */
267  void setSize(
268  float x_min, float x_max, float y_min, float y_max, float resolution,
269  float default_value = 0.5f);
270 
271  /** Change the size of gridmap, maintaining previous contents.
272  * \param new_x_min The "x" coordinates of new left most side of grid.
273  * \param new_x_max The "x" coordinates of new right most side of grid.
274  * \param new_y_min The "y" coordinates of new top most side of grid.
275  * \param new_y_max The "y" coordinates of new bottom most side of grid.
276  * \param new_cells_default_value The value of the new cells, tipically 0.5.
277  * \param additionalMargin If set to true (default), an additional margin of
278  * a few meters will be added to the grid, ONLY if the new coordinates are
279  * larger than current ones.
280  * \sa setSize
281  */
282  void resizeGrid(
283  float new_x_min, float new_x_max, float new_y_min, float new_y_max,
284  float new_cells_default_value = 0.5f,
285  bool additionalMargin = true) noexcept;
286 
287  /** Returns the area of the gridmap, in square meters */
288  inline double getArea() const
289  {
290  return size_x * size_y * mrpt::square(resolution);
291  }
292 
293  /** Returns the horizontal size of grid map in cells count */
294  inline unsigned int getSizeX() const { return size_x; }
295  /** Returns the vertical size of grid map in cells count */
296  inline unsigned int getSizeY() const { return size_y; }
297  /** Returns the "x" coordinate of left side of grid map */
298  inline float getXMin() const { return x_min; }
299  /** Returns the "x" coordinate of right side of grid map */
300  inline float getXMax() const { return x_max; }
301  /** Returns the "y" coordinate of top side of grid map */
302  inline float getYMin() const { return y_min; }
303  /** Returns the "y" coordinate of bottom side of grid map */
304  inline float getYMax() const { return y_max; }
305  /** Returns the resolution of the grid map */
306  inline float getResolution() const { return resolution; }
307  /** Transform a coordinate value into a cell index */
308  inline int x2idx(float x) const
309  {
310  return static_cast<int>((x - x_min) / resolution);
311  }
312  inline int y2idx(float y) const
313  {
314  return static_cast<int>((y - y_min) / resolution);
315  }
316 
317  inline int x2idx(double x) const
318  {
319  return static_cast<int>((x - x_min) / resolution);
320  }
321  inline int y2idx(double y) const
322  {
323  return static_cast<int>((y - y_min) / resolution);
324  }
325 
326  /** Transform a cell index into a coordinate value */
327  inline float idx2x(const size_t cx) const
328  {
329  return x_min + (cx + 0.5f) * resolution;
330  }
331  inline float idx2y(const size_t cy) const
332  {
333  return y_min + (cy + 0.5f) * resolution;
334  }
335 
336  /** Transform a coordinate value into a cell index, using a diferent "x_min"
337  * value */
338  inline int x2idx(float x, float xmin) const
339  {
340  return static_cast<int>((x - xmin) / resolution);
341  }
342  inline int y2idx(float y, float ymin) const
343  {
344  return static_cast<int>((y - ymin) / resolution);
345  }
346 
347  /** Scales an integer representation of the log-odd into a real valued
348  * probability in [0,1], using p=exp(l)/(1+exp(l)) */
349  static inline float l2p(const cellType l)
350  {
351  return get_logodd_lut().l2p(l);
352  }
353  /** Scales an integer representation of the log-odd into a linear scale
354  * [0,255], using p=exp(l)/(1+exp(l)) */
355  static inline uint8_t l2p_255(const cellType l)
356  {
357  return get_logodd_lut().l2p_255(l);
358  }
359  /** Scales a real valued probability in [0,1] to an integer representation
360  * of: log(p)-log(1-p) in the valid range of cellType */
361  static inline cellType p2l(const float p)
362  {
363  return get_logodd_lut().p2l(p);
364  }
365  /** Change the contents [0,1] of a cell, given its index */
366  inline void setCell(int x, int y, float value)
367  {
368  // The x> comparison implicitly holds if x<0
369  if (static_cast<unsigned int>(x) >= size_x ||
370  static_cast<unsigned int>(y) >= size_y)
371  return;
372  else
373  map[x + y * size_x] = p2l(value);
374  }
375 
376  /** Read the real valued [0,1] contents of a cell, given its index */
377  inline float getCell(int x, int y) const
378  {
379  // The x> comparison implicitly holds if x<0
380  if (static_cast<unsigned int>(x) >= size_x ||
381  static_cast<unsigned int>(y) >= size_y)
382  return 0.5f;
383  else
384  return l2p(map[x + y * size_x]);
385  }
386 
387  /** Access to a "row": mainly used for drawing grid as a bitmap efficiently,
388  * do not use it normally */
389  inline cellType* getRow(int cy)
390  {
391  if (cy < 0 || static_cast<unsigned int>(cy) >= size_y)
392  return nullptr;
393  else
394  return &map[0 + cy * size_x];
395  }
396 
397  /** Access to a "row": mainly used for drawing grid as a bitmap efficiently,
398  * do not use it normally */
399  inline const cellType* getRow(int cy) const
400  {
401  if (cy < 0 || static_cast<unsigned int>(cy) >= size_y)
402  return nullptr;
403  else
404  return &map[0 + cy * size_x];
405  }
406 
407  /** Change the contents [0,1] of a cell, given its coordinates */
408  inline void setPos(float x, float y, float value)
409  {
410  setCell(x2idx(x), y2idx(y), value);
411  }
412 
413  /** Read the real valued [0,1] contents of a cell, given its coordinates */
414  inline float getPos(float x, float y) const
415  {
416  return getCell(x2idx(x), y2idx(y));
417  }
418 
419  /** Returns "true" if cell is "static", i.e.if its occupancy is below a
420  * given threshold */
421  inline bool isStaticPos(float x, float y, float threshold = 0.7f) const
422  {
423  return isStaticCell(x2idx(x), y2idx(y), threshold);
424  }
425  inline bool isStaticCell(int cx, int cy, float threshold = 0.7f) const
426  {
427  return (getCell(cx, cy) <= threshold);
428  }
429 
430  /** Change a cell in the "basis" maps.Used for Voronoi calculation */
431  inline void setBasisCell(int x, int y, uint8_t value)
432  {
433  uint8_t* cell = m_basis_map.cellByIndex(x, y);
434 #ifdef _DEBUG
435  ASSERT_ABOVEEQ_(x, 0);
436  ASSERT_ABOVEEQ_(y, 0);
439 #endif
440  *cell = value;
441  }
442 
443  /** Reads a cell in the "basis" maps.Used for Voronoi calculation */
444  inline unsigned char getBasisCell(int x, int y) const
445  {
446  const uint8_t* cell = m_basis_map.cellByIndex(x, y);
447 #ifdef _DEBUG
448  ASSERT_ABOVEEQ_(x, 0);
449  ASSERT_ABOVEEQ_(y, 0);
452 #endif
453  return *cell;
454  }
455 
456  /** copy the gridmap contents, but not all the options, from another map
457  * instance */
458  void copyMapContentFrom(const COccupancyGridMap2D& otherMap);
459 
460  /** Used for returning entropy related information \sa computeEntropy */
462  {
463  /** The target variable for absolute entropy, computed
464  * as:<br><center>H(map)=Sum<sub>x,y</sub>{ -p(x,y)*ln(p(x,y))
465  * -(1-p(x,y))*ln(1-p(x,y)) }</center><br><br> */
466  double H{0};
467  /** The target variable for absolute "information", defining I(x) = 1 -
468  * H(x) */
469  double I{0};
470  /** The target variable for mean entropy, defined as entropy per cell:
471  * mean_H(map) = H(map) / (cells) */
472  double mean_H{0};
473  /** The target variable for mean information, defined as information per
474  * cell: mean_I(map) = I(map) / (cells) */
475  double mean_I{0};
476  /** The target variable for the area of cells with information, i.e.
477  * p(x)!=0.5 */
479  /** The mapped area in cells. */
480  unsigned long effectiveMappedCells{0};
481  };
482 
483  /** With this struct options are provided to the observation insertion
484  * process.
485  * \sa CObservation::insertIntoGridMap */
487  {
488  public:
489  /** Initilization of default parameters
490  */
492 
493  /** This method load the options from a ".ini" file.
494  * Only those parameters found in the given "section" and having
495  * the same name that the variable are loaded. Those not found in
496  * the file will stay with their previous values (usually the default
497  * values loaded at initialization). An example of an ".ini" file:
498  * \code
499  * [section]
500  * resolution=0.10 ; blah blah...
501  * modeSelection=1 ; 0=blah, 1=blah,...
502  * \endcode
503  */
504  void loadFromConfigFile(
506  const std::string& section) override; // See base docs
507  void dumpToTextStream(
508  std::ostream& out) const override; // See base docs
509 
510  /** The altitude (z-axis) of 2D scans (within a 0.01m tolerance) for
511  * they to be inserted in this map! */
512  float mapAltitude;
513  /** The parameter "mapAltitude" has effect while inserting observations
514  * in the grid only if this is true. */
516  /** The largest distance at which cells will be updated (Default 15
517  * meters) */
519  /** A value in the range [0.5,1] used for updating cell with a bayesian
520  * approach (default 0.8) */
522  /** A value in the range [0.5,1] for updating a free cell. (default=0
523  * means use the same than maxOccupancyUpdateCertainty) */
525  /** Like maxFreenessUpdateCertainty, but for invalid ranges (no echo).
526  * (default=0 means same than maxOccupancyUpdateCertainty)*/
528  /** If set to true (default), invalid range values (no echo rays) as
529  * consider as free space until "maxOccupancyUpdateCertainty", but ONLY
530  * when the previous and next rays are also an invalid ray. */
532  /** Specify the decimation of the range scan (default=1 : take all the
533  * range values!) */
535  /** The tolerance in rads in pitch & roll for a laser scan to be
536  * considered horizontal, then processed by calls to this class
537  * (default=0). */
539  /** Gaussian sigma of the filter used in getAsImageFiltered (for
540  * features detection) (Default=1) (0:Disabled) */
542  /** Size of the Median filter used in getAsImageFiltered (for features
543  * detection) (Default=3) (0:Disabled) */
545  /** Enabled: Rays widen with distance to approximate the real behavior
546  * of lasers, disabled: insert rays as simple lines (Default=false) */
548  };
549 
550  /** With this struct options are provided to the observation insertion
551  * process \sa CObservation::insertIntoGridMap */
553 
554  /** The type for selecting a likelihood computation method */
556  {
564  // Remember: Update TEnumType below if new values are added here!
565  };
566 
567  /** With this struct options are provided to the observation likelihood
568  * computation process */
570  {
571  public:
572  /** Initilization of default parameters */
574 
575  /** This method load the options from a ".ini" file.
576  * Only those parameters found in the given "section" and having
577  * the same name that the variable are loaded. Those not found in
578  * the file will stay with their previous values (usually the default
579  * values loaded at initialization). An example of an ".ini" file:
580  * \code
581  * [section]
582  * resolution=0.10 ; blah blah...
583  * modeSelection=1 ; 0=blah, 1=blah,...
584  * \endcode
585  */
586  void loadFromConfigFile(
588  const std::string& section) override; // See base docs
589  void dumpToTextStream(
590  std::ostream& out) const override; // See base docs
591 
592  /** The selected method to compute an observation likelihood */
594  /** [LikelihoodField] The laser range "sigma" used in computations;
595  * Default value = 0.35 */
596  float LF_stdHit;
597  /** [LikelihoodField] */
599  /** [LikelihoodField] The max. range of the sensor (Default= 81 m) */
600  float LF_maxRange;
601  /** [LikelihoodField] The decimation of the points in a scan, default=1
602  * == no decimation */
604  /** [LikelihoodField] The max. distance for searching correspondences
605  * around each sensed point */
607  /** [LikelihoodField] (Default:false) Use `exp(dist^2/std^2)` instead of
608  * `exp(dist^2/std^2)` */
610  /** [LikelihoodField] Set this to "true" ot use an alternative method,
611  * where the likelihood of the whole range scan is computed by
612  * "averaging" of individual ranges, instead of by the "product". */
614  /** [MI] The exponent in the MI likelihood computation. Default value =
615  * 5 */
616  float MI_exponent;
617  /** [MI] The scan rays decimation: at every N rays, one will be used to
618  * compute the MI */
620  /** [MI] The ratio for the max. distance used in the MI computation and
621  * in the insertion of scans, e.g. if set to 2.0 the MI will use twice
622  * the distance that the update distance. */
624  /** [rayTracing] If true (default), the rayTracing method will ignore
625  * measured ranges shorter than the simulated ones. */
627  /** [rayTracing] One out of "rayTracing_decimation" rays will be
628  * simulated and compared only: set to 1 to use all the sensed ranges.
629  */
631  /** [rayTracing] The laser range sigma. */
633  /** [Consensus] The down-sample ratio of ranges (default=1, consider all
634  * the ranges) */
636  /** [Consensus] The power factor for the likelihood (default=5) */
638  /** [OWA] The sequence of weights to be multiplied to of the ordered
639  * list of likelihood values (first one is the largest); the size of
640  * this vector determines the number of highest likelihood values to
641  * fuse. */
642  std::vector<float> OWA_weights;
643 
644  /** Enables the usage of a cache of likelihood values (for LF methods),
645  * if set to true (default=false). */
648 
649  /** Auxiliary private class. */
650  using TPairLikelihoodIndex = std::pair<double, mrpt::math::TPoint2D>;
651 
652  /** Some members of this struct will contain intermediate or output data
653  * after calling "computeObservationLikelihood" for some likelihood
654  * functions */
656  {
657  public:
659  /** [OWA method] This will contain the ascending-ordered list of
660  * pairs:(likelihood values, 2D point in map coordinates). */
661  std::vector<TPairLikelihoodIndex> OWA_pairList;
662  /** [OWA method] This will contain the ascending-ordered list of
663  * likelihood values for individual range measurements in the scan. */
664  std::vector<double> OWA_individualLikValues;
666 
667  /** Performs a downsampling of the gridmap, by a given factor:
668  * resolution/=ratio */
669  void subSample(int downRatio);
670 
671  /** Computes the entropy and related values of this grid map.
672  * The entropy is computed as the summed entropy of each cell, taking them
673  * as discrete random variables following a Bernoulli distribution:
674  * \param info The output information is returned here */
675  void computeEntropy(TEntropyInfo& info) const;
676 
677  /** @name Voronoi methods
678  @{ */
679 
680  /** Build the Voronoi diagram of the grid map.
681  * \param threshold The threshold for binarizing the map.
682  * \param robot_size Size in "units" (meters) of robot, approx.
683  * \param x1 Left coordinate of area to be computed. Default, entire map.
684  * \param x2 Right coordinate of area to be computed. Default, entire map.
685  * \param y1 Top coordinate of area to be computed. Default, entire map.
686  * \param y2 Bottom coordinate of area to be computed. Default, entire map.
687  * \sa findCriticalPoints
688  */
689  void buildVoronoiDiagram(
690  float threshold, float robot_size, int x1 = 0, int x2 = 0, int y1 = 0,
691  int y2 = 0);
692 
693  /** Reads a the clearance of a cell (in centimeters), after building the
694  * Voronoi diagram with \a buildVoronoiDiagram */
695  inline uint16_t getVoroniClearance(int cx, int cy) const
696  {
697 #ifdef _DEBUG
698  ASSERT_ABOVEEQ_(cx, 0);
699  ASSERT_ABOVEEQ_(cy, 0);
702 #endif
703  const uint16_t* cell = m_voronoi_diagram.cellByIndex(cx, cy);
704  return *cell;
705  }
706 
707  protected:
708  /** Used to set the clearance of a cell, while building the Voronoi diagram.
709  */
710  inline void setVoroniClearance(int cx, int cy, uint16_t dist)
711  {
712  uint16_t* cell = m_voronoi_diagram.cellByIndex(cx, cy);
713 #ifdef _DEBUG
714  ASSERT_ABOVEEQ_(cx, 0);
715  ASSERT_ABOVEEQ_(cy, 0);
718 #endif
719  *cell = dist;
720  }
721 
722  public:
723  /** Return the auxiliary "basis" map built while building the Voronoi
724  * diagram \sa buildVoronoiDiagram */
726  {
727  return m_basis_map;
728  }
729 
730  /** Return the Voronoi diagram; each cell contains the distance to its
731  * closer obstacle, or 0 if not part of the Voronoi diagram \sa
732  * buildVoronoiDiagram */
734  const
735  {
736  return m_voronoi_diagram;
737  }
738 
739  /** Builds a list with the critical points from Voronoi diagram, which must
740  * must be built before calling this method.
741  * \param filter_distance The minimum distance between two critical points.
742  * \sa buildVoronoiDiagram
743  */
744  void findCriticalPoints(float filter_distance);
745 
746  /** @} */ // End of Voronoi methods
747 
748  /** Compute the clearance of a given cell, and returns its two first
749  * basis (closest obstacle) points.Used to build Voronoi and critical
750  * points.
751  * \return The clearance of the cell, in 1/100 of "cell".
752  * \param cx The cell index
753  * \param cy The cell index
754  * \param basis_x Target buffer for coordinates of basis, having a size of
755  * two "ints".
756  * \param basis_y Target buffer for coordinates of basis, having a size of
757  * two "ints".
758  * \param nBasis The number of found basis: Can be 0,1 or 2.
759  * \param GetContourPoint If "true" the basis are not returned, but the
760  * closest free cells.Default at false.
761  * \sa Build_VoronoiDiagram
762  */
763  int computeClearance(
764  int cx, int cy, int* basis_x, int* basis_y, int* nBasis,
765  bool GetContourPoint = false) const;
766 
767  /** An alternative method for computing the clearance of a given location
768  * (in meters).
769  * \return The clearance (distance to closest OCCUPIED cell), in meters.
770  */
771  float computeClearance(float x, float y, float maxSearchDistance) const;
772 
773  /** Compute the 'cost' of traversing a segment of the map according to the
774  * occupancy of traversed cells.
775  * \return This returns '1-mean(traversed cells occupancy)', i.e. 0.5 for
776  * unknown cells, 1 for a free path.
777  */
778  float computePathCost(float x1, float y1, float x2, float y2) const;
779 
780  /** \name Sensor simulators
781  @{ */
782 
783  /** Simulates a laser range scan into the current grid map.
784  * The simulated scan is stored in a CObservation2DRangeScan object, which
785  *is also used
786  * to pass some parameters: all previously stored characteristics (as
787  *aperture,...) are
788  * taken into account for simulation. Only a few more parameters are
789  *needed. Additive gaussian noise can be optionally added to the simulated
790  *scan.
791  * \param inout_Scan [IN/OUT] This must be filled with desired parameters
792  *before calling, and will contain the scan samples on return.
793  * \param robotPose [IN] The robot pose in this map coordinates. Recall that
794  *sensor pose relative to this robot pose must be specified in the
795  *observation object.
796  * \param threshold [IN] The minimum occupancy threshold to consider a cell
797  *to be occupied (Default: 0.5f)
798  * \param N [IN] The count of range scan "rays", by default to 361.
799  * \param noiseStd [IN] The standard deviation of measurement noise. If not
800  *desired, set to 0.
801  * \param decimation [IN] The rays that will be simulated are at indexes: 0,
802  *D, 2D, 3D, ... Default is D=1
803  * \param angleNoiseStd [IN] The sigma of an optional Gaussian noise added
804  *to the angles at which ranges are measured (in radians).
805  *
806  * \sa laserScanSimulatorWithUncertainty(), sonarSimulator(),
807  *COccupancyGridMap2D::RAYTRACE_STEP_SIZE_IN_CELL_UNITS
808  */
809  void laserScanSimulator(
811  const mrpt::poses::CPose2D& robotPose, float threshold = 0.6f,
812  size_t N = 361, float noiseStd = 0, unsigned int decimation = 1,
813  float angleNoiseStd = mrpt::DEG2RAD(.0)) const;
814 
815  /** Simulates the observations of a sonar rig into the current grid map.
816  * The simulated ranges are stored in a CObservationRange object, which is
817  * also used
818  * to pass in some needed parameters, as the poses of the sonar sensors
819  * onto the mobile robot.
820  * \param inout_observation [IN/OUT] This must be filled with desired
821  * parameters before calling, and will contain the simulated ranges on
822  * return.
823  * \param robotPose [IN] The robot pose in this map coordinates. Recall that
824  * sensor pose relative to this robot pose must be specified in the
825  * observation object.
826  * \param threshold [IN] The minimum occupancy threshold to consider a cell
827  * to be occupied (Default: 0.5f)
828  * \param rangeNoiseStd [IN] The standard deviation of measurement noise. If
829  * not desired, set to 0.
830  * \param angleNoiseStd [IN] The sigma of an optional Gaussian noise added
831  * to the angles at which ranges are measured (in radians).
832  *
833  * \sa laserScanSimulator(),
834  * COccupancyGridMap2D::RAYTRACE_STEP_SIZE_IN_CELL_UNITS
835  */
836  void sonarSimulator(
837  mrpt::obs::CObservationRange& inout_observation,
838  const mrpt::poses::CPose2D& robotPose, float threshold = 0.5f,
839  float rangeNoiseStd = 0.f,
840  float angleNoiseStd = mrpt::DEG2RAD(0.f)) const;
841 
842  /** Simulate just one "ray" in the grid map. This method is used internally
843  * to sonarSimulator and laserScanSimulator. \sa
844  * COccupancyGridMap2D::RAYTRACE_STEP_SIZE_IN_CELL_UNITS */
845  void simulateScanRay(
846  const double x, const double y, const double angle_direction,
847  float& out_range, bool& out_valid, const double max_range_meters,
848  const float threshold_free = 0.4f, const double noiseStd = .0,
849  const double angleNoiseStd = .0) const;
850 
851  /** Methods for TLaserSimulUncertaintyParams in
852  * laserScanSimulatorWithUncertainty() */
854  {
855  /** Performs an unscented transform */
857  /** Montecarlo-based estimation */
859  };
860 
861  /** Input params for laserScanSimulatorWithUncertainty() */
863  {
864  /** (Default: sumMonteCarlo) Select the method to do the uncertainty
865  * propagation */
867  /** @name Parameters for each uncertainty method
868  @{ */
869  /** [sumUnscented] UT parameters. Defaults: alpha=0.99, kappa=0,
870  * betta=2.0 */
872  /** [sumMonteCarlo] MonteCarlo parameter: number of samples (Default:
873  * 10) */
874  size_t MC_samples;
875  /** @} */
876 
877  /** @name Generic parameters for all methods
878  @{ */
879  /** The robot pose Gaussian, in map coordinates. Recall that sensor pose
880  * relative to this robot pose must be specified in the observation
881  * object */
883  /** (Default: M_PI) The "aperture" or field-of-view of the range finder,
884  * in radians (typically M_PI = 180 degrees). */
885  float aperture;
886  /** (Default: true) The scanning direction: true=counterclockwise;
887  * false=clockwise */
889  /** (Default: 80) The maximum range allowed by the device, in meters
890  * (e.g. 80m, 50m,...) */
891  float maxRange;
892  /** (Default: at origin) The 6D pose of the sensor on the robot at the
893  * moment of starting the scan. */
895  size_t nRays;
896  /** (Default: 0) The standard deviation of measurement noise. If not
897  * desired, set to 0 */
899  /** (Default: 0) The sigma of an optional Gaussian noise added to the
900  * angles at which ranges are measured (in radians) */
902  /** (Default: 1) The rays that will be simulated are at indexes: 0, D,
903  * 2D, 3D,... */
904  unsigned int decimation;
905  /** (Default: 0.6f) The minimum occupancy threshold to consider a cell
906  * to be occupied */
907  float threshold;
908  /** @} */
909 
911  };
912 
913  /** Output params for laserScanSimulatorWithUncertainty() */
915  {
916  /** The scan + its uncertainty */
918 
920  };
921 
922  /** Like laserScanSimulatorWithUncertainty() (see it for a discussion of
923  * most parameters) but taking into account
924  * the robot pose uncertainty and generating a vector of predicted
925  * variances for each ray.
926  * Range uncertainty includes both, sensor noise and large non-linear
927  * effects caused by borders and discontinuities in the environment
928  * as seen from different robot poses.
929  *
930  * \param in_params [IN] Input settings. See TLaserSimulUncertaintyParams
931  * \param in_params [OUT] Output range + uncertainty.
932  *
933  * \sa laserScanSimulator(),
934  * COccupancyGridMap2D::RAYTRACE_STEP_SIZE_IN_CELL_UNITS
935  */
937  const TLaserSimulUncertaintyParams& in_params,
938  TLaserSimulUncertaintyResult& out_results) const;
939 
940  /** @} */
941 
942  /** Computes the likelihood [0,1] of a set of points, given the current grid
943  * map as reference.
944  * \param pm The points map
945  * \param relativePose The relative pose of the points map in this map's
946  * coordinates, or nullptr for (0,0,0).
947  * See "likelihoodOptions" for configuration parameters.
948  */
950  const CPointsMap* pm,
951  const mrpt::poses::CPose2D* relativePose = nullptr);
952 
953  /** Computes the likelihood [0,1] of a set of points, given the current grid
954  * map as reference.
955  * \param pm The points map
956  * \param relativePose The relative pose of the points map in this map's
957  * coordinates, or nullptr for (0,0,0).
958  * See "likelihoodOptions" for configuration parameters.
959  */
961  const CPointsMap* pm,
962  const mrpt::poses::CPose2D* relativePose = nullptr);
963 
964  /** Saves the gridmap as a graphical file (BMP,PNG,...).
965  * The format will be derived from the file extension (see
966  * CImage::saveToFile )
967  * \return False on any error.
968  */
969  bool saveAsBitmapFile(const std::string& file) const;
970 
971  /** Saves a composite image with two gridmaps and lines representing a set
972  * of correspondences between them.
973  * \sa saveAsEMFTwoMapsWithCorrespondences
974  * \return False on any error.
975  */
977  const std::string& fileName, const COccupancyGridMap2D* m1,
978  const COccupancyGridMap2D* m2,
979  const mrpt::tfest::TMatchingPairList& corrs);
980 
981  /** Saves a composite image with two gridmaps and numbers for the
982  * correspondences between them.
983  * \sa saveAsBitmapTwoMapsWithCorrespondences
984  * \return False on any error.
985  */
987  const std::string& fileName, const COccupancyGridMap2D* m1,
988  const COccupancyGridMap2D* m2,
989  const mrpt::tfest::TMatchingPairList& corrs);
990 
991  /** Saves the gridmap as a graphical bitmap file, 8 bit gray scale, 1 pixel
992  * is 1 cell, and with an overlay of landmarks.
993  * \note The template parameter CLANDMARKSMAP is assumed to be
994  * mrpt::maps::CLandmarksMap normally.
995  * \return False on any error.
996  */
997  template <class CLANDMARKSMAP>
999  const std::string& file, const CLANDMARKSMAP* landmarks,
1000  bool addTextLabels = false,
1001  const mrpt::img::TColor& marks_color =
1002  mrpt::img::TColor(0, 0, 255)) const
1003  {
1004  MRPT_START
1005  mrpt::img::CImage img(1, 1, 3);
1006  getAsImageFiltered(img, false, true); // in RGB
1007  const bool topleft = img.isOriginTopLeft();
1008  for (unsigned int i = 0; i < landmarks->landmarks.size(); i++)
1009  {
1010  const typename CLANDMARKSMAP::landmark_type* lm =
1011  landmarks->landmarks.get(i);
1012  int px = x2idx(lm->pose_mean.x);
1013  int py = topleft ? size_y - 1 - y2idx(lm->pose_mean.y)
1014  : y2idx(lm->pose_mean.y);
1015  img.rectangle(px - 7, (py + 7), px + 7, (py - 7), marks_color);
1016  img.rectangle(px - 6, (py + 6), px + 6, (py - 6), marks_color);
1017  if (addTextLabels)
1018  img.textOut(
1019  px, py - 8, format("%u", i), mrpt::img::TColor::black());
1020  }
1021  return img.saveToFile(file.c_str());
1022  MRPT_END
1023  }
1024 
1025  /** Returns the grid as a 8-bit graylevel image, where each pixel is a cell
1026  * (output image is RGB only if forceRGB is true)
1027  * If "tricolor" is true, only three gray levels will appear in the image:
1028  * gray for unobserved cells, and black/white for occupied/empty cells
1029  * respectively.
1030  * \sa getAsImageFiltered
1031  */
1032  void getAsImage(
1033  mrpt::img::CImage& img, bool verticalFlip = false,
1034  bool forceRGB = false, bool tricolor = false) const;
1035 
1036  /** Returns the grid as a 8-bit graylevel image, where each pixel is a cell
1037  * (output image is RGB only if forceRGB is true) - This method filters the
1038  * image for easy feature detection
1039  * If "tricolor" is true, only three gray levels will appear in the image:
1040  * gray for unobserved cells, and black/white for occupied/empty cells
1041  * respectively.
1042  * \sa getAsImage
1043  */
1044  void getAsImageFiltered(
1045  img::CImage& img, bool verticalFlip = false,
1046  bool forceRGB = false) const;
1047 
1048  /** Returns a 3D plane with its texture being the occupancy grid and
1049  * transparency proportional to "uncertainty" (i.e. a value of 0.5 is fully
1050  * transparent)
1051  */
1052  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
1053 
1054  /** Get a point cloud with all (border) occupied cells as points */
1055  void getAsPointCloud(
1057  const float occup_threshold = 0.5f) const;
1058 
1059  /** Returns true upon map construction or after calling clear(), the return
1060  * changes to false upon successful insertObservation() or any other
1061  * method to load data in the map.
1062  */
1063  bool isEmpty() const override;
1064 
1065  /** Load the gridmap from a image in a file (the format can be any supported
1066  * by CImage::loadFromFile).
1067  * \param file The file to be loaded.
1068  * \param resolution The size of a pixel (cell), in meters. Recall cells are
1069  * always squared, so just a dimension is needed.
1070  * \param xCentralPixel The `x` coordinate (0=first, increases <b>left to
1071  * right</b> on the image) for the pixel which will be taken at coordinates
1072  * origin (0,0). (Default: the center of the image)
1073  * \param yCentralPixel The `y` coordinate (0=first, increases <b>BOTTOM
1074  * upwards</b> on the image) for the pixel which will be taken at
1075  * coordinates origin (0,0). (Default: the center of the image)
1076  * \return False on any error.
1077  * \sa loadFromBitmap
1078  */
1079  bool loadFromBitmapFile(
1080  const std::string& file, float resolution, float xCentralPixel = -1,
1081  float yCentralPixel = -1);
1082 
1083  /** Load the gridmap from a image in a file (the format can be any supported
1084  * by CImage::loadFromFile).
1085  * See loadFromBitmapFile() for the meaning of parameters */
1086  bool loadFromBitmap(
1087  const mrpt::img::CImage& img, float resolution,
1088  float xCentralPixel = -1, float yCentralPixel = -1);
1089 
1090  /** See the base class for more details: In this class it is implemented as
1091  * correspondences of the passed points map to occupied cells.
1092  * NOTICE: That the "z" dimension is ignored in the points. Clip the points
1093  * as appropiated if needed before calling this method.
1094  *
1095  * \sa computeMatching3DWith
1096  */
1097  virtual void determineMatching2D(
1098  const mrpt::maps::CMetricMap* otherMap,
1099  const mrpt::poses::CPose2D& otherMapPose,
1100  mrpt::tfest::TMatchingPairList& correspondences,
1101  const TMatchingParams& params,
1102  TMatchingExtraResults& extraResults) const override;
1103 
1104  /** See docs in base class: in this class this always returns 0 */
1105  float compute3DMatchingRatio(
1106  const mrpt::maps::CMetricMap* otherMap,
1107  const mrpt::poses::CPose3D& otherMapPose,
1108  const TMatchingRatioParams& params) const override;
1109 
1110  /** This virtual method saves the map to a file "filNamePrefix"+<
1111  * some_file_extension >, as an image or in any other applicable way (Notice
1112  * that other methods to save the map may be implemented in classes
1113  * implementing this virtual interface). */
1115  const std::string& filNamePrefix) const override;
1116 
1117  /** The structure used to store the set of Voronoi diagram
1118  * critical points.
1119  * \sa findCriticalPoints
1120  */
1122  {
1124  : x(),
1125  y(),
1126  clearance(),
1127  x_basis1(),
1128  y_basis1(),
1129  x_basis2(),
1130  y_basis2()
1131  {
1132  }
1133 
1134  /** The coordinates of critical point. */
1135  std::vector<int> x, y;
1136  /** The clearance of critical points, in 1/100 of cells. */
1137  std::vector<int> clearance;
1138  /** Their two first basis points coordinates. */
1139  std::vector<int> x_basis1, y_basis1, x_basis2, y_basis2;
1141 
1142  private:
1143  // See docs in base class
1145  const mrpt::obs::CObservation* obs,
1146  const mrpt::poses::CPose3D& takenFrom) override;
1147  // See docs in base class
1149  const mrpt::obs::CObservation* obs) const override;
1150 
1151  /** Returns a byte with the occupancy of the 8 sorrounding cells.
1152  * \param cx The cell index
1153  * \param cy The cell index
1154  * \sa direction2idx
1155  */
1156  inline unsigned char GetNeighborhood(int cx, int cy) const;
1157 
1158  /** Used to store the 8 possible movements from a cell to the
1159  * sorrounding ones.Filled in the constructor.
1160  * \sa direction2idx
1161  */
1163 
1164  /** Returns the index [0,7] of the given movement, or
1165  * -1 if invalid one.
1166  * \sa direccion_vecino_x,direccion_vecino_y,GetNeighborhood
1167  */
1168  int direction2idx(int dx, int dy);
1169 
1171  /** See COccupancyGridMap2D::COccupancyGridMap2D */
1172  float min_x, max_x, min_y, max_y, resolution;
1173  /** Observations insertion options */
1175  /** Probabilistic observation likelihood options */
1178 };
1179 
1180 bool operator<(
1183 }
1193 
1194 
mrpt::poses::CPosePDFGaussian robotPose
The robot pose Gaussian, in map coordinates.
double computeObservationLikelihood_ConsensusOWA(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
void findCriticalPoints(float filter_distance)
Builds a list with the critical points from Voronoi diagram, which must must be built before calling ...
void laserScanSimulator(mrpt::obs::CObservation2DRangeScan &inout_Scan, const mrpt::poses::CPose2D &robotPose, float threshold=0.6f, size_t N=361, float noiseStd=0, unsigned int decimation=1, float angleNoiseStd=mrpt::DEG2RAD(.0)) const
Simulates a laser range scan into the current grid map.
float getXMax() const
Returns the "x" coordinate of right side of grid map.
float consensus_pow
[Consensus] The power factor for the likelihood (default=5)
double computeObservationLikelihood_Consensus(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood" (This method ...
COccupancyGridMap2D(float min_x=-20.0f, float max_x=20.0f, float min_y=-20.0f, float max_y=20.0f, float resolution=0.05f)
Constructor.
void setCell(int x, int y, float value)
Change the contents [0,1] of a cell, given its index.
Parameters for CMetricMap::compute3DMatchingRatio()
double getArea() const
Returns the area of the gridmap, in square meters.
double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
float getYMin() const
Returns the "y" coordinate of top side of grid map.
int32_t consensus_takeEachRange
[Consensus] The down-sample ratio of ranges (default=1, consider all the ranges)
uint16_t getVoroniClearance(int cx, int cy) const
Reads a the clearance of a cell (in centimeters), after building the Voronoi diagram with buildVorono...
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters.
#define MRPT_START
Definition: exceptions.h:262
float threshold
(Default: 0.6f) The minimum occupancy threshold to consider a cell to be occupied ...
bool wideningBeamsWithDistance
Enabled: Rays widen with distance to approximate the real behavior of lasers, disabled: insert rays a...
unsigned __int16 uint16_t
Definition: rptypes.h:44
int laserRaysSkip
In this mode, some laser rays can be skips to speep-up.
float MI_exponent
[MI] The exponent in the MI likelihood computation.
double computeObservationLikelihood_rayTracing(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
std::vector< int > x
The coordinates of critical point.
float getResolution() const
Returns the resolution of the grid map.
bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation *obs) const override
Returns true if this map is able to compute a sensible likelihood function for this observation (i...
With this struct options are provided to the observation insertion process.
A 2D range scan plus an uncertainty model for each range.
mrpt::obs::CObservation2DRangeScanWithUncertainty scanWithUncert
The scan + its uncertainty.
float CFD_features_median_size
Size of the Median filter used in getAsImageFiltered (for features detection) (Default=3) (0:Disabled...
std::vector< double > OWA_individualLikValues
[OWA method] This will contain the ascending-ordered list of likelihood values for individual range m...
const std::vector< cellType > & getRawMap() const
Read-only access to the raw cell contents (cells are in log-odd units)
uint16_t decimation
Specify the decimation of the range scan (default=1 : take all the range values!) ...
mrpt::poses::CPose3D sensorPose
(Default: at origin) The 6D pose of the sensor on the robot at the moment of starting the scan...
double effectiveMappedArea
The target variable for the area of cells with information, i.e.
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
std::vector< float > OWA_weights
[OWA] The sequence of weights to be multiplied to of the ordered list of likelihood values (first one...
double DEG2RAD(const double x)
Degrees to radians.
static double H(double p)
Entropy computation internal function:
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
Output params for laserScanSimulatorWithUncertainty()
mrpt::containers::CDynamicGrid< uint16_t > m_voronoi_diagram
Used to store the Voronoi diagram.
int16_t cellType
The type of the map cells:
float rangeNoiseStd
(Default: 0) The standard deviation of measurement noise.
TLikelihoodMethod
The type for selecting a likelihood computation method.
float CFD_features_gaussian_size
Gaussian sigma of the filter used in getAsImageFiltered (for features detection) (Default=1) (0:Disab...
The structure used to store the set of Voronoi diagram critical points.
int y2idx(float y, float ymin) const
void updateCell(int x, int y, float v)
Performs the Bayesian fusion of a new observation of a cell.
mrpt::containers::CDynamicGrid< uint8_t > m_basis_map
Used for Voronoi calculation.Same struct as "map", but contains a "0" if not a basis point...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
struct mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly updateInfoChangeOnly
bool LF_alternateAverageMethod
[LikelihoodField] Set this to "true" ot use an alternative method, where the likelihood of the whole ...
signed char int8_t
Definition: rptypes.h:40
TInsertionOptions insertionOptions
With this struct options are provided to the observation insertion process.
void getAsImageFiltered(img::CImage &img, bool verticalFlip=false, bool forceRGB=false) const
Returns the grid as a 8-bit graylevel image, where each pixel is a cell (output image is RGB only if ...
static bool saveAsEMFTwoMapsWithCorrespondences(const std::string &fileName, const COccupancyGridMap2D *m1, const COccupancyGridMap2D *m2, const mrpt::tfest::TMatchingPairList &corrs)
Saves a composite image with two gridmaps and numbers for the correspondences between them...
static const cellType OCCGRID_CELLTYPE_MAX
bool rightToLeft
(Default: true) The scanning direction: true=counterclockwise; false=clockwise
void buildVoronoiDiagram(float threshold, float robot_size, int x1=0, int x2=0, int y1=0, int y2=0)
Build the Voronoi diagram of the grid map.
void freeMap()
Frees the dynamic memory buffers of map.
std::vector< double > precomputedLikelihood
Auxiliary variables to speed up the computation of observation likelihood values for LF method among ...
float MI_ratio_max_distance
[MI] The ratio for the max.
bool rayTracing_useDistanceFilter
[rayTracing] If true (default), the rayTracing method will ignore measured ranges shorter than the si...
std::vector< cellType > map
Store of cell occupancy values.
static bool saveAsBitmapTwoMapsWithCorrespondences(const std::string &fileName, const COccupancyGridMap2D *m1, const COccupancyGridMap2D *m2, const mrpt::tfest::TMatchingPairList &corrs)
Saves a composite image with two gridmaps and lines representing a set of correspondences between the...
const cellType * getRow(int cy) const
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
const mrpt::containers::CDynamicGrid< uint16_t > & getVoronoiDiagram() const
Return the Voronoi diagram; each cell contains the distance to its closer obstacle, or 0 if not part of the Voronoi diagram.
unsigned char uint8_t
Definition: rptypes.h:41
float LF_stdHit
[LikelihoodField] The laser range "sigma" used in computations; Default value = 0.35
void setRawCell(unsigned int cellIndex, cellType b)
Changes a cell by its absolute index (Do not use it normally)
T square(const T x)
Inline function for the square of a number.
uint32_t LF_decimation
[LikelihoodField] The decimation of the points in a scan, default=1 == no decimation ...
bool enableLikelihoodCache
Enables the usage of a cache of likelihood values (for LF methods), if set to true (default=false)...
float getCell_nocheck(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
bool saveAsBitmapFile(const std::string &file) const
Saves the gridmap as a graphical file (BMP,PNG,...).
static CLogOddsGridMapLUT< cellType > & get_logodd_lut()
Lookup tables for log-odds.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Definition: CPointsMap.h:64
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)) }
MRPT_FILL_ENUM_MEMBER(mrpt::maps::COccupancyGridMap2D, lmMeanInformation)
mrpt::img::CImage CImage
Definition: utils/CImage.h:5
This class allows loading and storing values and vectors of different types from a configuration text...
virtual void OnPostSuccesfulInsertObs(const mrpt::obs::CObservation *) override
See base class.
double computeObservationLikelihood_CellsDifference(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
__int16 int16_t
Definition: rptypes.h:43
float getXMin() const
Returns the "x" coordinate of left side of grid map.
size_t MC_samples
[sumMonteCarlo] MonteCarlo parameter: number of samples (Default: 10)
With this struct options are provided to the observation likelihood computation process.
bool isStaticCell(int cx, int cy, float threshold=0.7f) const
bool isEmpty() const override
Returns true upon map construction or after calling clear(), the return changes to false upon success...
std::pair< double, mrpt::math::TPoint2D > TPairLikelihoodIndex
Auxiliary private class.
GLint GLvoid * img
Definition: glext.h:3763
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
static constexpr TColor black()
Definition: TColor.h:63
std::vector< int > x_basis1
Their two first basis points coordinates.
bool loadFromBitmap(const mrpt::img::CImage &img, float resolution, float xCentralPixel=-1, float yCentralPixel=-1)
Load the gridmap from a image in a file (the format can be any supported by CImage::loadFromFile).
bool loadFromBitmapFile(const std::string &file, float resolution, float xCentralPixel=-1, float yCentralPixel=-1)
Load the gridmap from a image in a file (the format can be any supported by CImage::loadFromFile).
float rayTracing_stdHit
[rayTracing] The laser range sigma.
TLaserSimulUncertaintyMethod
Methods for TLaserSimulUncertaintyParams in laserScanSimulatorWithUncertainty()
void copyMapContentFrom(const COccupancyGridMap2D &otherMap)
copy the gridmap contents, but not all the options, from another map instance
float aperture
(Default: M_PI) The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180...
A list of TMatchingPair.
Definition: TMatchingPair.h:81
double I
The target variable for absolute "information", defining I(x) = 1 - H(x)
GLubyte GLubyte b
Definition: glext.h:6279
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
void subSample(int downRatio)
Performs a downsampling of the gridmap, by a given factor: resolution/=ratio.
TLikelihoodMethod likelihoodMethod
The selected method to compute an observation likelihood.
double I_change
The cummulative change in Information: This is updated only from the "updateCell" method...
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::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...
TUpdateCellsInfoChangeOnly(bool enabled_=false, double I_change_=0, int cellsUpdated_=0)
unsigned char getBasisCell(int x, int y) const
Reads a cell in the "basis" maps.Used for Voronoi calculation.
T * cellByIndex(unsigned int cx, unsigned int cy)
Returns a pointer to the contents of a cell given by its cell indexes, or nullptr if it is out of the...
Definition: CDynamicGrid.h:232
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
size_t getSizeX() const
Returns the horizontal size of grid map in cells count.
Definition: CDynamicGrid.h:252
float maxDistanceInsertion
The largest distance at which cells will be updated (Default 15 meters)
unsigned int decimation
(Default: 1) The rays that will be simulated are at indexes: 0, D, 2D, 3D,...
void sonarSimulator(mrpt::obs::CObservationRange &inout_observation, const mrpt::poses::CPose2D &robotPose, float threshold=0.5f, float rangeNoiseStd=0.f, float angleNoiseStd=mrpt::DEG2RAD(0.f)) const
Simulates the observations of a sonar rig into the current grid map.
#define ASSERT_ABOVEEQ_(__A, __B)
Definition: exceptions.h:183
bool LF_useSquareDist
[LikelihoodField] (Default:false) Use exp(dist^2/std^2) instead of exp(dist^2/std^2) ...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini" file.
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions likelihoodOptions
void setCell_nocheck(int x, int y, float value)
Change the contents [0,1] of a cell, given its index.
double computeLikelihoodField_II(const CPointsMap *pm, const mrpt::poses::CPose2D *relativePose=nullptr)
Computes the likelihood [0,1] of a set of points, given the current grid map as reference.
static const cellType OCCGRID_P2LTABLE_SIZE
void getAsPointCloud(mrpt::maps::CSimplePointsMap &pm, const float occup_threshold=0.5f) const
Get a point cloud with all (border) occupied cells as points.
double mean_H
The target variable for mean entropy, defined as entropy per cell: mean_H(map) = H(map) / (cells) ...
size_t getSizeY() const
Returns the vertical size of grid map in cells count.
Definition: CDynamicGrid.h:254
void laserScanSimulatorWithUncertainty(const TLaserSimulUncertaintyParams &in_params, TLaserSimulUncertaintyResult &out_results) const
Like laserScanSimulatorWithUncertainty() (see it for a discussion of most parameters) but taking into...
bool isStaticPos(float x, float y, float threshold=0.7f) const
Returns "true" if cell is "static", i.e.if its occupancy is below a given threshold.
An internal structure for storing data related to counting the new information apported by some obser...
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
A class for storing an occupancy grid map.
void getAsImage(mrpt::img::CImage &img, bool verticalFlip=false, bool forceRGB=false, bool tricolor=false) const
Returns the grid as a 8-bit graylevel image, where each pixel is a cell (output image is RGB only if ...
float angleNoiseStd
(Default: 0) The sigma of an optional Gaussian noise added to the angles at which ranges are measured...
__int32 int32_t
Definition: rptypes.h:46
int direccion_vecino_x[8]
Used to store the 8 possible movements from a cell to the sorrounding ones.Filled in the constructor...
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 DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void setBasisCell(int x, int y, uint8_t value)
Change a cell in the "basis" maps.Used for Voronoi calculation.
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...
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D plane with its texture being the occupancy grid and transparency proportional to "uncert...
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:54
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:38
int direction2idx(int dx, int dy)
Returns the index [0,7] of the given movement, or -1 if invalid one.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
Input params for laserScanSimulatorWithUncertainty()
void simulateScanRay(const double x, const double y, const double angle_direction, float &out_range, bool &out_valid, const double max_range_meters, const float threshold_free=0.4f, const double noiseStd=.0, const double angleNoiseStd=.0) const
Simulate just one "ray" in the grid map.
cellType * getRow(int cy)
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
int cellsUpdated
The cummulative updated cells count: This is updated only from the "updateCell" method.
const mrpt::containers::CDynamicGrid< uint8_t > & getBasisMap() const
Return the auxiliary "basis" map built while building the Voronoi diagram.
float horizontalTolerance
The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, then processed by calls to this class (default=0).
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
int32_t rayTracing_decimation
[rayTracing] One out of "rayTracing_decimation" rays will be simulated and compared only: set to 1 to...
static std::vector< float > entropyTable
Internally used to speed-up entropy calculation.
float maxFreenessUpdateCertainty
A value in the range [0.5,1] for updating a free cell.
unsigned char GetNeighborhood(int cx, int cy) const
Returns a byte with the occupancy of the 8 sorrounding cells.
#define MRPT_END
Definition: exceptions.h:266
TLaserSimulUncertaintyMethod method
(Default: sumMonteCarlo) Select the method to do the uncertainty propagation
bool m_is_empty
True upon construction; used by isEmpty()
bool useMapAltitude
The parameter "mapAltitude" has effect while inserting observations in the grid only if this is true...
virtual void internal_clear() override
Clear the map: It set all cells to their default occupancy value (0.5), without changing the resoluti...
virtual bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Insert the observation information into this map.
void setVoroniClearance(int cx, int cy, uint16_t dist)
Used to set the clearance of a cell, while building the Voronoi diagram.
uint32_t MI_skip_rays
[MI] The scan rays decimation: at every N rays, one will be used to compute the MI ...
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
float mapAltitude
The altitude (z-axis) of 2D scans (within a 0.01m tolerance) for they to be inserted in this map! ...
float idx2y(const size_t cy) const
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini" file.
float getYMax() const
Returns the "y" coordinate of bottom side of grid map.
struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList CriticalPointsList
static double RAYTRACE_STEP_SIZE_IN_CELL_UNITS
(Default:1.0) Can be set to <1 if a more fine raytracing is needed in sonarSimulator() and laserScanS...
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.
std::vector< TPairLikelihoodIndex > OWA_pairList
[OWA method] This will contain the ascending-ordered list of pairs:(likelihood values, 2D point in map coordinates).
A generic provider of log-odds grid-map maintainance functions.
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.
GLsizei const GLfloat * value
Definition: glext.h:4117
#define ASSERT_BELOWEQ_(__A, __B)
Definition: exceptions.h:177
float maxRange
(Default: 80) The maximum range allowed by the device, in meters (e.g.
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.
float maxOccupancyUpdateCertainty
A value in the range [0.5,1] used for updating cell with a bayesian approach (default 0...
A RGB color - 8bit.
Definition: TColor.h:20
float voroni_free_threshold
The free-cells threshold used to compute the Voronoi diagram.
GLenum GLint x
Definition: glext.h:3538
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...
This class stores any customizable set of metric maps.
unsigned int getSizeY() const
Returns the vertical size of grid map in cells count.
int x2idx(float x, float xmin) const
Transform a coordinate value into a cell index, using a diferent "x_min" value.
class mrpt::maps::COccupancyGridMap2D::TLikelihoodOutput likelihoodOutputs
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
float maxFreenessInvalidRanges
Like maxFreenessUpdateCertainty, but for invalid ranges (no echo).
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.
int computeClearance(int cx, int cy, int *basis_x, int *basis_y, int *nBasis, bool GetContourPoint=false) const
Compute the clearance of a given cell, and returns its two first basis (closest obstacle) points...
double computeObservationLikelihood_likelihoodField_Thrun(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
unsigned __int32 uint32_t
Definition: rptypes.h:47
double computeLikelihoodField_Thrun(const CPointsMap *pm, const mrpt::poses::CPose2D *relativePose=nullptr)
Computes the likelihood [0,1] of a set of points, given the current grid map as reference.
#define MAP_DEFINITION_END(_CLASS_NAME_)
Some members of this struct will contain intermediate or output data after calling "computeObservatio...
Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...
Used for returning entropy related information.
bool considerInvalidRangesAsFreeSpace
If set to true (default), invalid range values (no echo rays) as consider as free space until "maxOcc...
GLfloat GLfloat p
Definition: glext.h:6305
std::vector< int > clearance
The clearance of critical points, in 1/100 of cells.
GLenum const GLfloat * params
Definition: glext.h:3534
int x2idx(float x) const
Transform a coordinate value into a cell index.
static uint8_t l2p_255(const cellType l)
Scales an integer representation of the log-odd into a linear scale [0,255], using p=exp(l)/(1+exp(l)...
void setPos(float x, float y, float value)
Change the contents [0,1] of a cell, given its coordinates.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
double computeObservationLikelihood_likelihoodField_II(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
static float l2p(const cellType l)
Scales an integer representation of the log-odd into a real valued probability in [0...
double computeObservationLikelihood_MI(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
One of the methods that can be selected for implementing "computeObservationLikelihood".
One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
bool saveAsBitmapFileWithLandmarks(const std::string &file, const CLANDMARKSMAP *landmarks, bool addTextLabels=false, const mrpt::img::TColor &marks_color=mrpt::img::TColor(0, 0, 255)) const
Saves the gridmap as a graphical bitmap file, 8 bit gray scale, 1 pixel is 1 cell, and with an overlay of landmarks.
bool enabled
If set to false (default), this struct is not used.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020