Main MRPT website > C++ reference for 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-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 #ifndef COccupancyGridMap2D_H
11 #define COccupancyGridMap2D_H
12 
15 #include <mrpt/utils/CImage.h>
17 #include <mrpt/maps/CMetricMap.h>
21 #include <mrpt/poses/poses_frwds.h>
24 #include <mrpt/obs/obs_frwds.h>
25 #include <mrpt/utils/TEnumType.h>
26 
27 #include <mrpt/config.h>
28 #if ( \
29  !defined(OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS) && \
30  !defined(OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS)) || \
31  (defined(OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS) && \
32  defined(OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS))
33 #error One of OCCUPANCY_GRIDMAP_CELL_SIZE_16BITS or OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS must be defined.
34 #endif
35 
36 namespace mrpt
37 {
38 namespace maps
39 {
40 /** A class for storing an occupancy grid map.
41  * COccupancyGridMap2D is a class for storing a metric map
42  * representation in the form of a probabilistic occupancy
43  * grid map: value of 0 means certainly occupied, 1 means
44  * a certainly empty cell. Initially 0.5 means uncertainty.
45  *
46  * The cells keep the log-odd representation of probabilities instead of the
47  *probabilities themselves.
48  * More details can be found at http://www.mrpt.org/Occupancy_Grids
49  *
50  * The algorithm for updating the grid from a laser scanner can optionally take
51  *into account the progressive widening of the beams, as
52  * described in [this page](http://www.mrpt.org/Occupancy_Grids)
53  *
54  * Some implemented methods are:
55  * - Update of individual cells
56  * - Insertion of observations
57  * - Voronoi diagram and critical points (\a buildVoronoiDiagram)
58  * - Saving and loading from/to a bitmap
59  * - Laser scans simulation for the map contents
60  * - Entropy and information methods (See computeEntropy)
61  *
62  * \ingroup mrpt_maps_grp
63  **/
65 // Inherit from the corresponding specialization of CLogOddsGridMap2D<>:
66 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
67  public CLogOddsGridMap2D<int8_t>
68 #else
69  public CLogOddsGridMap2D<int16_t>
70 #endif
71 {
73  public:
74 /** The type of the map cells: */
75 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
76  typedef int8_t cellType;
77  typedef uint8_t cellTypeUnsigned;
78 #else
79  typedef int16_t cellType;
81 #endif
82 
83  /** Discrete to float conversion factors: The min/max values of the integer
84  * cell type, eg.[0,255] or [0,65535] */
91 
92  /** (Default:1.0) Can be set to <1 if a more fine raytracing is needed in
93  * sonarSimulator() and laserScanSimulator(), or >1 to speed it up. */
95 
96  protected:
97  friend class CMultiMetricMap;
98  friend class CMultiMetricMapPDF;
99 
100  /** Frees the dynamic memory buffers of map. */
101  void freeMap();
102  /** Lookup tables for log-odds */
104 
105  /** Store of cell occupancy values. Order: row by row, from left to right */
106  std::vector<cellType> map;
107  /** The size of the grid in cells */
109  /** The limits of the grid in "units" (meters) */
110  float x_min, x_max, y_min, y_max;
111  /** Cell size, i.e. resolution of the grid map. */
112  float resolution;
113 
114  /** Auxiliary variables to speed up the computation of observation
115  * likelihood values for LF method among others, at a high cost in memory
116  * (see TLikelihoodOptions::enableLikelihoodCache). */
117  std::vector<double> precomputedLikelihood;
119 
120  /** Used for Voronoi calculation.Same struct as "map", but contains a "0" if
121  * not a basis point. */
123 
124  /** Used to store the Voronoi diagram.
125  * Contains the distance of each cell to its closer obstacles
126  * in 1/100th distance units (i.e. in centimeters), or 0 if not into the
127  * Voronoi diagram */
129 
130  /** True upon construction; used by isEmpty() */
132 
133  /** See base class */
134  virtual void OnPostSuccesfulInsertObs(
135  const mrpt::obs::CObservation*) override;
136 
137  /** The free-cells threshold used to compute the Voronoi diagram. */
139 
140  /** Entropy computation internal function: */
141  static double H(double p);
142  /** Internally used to speed-up entropy calculation */
143  static std::vector<float> entropyTable;
144 
145  /** Change the contents [0,1] of a cell, given its index */
146  inline void setCell_nocheck(int x, int y, float value)
147  {
148  map[x + y * size_x] = p2l(value);
149  }
150 
151  /** Read the real valued [0,1] contents of a cell, given its index */
152  inline float getCell_nocheck(int x, int y) const
153  {
154  return l2p(map[x + y * size_x]);
155  }
156  /** Changes a cell by its absolute index (Do not use it normally) */
157  inline void setRawCell(unsigned int cellIndex, cellType b)
158  {
159  if (cellIndex < size_x * size_y) map[cellIndex] = b;
160  }
161 
162  /** One of the methods that can be selected for implementing
163  * "computeObservationLikelihood" (This method is the Range-Scan Likelihood
164  * Consensus for gridmaps, see the ICRA2007 paper by Blanco et al.) */
166  const mrpt::obs::CObservation* obs,
167  const mrpt::poses::CPose2D& takenFrom);
168  /** One of the methods that can be selected for implementing
169  * "computeObservationLikelihood". TODO: This method is described in.... */
171  const mrpt::obs::CObservation* obs,
172  const mrpt::poses::CPose2D& takenFrom);
173  /** One of the methods that can be selected for implementing
174  * "computeObservationLikelihood" */
176  const mrpt::obs::CObservation* obs,
177  const mrpt::poses::CPose2D& takenFrom);
178  /** One of the methods that can be selected for implementing
179  * "computeObservationLikelihood" */
181  const mrpt::obs::CObservation* obs,
182  const mrpt::poses::CPose2D& takenFrom);
183  /** One of the methods that can be selected for implementing
184  * "computeObservationLikelihood" */
186  const mrpt::obs::CObservation* obs,
187  const mrpt::poses::CPose2D& takenFrom);
188  /** One of the methods that can be selected for implementing
189  * "computeObservationLikelihood".*/
191  const mrpt::obs::CObservation* obs,
192  const mrpt::poses::CPose2D& takenFrom);
193  /** One of the methods that can be selected for implementing
194  * "computeObservationLikelihood". */
196  const mrpt::obs::CObservation* obs,
197  const mrpt::poses::CPose2D& takenFrom);
198 
199  /** Clear the map: It set all cells to their default occupancy value (0.5),
200  * without changing the resolution (the grid extension is reset to the
201  * default values). */
202  virtual void internal_clear() override;
203 
204  /** Insert the observation information into this map.
205  *
206  * \param obs The observation
207  * \param robotPose The 3D pose of the robot mobile base in the map
208  * reference system, or nullptr (default) if you want to use
209  * CPose2D(0,0,deg)
210  *
211  * After successfull execution, "lastObservationInsertionInfo" is updated.
212  *
213  * \sa insertionOptions, CObservation::insertObservationInto
214  */
215  virtual bool internal_insertObservation(
216  const mrpt::obs::CObservation* obs,
217  const mrpt::poses::CPose3D* robotPose = nullptr) override;
218 
219  public:
220  /** Read-only access to the raw cell contents (cells are in log-odd units)
221  */
222  const std::vector<cellType>& getRawMap() const { return this->map; }
223  /** Performs the Bayesian fusion of a new observation of a cell \sa
224  * updateInfoChangeOnly, updateCell_fast_occupied, updateCell_fast_free */
225  void updateCell(int x, int y, float v);
226 
227  /** An internal structure for storing data related to counting the new
228  * information apported by some observation */
230  {
232  bool enabled = false, double I_change = 0, int cellsUpdated = 0)
233  : enabled(enabled),
236  laserRaysSkip(1)
237  {
238  }
239  /** If set to false (default), this struct is not used. Set to true only
240  * when measuring the info of an observation. */
241  bool enabled;
242  /** The cummulative change in Information: This is updated only from the
243  * "updateCell" method. */
244  double I_change;
245  /** The cummulative updated cells count: This is updated only from the
246  * "updateCell" method. */
248  /** In this mode, some laser rays can be skips to speep-up */
251 
252  /** Fills all the cells with a default value. */
253  void fill(float default_value = 0.5f);
254 
255  /** Constructor */
257  float min_x = -20.0f, float max_x = 20.0f, float min_y = -20.0f,
258  float max_y = 20.0f, float resolution = 0.05f);
259  /** Destructor */
260  virtual ~COccupancyGridMap2D();
261 
262  /** Change the size of gridmap, erasing all its previous contents.
263  * \param x_min The "x" coordinates of left most side of grid.
264  * \param x_max The "x" coordinates of right most side of grid.
265  * \param y_min The "y" coordinates of top most side of grid.
266  * \param y_max The "y" coordinates of bottom most side of grid.
267  * \param resolution The new size of cells.
268  * \param default_value The value of cells, tipically 0.5.
269  * \sa ResizeGrid
270  */
271  void setSize(
272  float x_min, float x_max, float y_min, float y_max, float resolution,
273  float default_value = 0.5f);
274 
275  /** Change the size of gridmap, maintaining previous contents.
276  * \param new_x_min The "x" coordinates of new left most side of grid.
277  * \param new_x_max The "x" coordinates of new right most side of grid.
278  * \param new_y_min The "y" coordinates of new top most side of grid.
279  * \param new_y_max The "y" coordinates of new bottom most side of grid.
280  * \param new_cells_default_value The value of the new cells, tipically 0.5.
281  * \param additionalMargin If set to true (default), an additional margin of
282  * a few meters will be added to the grid, ONLY if the new coordinates are
283  * larger than current ones.
284  * \sa setSize
285  */
286  void resizeGrid(
287  float new_x_min, float new_x_max, float new_y_min, float new_y_max,
288  float new_cells_default_value = 0.5f,
289  bool additionalMargin = true) noexcept;
290 
291  /** Returns the area of the gridmap, in square meters */
292  inline double getArea() const
293  {
295  }
296 
297  /** Returns the horizontal size of grid map in cells count */
298  inline unsigned int getSizeX() const { return size_x; }
299  /** Returns the vertical size of grid map in cells count */
300  inline unsigned int getSizeY() const { return size_y; }
301  /** Returns the "x" coordinate of left side of grid map */
302  inline float getXMin() const { return x_min; }
303  /** Returns the "x" coordinate of right side of grid map */
304  inline float getXMax() const { return x_max; }
305  /** Returns the "y" coordinate of top side of grid map */
306  inline float getYMin() const { return y_min; }
307  /** Returns the "y" coordinate of bottom side of grid map */
308  inline float getYMax() const { return y_max; }
309  /** Returns the resolution of the grid map */
310  inline float getResolution() const { return resolution; }
311  /** Transform a coordinate value into a cell index */
312  inline int x2idx(float x) const
313  {
314  return static_cast<int>((x - x_min) / resolution);
315  }
316  inline int y2idx(float y) const
317  {
318  return static_cast<int>((y - y_min) / resolution);
319  }
320 
321  inline int x2idx(double x) const
322  {
323  return static_cast<int>((x - x_min) / resolution);
324  }
325  inline int y2idx(double y) const
326  {
327  return static_cast<int>((y - y_min) / resolution);
328  }
329 
330  /** Transform a cell index into a coordinate value */
331  inline float idx2x(const size_t cx) const
332  {
333  return x_min + (cx + 0.5f) * resolution;
334  }
335  inline float idx2y(const size_t cy) const
336  {
337  return y_min + (cy + 0.5f) * resolution;
338  }
339 
340  /** Transform a coordinate value into a cell index, using a diferent "x_min"
341  * value */
342  inline int x2idx(float x, float x_min) const
343  {
344  return static_cast<int>((x - x_min) / resolution);
345  }
346  inline int y2idx(float y, float y_min) const
347  {
348  return static_cast<int>((y - y_min) / resolution);
349  }
350 
351  /** Scales an integer representation of the log-odd into a real valued
352  * probability in [0,1], using p=exp(l)/(1+exp(l)) */
353  static inline float l2p(const cellType l) { return get_logodd_lut().l2p(l); }
354  /** Scales an integer representation of the log-odd into a linear scale
355  * [0,255], using p=exp(l)/(1+exp(l)) */
356  static inline uint8_t l2p_255(const cellType l)
357  {
358  return get_logodd_lut().l2p_255(l);
359  }
360  /** Scales a real valued probability in [0,1] to an integer representation
361  * of: log(p)-log(1-p) in the valid range of cellType */
362  static inline cellType p2l(const float p) { return get_logodd_lut().p2l(p); }
363  /** Change the contents [0,1] of a cell, given its index */
364  inline void setCell(int x, int y, float value)
365  {
366  // The x> comparison implicitly holds if x<0
367  if (static_cast<unsigned int>(x) >= size_x ||
368  static_cast<unsigned int>(y) >= size_y)
369  return;
370  else
371  map[x + y * size_x] = p2l(value);
372  }
373 
374  /** Read the real valued [0,1] contents of a cell, given its index */
375  inline float getCell(int x, int y) const
376  {
377  // The x> comparison implicitly holds if x<0
378  if (static_cast<unsigned int>(x) >= size_x ||
379  static_cast<unsigned int>(y) >= size_y)
380  return 0.5f;
381  else
382  return l2p(map[x + y * size_x]);
383  }
384 
385  /** Access to a "row": mainly used for drawing grid as a bitmap efficiently,
386  * do not use it normally */
387  inline cellType* getRow(int cy)
388  {
389  if (cy < 0 || static_cast<unsigned int>(cy) >= size_y)
390  return nullptr;
391  else
392  return &map[0 + cy * size_x];
393  }
394 
395  /** Access to a "row": mainly used for drawing grid as a bitmap efficiently,
396  * do not use it normally */
397  inline const cellType* getRow(int cy) const
398  {
399  if (cy < 0 || static_cast<unsigned int>(cy) >= size_y)
400  return nullptr;
401  else
402  return &map[0 + cy * size_x];
403  }
404 
405  /** Change the contents [0,1] of a cell, given its coordinates */
406  inline void setPos(float x, float y, float value)
407  {
408  setCell(x2idx(x), y2idx(y), value);
409  }
410 
411  /** Read the real valued [0,1] contents of a cell, given its coordinates */
412  inline float getPos(float x, float y) const
413  {
414  return getCell(x2idx(x), y2idx(y));
415  }
416 
417  /** Returns "true" if cell is "static", i.e.if its occupancy is below a
418  * given threshold */
419  inline bool isStaticPos(float x, float y, float threshold = 0.7f) const
420  {
421  return isStaticCell(x2idx(x), y2idx(y), threshold);
422  }
423  inline bool isStaticCell(int cx, int cy, float threshold = 0.7f) const
424  {
425  return (getCell(cx, cy) <= threshold);
426  }
427 
428  /** Change a cell in the "basis" maps.Used for Voronoi calculation */
429  inline void setBasisCell(int x, int y, uint8_t value)
430  {
431  uint8_t* cell = m_basis_map.cellByIndex(x, y);
432 #ifdef _DEBUG
433  ASSERT_ABOVEEQ_(x, 0)
434  ASSERT_ABOVEEQ_(y, 0)
437 #endif
438  *cell = value;
439  }
440 
441  /** Reads a cell in the "basis" maps.Used for Voronoi calculation */
442  inline unsigned char getBasisCell(int x, int y) const
443  {
444  const uint8_t* cell = m_basis_map.cellByIndex(x, y);
445 #ifdef _DEBUG
446  ASSERT_ABOVEEQ_(x, 0)
447  ASSERT_ABOVEEQ_(y, 0)
450 #endif
451  return *cell;
452  }
453 
454  /** copy the gridmap contents, but not all the options, from another map
455  * instance */
456  void copyMapContentFrom(const COccupancyGridMap2D& otherMap);
457 
458  /** Used for returning entropy related information \sa computeEntropy */
460  {
462  : H(0),
463  I(0),
464  mean_H(0),
465  mean_I(0),
468  {
469  }
470  /** The target variable for absolute entropy, computed
471  * as:<br><center>H(map)=Sum<sub>x,y</sub>{ -p(x,y)*ln(p(x,y))
472  * -(1-p(x,y))*ln(1-p(x,y)) }</center><br><br> */
473  double H;
474  /** The target variable for absolute "information", defining I(x) = 1 -
475  * H(x) */
476  double I;
477  /** The target variable for mean entropy, defined as entropy per cell:
478  * mean_H(map) = H(map) / (cells) */
479  double mean_H;
480  /** The target variable for mean information, defined as information per
481  * cell: mean_I(map) = I(map) / (cells) */
482  double mean_I;
483  /** The target variable for the area of cells with information, i.e.
484  * p(x)!=0.5 */
486  /** The mapped area in cells. */
487  unsigned long effectiveMappedCells;
488  };
489 
490  /** With this struct options are provided to the observation insertion
491  * process.
492  * \sa CObservation::insertIntoGridMap */
494  {
495  public:
496  /** Initilization of default parameters
497  */
499 
500  /** This method load the options from a ".ini" file.
501  * Only those parameters found in the given "section" and having
502  * the same name that the variable are loaded. Those not found in
503  * the file will stay with their previous values (usually the default
504  * values loaded at initialization). An example of an ".ini" file:
505  * \code
506  * [section]
507  * resolution=0.10 ; blah blah...
508  * modeSelection=1 ; 0=blah, 1=blah,...
509  * \endcode
510  */
511  void loadFromConfigFile(
513  const std::string& section) override; // See base docs
514  void dumpToTextStream(
515  mrpt::utils::CStream& out) const override; // See base docs
516 
517  /** The altitude (z-axis) of 2D scans (within a 0.01m tolerance) for
518  * they to be inserted in this map! */
519  float mapAltitude;
520  /** The parameter "mapAltitude" has effect while inserting observations
521  * in the grid only if this is true. */
523  /** The largest distance at which cells will be updated (Default 15
524  * meters) */
526  /** A value in the range [0.5,1] used for updating cell with a bayesian
527  * approach (default 0.8) */
529  /** If set to true (default), invalid range values (no echo rays) as
530  * consider as free space until "maxOccupancyUpdateCertainty", but ONLY
531  * when the previous and next rays are also an invalid ray. */
533  /** Specify the decimation of the range scan (default=1 : take all the
534  * range values!) */
536  /** The tolerance in rads in pitch & roll for a laser scan to be
537  * considered horizontal, then processed by calls to this class
538  * (default=0). */
540  /** Gaussian sigma of the filter used in getAsImageFiltered (for
541  * features detection) (Default=1) (0:Disabled) */
543  /** Size of the Median filter used in getAsImageFiltered (for features
544  * detection) (Default=3) (0:Disabled) */
546  /** Enabled: Rays widen with distance to approximate the real behavior
547  * of lasers, disabled: insert rays as simple lines (Default=false) */
549  };
550 
551  /** With this struct options are provided to the observation insertion
552  * process \sa CObservation::insertIntoGridMap */
554 
555  /** The type for selecting a likelihood computation method */
557  {
565  // Remember: Update TEnumType below if new values are added here!
566  };
567 
568  /** With this struct options are provided to the observation likelihood
569  * computation process */
571  {
572  public:
573  /** Initilization of default parameters */
575 
576  /** This method load the options from a ".ini" file.
577  * Only those parameters found in the given "section" and having
578  * the same name that the variable are loaded. Those not found in
579  * the file will stay with their previous values (usually the default
580  * values loaded at initialization). An example of an ".ini" file:
581  * \code
582  * [section]
583  * resolution=0.10 ; blah blah...
584  * modeSelection=1 ; 0=blah, 1=blah,...
585  * \endcode
586  */
587  void loadFromConfigFile(
589  const std::string& section) override; // See base docs
590  void dumpToTextStream(
591  mrpt::utils::CStream& out) const override; // See base docs
592 
593  /** The selected method to compute an observation likelihood */
595  /** [LikelihoodField] The laser range "sigma" used in computations;
596  * Default value = 0.35 */
597  float LF_stdHit;
598  /** [LikelihoodField] */
600  /** [LikelihoodField] The max. range of the sensor (Default= 81 m) */
601  float LF_maxRange;
602  /** [LikelihoodField] The decimation of the points in a scan, default=1
603  * == no decimation */
605  /** [LikelihoodField] The max. distance for searching correspondences
606  * around each sensed point */
608  /** [LikelihoodField] (Default:false) Use `exp(dist^2/std^2)` instead of
609  * `exp(dist^2/std^2)` */
611  /** [LikelihoodField] Set this to "true" ot use an alternative method,
612  * where the likelihood of the whole range scan is computed by
613  * "averaging" of individual ranges, instead of by the "product". */
615  /** [MI] The exponent in the MI likelihood computation. Default value =
616  * 5 */
617  float MI_exponent;
618  /** [MI] The scan rays decimation: at every N rays, one will be used to
619  * compute the MI */
621  /** [MI] The ratio for the max. distance used in the MI computation and
622  * in the insertion of scans, e.g. if set to 2.0 the MI will use twice
623  * the distance that the update distance. */
625  /** [rayTracing] If true (default), the rayTracing method will ignore
626  * measured ranges shorter than the simulated ones. */
628  /** [rayTracing] One out of "rayTracing_decimation" rays will be
629  * simulated and compared only: set to 1 to use all the sensed ranges.
630  */
632  /** [rayTracing] The laser range sigma. */
634  /** [Consensus] The down-sample ratio of ranges (default=1, consider all
635  * the ranges) */
637  /** [Consensus] The power factor for the likelihood (default=5) */
639  /** [OWA] The sequence of weights to be multiplied to of the ordered
640  * list of likelihood values (first one is the largest); the size of
641  * this vector determines the number of highest likelihood values to
642  * fuse. */
643  std::vector<float> OWA_weights;
644 
645  /** Enables the usage of a cache of likelihood values (for LF methods),
646  * if set to true (default=false). */
649 
650  /** Auxiliary private class. */
651  typedef std::pair<double, mrpt::math::TPoint2D> TPairLikelihoodIndex;
652 
653  /** Some members of this struct will contain intermediate or output data
654  * after calling "computeObservationLikelihood" for some likelihood
655  * functions */
657  {
658  public:
660  /** [OWA method] This will contain the ascending-ordered list of
661  * pairs:(likelihood values, 2D point in map coordinates). */
662  std::vector<TPairLikelihoodIndex> OWA_pairList;
663  /** [OWA method] This will contain the ascending-ordered list of
664  * likelihood values for individual range measurements in the scan. */
665  std::vector<double> OWA_individualLikValues;
667 
668  /** Performs a downsampling of the gridmap, by a given factor:
669  * resolution/=ratio */
670  void subSample(int downRatio);
671 
672  /** Computes the entropy and related values of this grid map.
673  * The entropy is computed as the summed entropy of each cell, taking them
674  * as discrete random variables following a Bernoulli distribution:
675  * \param info The output information is returned here */
676  void computeEntropy(TEntropyInfo& info) const;
677 
678  /** @name Voronoi methods
679  @{ */
680 
681  /** Build the Voronoi diagram of the grid map.
682  * \param threshold The threshold for binarizing the map.
683  * \param robot_size Size in "units" (meters) of robot, approx.
684  * \param x1 Left coordinate of area to be computed. Default, entire map.
685  * \param x2 Right coordinate of area to be computed. Default, entire map.
686  * \param y1 Top coordinate of area to be computed. Default, entire map.
687  * \param y2 Bottom coordinate of area to be computed. Default, entire map.
688  * \sa findCriticalPoints
689  */
690  void buildVoronoiDiagram(
691  float threshold, float robot_size, int x1 = 0, int x2 = 0, int y1 = 0,
692  int y2 = 0);
693 
694  /** Reads a the clearance of a cell (in centimeters), after building the
695  * Voronoi diagram with \a buildVoronoiDiagram */
696  inline uint16_t getVoroniClearance(int cx, int cy) const
697  {
698 #ifdef _DEBUG
699  ASSERT_ABOVEEQ_(cx, 0)
700  ASSERT_ABOVEEQ_(cy, 0)
703 #endif
704  const uint16_t* cell = m_voronoi_diagram.cellByIndex(cx, cy);
705  return *cell;
706  }
707 
708  protected:
709  /** Used to set the clearance of a cell, while building the Voronoi diagram.
710  */
711  inline void setVoroniClearance(int cx, int cy, uint16_t dist)
712  {
713  uint16_t* cell = m_voronoi_diagram.cellByIndex(cx, cy);
714 #ifdef _DEBUG
715  ASSERT_ABOVEEQ_(cx, 0)
716  ASSERT_ABOVEEQ_(cy, 0)
719 #endif
720  *cell = dist;
721  }
722 
723  public:
724  /** Return the auxiliary "basis" map built while building the Voronoi
725  * diagram \sa buildVoronoiDiagram */
727  {
728  return m_basis_map;
729  }
730 
731  /** Return the Voronoi diagram; each cell contains the distance to its
732  * closer obstacle, or 0 if not part of the Voronoi diagram \sa
733  * buildVoronoiDiagram */
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::utils::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::utils::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::utils::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::utils::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, const mrpt::utils::TColor& marks_color =
1001  mrpt::utils::TColor(0, 0, 255)) const
1002  {
1003  MRPT_START
1004  using namespace mrpt::utils;
1005  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(px, py - 8, format("%u", i), TColor::black());
1019  }
1020  return img.saveToFile(file.c_str());
1021  MRPT_END
1022  }
1023 
1024  /** Returns the grid as a 8-bit graylevel image, where each pixel is a cell
1025  * (output image is RGB only if forceRGB is true)
1026  * If "tricolor" is true, only three gray levels will appear in the image:
1027  * gray for unobserved cells, and black/white for occupied/empty cells
1028  * respectively.
1029  * \sa getAsImageFiltered
1030  */
1031  void getAsImage(
1032  utils::CImage& img, bool verticalFlip = false, bool forceRGB = false,
1033  bool tricolor = false) const;
1034 
1035  /** Returns the grid as a 8-bit graylevel image, where each pixel is a cell
1036  * (output image is RGB only if forceRGB is true) - This method filters the
1037  * image for easy feature detection
1038  * If "tricolor" is true, only three gray levels will appear in the image:
1039  * gray for unobserved cells, and black/white for occupied/empty cells
1040  * respectively.
1041  * \sa getAsImage
1042  */
1043  void getAsImageFiltered(
1044  utils::CImage& img, bool verticalFlip = false,
1045  bool forceRGB = false) const;
1046 
1047  /** Returns a 3D plane with its texture being the occupancy grid and
1048  * transparency proportional to "uncertainty" (i.e. a value of 0.5 is fully
1049  * transparent)
1050  */
1051  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
1052 
1053  /** Get a point cloud with all (border) occupied cells as points */
1054  void getAsPointCloud(
1056  const float occup_threshold = 0.5f) const;
1057 
1058  /** Returns true upon map construction or after calling clear(), the return
1059  * changes to false upon successful insertObservation() or any other
1060  * method to load data in the map.
1061  */
1062  bool isEmpty() const override;
1063 
1064  /** Load the gridmap from a image in a file (the format can be any supported
1065  * by CImage::loadFromFile).
1066  * \param file The file to be loaded.
1067  * \param resolution The size of a pixel (cell), in meters. Recall cells are
1068  * always squared, so just a dimension is needed.
1069  * \param xCentralPixel The `x` coordinate (0=first, increases <b>left to
1070  * right</b> on the image) for the pixel which will be taken at coordinates
1071  * origin (0,0). (Default: the center of the image)
1072  * \param yCentralPixel The `y` coordinate (0=first, increases <b>BOTTOM
1073  * upwards</b> on the image) for the pixel which will be taken at
1074  * coordinates origin (0,0). (Default: the center of the image)
1075  * \return False on any error.
1076  * \sa loadFromBitmap
1077  */
1078  bool loadFromBitmapFile(
1079  const std::string& file, float resolution, float xCentralPixel = -1,
1080  float yCentralPixel = -1);
1081 
1082  /** Load the gridmap from a image in a file (the format can be any supported
1083  * by CImage::loadFromFile).
1084  * See loadFromBitmapFile() for the meaning of parameters */
1085  bool loadFromBitmap(
1086  const mrpt::utils::CImage& img, float resolution,
1087  float xCentralPixel = -1, float yCentralPixel = -1);
1088 
1089  /** See the base class for more details: In this class it is implemented as
1090  * correspondences of the passed points map to occupied cells.
1091  * NOTICE: That the "z" dimension is ignored in the points. Clip the points
1092  * as appropiated if needed before calling this method.
1093  *
1094  * \sa computeMatching3DWith
1095  */
1096  virtual void determineMatching2D(
1097  const mrpt::maps::CMetricMap* otherMap,
1098  const mrpt::poses::CPose2D& otherMapPose,
1099  mrpt::utils::TMatchingPairList& correspondences,
1100  const TMatchingParams& params,
1101  TMatchingExtraResults& extraResults) const override;
1102 
1103  /** See docs in base class: in this class this always returns 0 */
1104  float compute3DMatchingRatio(
1105  const mrpt::maps::CMetricMap* otherMap,
1106  const mrpt::poses::CPose3D& otherMapPose,
1107  const TMatchingRatioParams& params) const override;
1108 
1109  /** This virtual method saves the map to a file "filNamePrefix"+<
1110  * some_file_extension >, as an image or in any other applicable way (Notice
1111  * that other methods to save the map may be implemented in classes
1112  * implementing this virtual interface). */
1114  const std::string& filNamePrefix) const override;
1115 
1116  /** The structure used to store the set of Voronoi diagram
1117  * critical points.
1118  * \sa findCriticalPoints
1119  */
1121  {
1123  : x(),
1124  y(),
1125  clearance(),
1126  x_basis1(),
1127  y_basis1(),
1128  x_basis2(),
1129  y_basis2()
1130  {
1131  }
1132 
1133  /** The coordinates of critical point. */
1134  std::vector<int> x, y;
1135  /** The clearance of critical points, in 1/100 of cells. */
1136  std::vector<int> clearance;
1137  /** Their two first basis points coordinates. */
1138  std::vector<int> x_basis1, y_basis1, x_basis2, y_basis2;
1140 
1141  private:
1142  // See docs in base class
1144  const mrpt::obs::CObservation* obs,
1145  const mrpt::poses::CPose3D& takenFrom) override;
1146  // See docs in base class
1148  const mrpt::obs::CObservation* obs) const override;
1149 
1150  /** Returns a byte with the occupancy of the 8 sorrounding cells.
1151  * \param cx The cell index
1152  * \param cy The cell index
1153  * \sa direction2idx
1154  */
1155  inline unsigned char GetNeighborhood(int cx, int cy) const;
1156 
1157  /** Used to store the 8 possible movements from a cell to the
1158  * sorrounding ones.Filled in the constructor.
1159  * \sa direction2idx
1160  */
1162 
1163  /** Returns the index [0,7] of the given movement, or
1164  * -1 if invalid one.
1165  * \sa direccion_vecino_x,direccion_vecino_y,GetNeighborhood
1166  */
1167  int direction2idx(int dx, int dy);
1168 
1170  /** See COccupancyGridMap2D::COccupancyGridMap2D */
1171  float min_x, max_x, min_y, max_y, resolution;
1172  /** Observations insertion options */
1174  /** Probabilistic observation likelihood options */
1177 };
1178 
1179 bool operator<(
1182 
1183 } // End of namespace
1184 namespace utils
1185 {
1186 template <>
1188 {
1190  static void fill(bimap<enum_t, std::string>& m_map)
1191  {
1192  using namespace mrpt::maps;
1200  }
1201 };
1202 }
1203 } // End of namespace
1204 
1205 #endif
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 ...
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.
bool saveAsBitmapFileWithLandmarks(const std::string &file, const CLANDMARKSMAP *landmarks, bool addTextLabels=false, const mrpt::utils::TColor &marks_color=mrpt::utils::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.
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.
#define ASSERT_BELOWEQ_(__A, __B)
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.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
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...
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
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".
std::vector< int > x
The coordinates of critical point.
float getResolution() const
Returns the resolution of the grid map.
double DEG2RAD(const double x)
Degrees to radians.
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...
int y2idx(float y, float y_min) const
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...
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...
static bool saveAsBitmapTwoMapsWithCorrespondences(const std::string &fileName, const COccupancyGridMap2D *m1, const COccupancyGridMap2D *m2, const mrpt::utils::TMatchingPairList &corrs)
Saves a composite image with two gridmaps and lines representing a set of correspondences between the...
double effectiveMappedArea
The target variable for the area of cells with information, i.e.
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:118
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...
static double H(double p)
Entropy computation internal function:
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
Output params for laserScanSimulatorWithUncertainty()
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.
void updateCell(int x, int y, float v)
Performs the Bayesian fusion of a new observation of a cell.
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::utils::DEG2RAD(0)) const
Simulates a laser range scan into the current grid map.
size_t getSizeY() const
Returns the vertical size of grid map in cells count.
Definition: CDynamicGrid.h:256
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
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini" file.
TInsertionOptions insertionOptions
With this struct options are provided to the observation insertion process.
Only specializations of this class are defined for each enum type of interest.
Definition: TEnumType.h:24
static const cellType OCCGRID_CELLTYPE_MAX
std::pair< double, mrpt::math::TPoint2D > TPairLikelihoodIndex
Auxiliary private class.
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.
const mrpt::utils::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.
std::vector< double > precomputedLikelihood
Auxiliary variables to speed up the computation of observation likelihood values for LF method among ...
#define MRPT_FILL_ENUM_MEMBER(_CLASS, _VALUE)
Definition: TEnumType.h:32
float MI_ratio_max_distance
[MI] The ratio for the max.
void getAsImage(utils::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 ...
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.
const cellType * getRow(int cy) const
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
This class allows loading and storing values and vectors of different types from a configuration text...
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)
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,...).
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
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: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)) }
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
#define MRPT_END
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...
const mrpt::utils::CDynamicGrid< uint8_t > & getBasisMap() const
Return the auxiliary "basis" map built while building the Voronoi diagram.
GLint GLvoid * img
Definition: glext.h:3763
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
std::vector< int > x_basis1
Their two first basis points coordinates.
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.
A list of TMatchingPair.
Definition: TMatchingPair.h:93
TLaserSimulUncertaintyMethod
Methods for TLaserSimulUncertaintyParams in laserScanSimulatorWithUncertainty()
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini" file.
void copyMapContentFrom(const COccupancyGridMap2D &otherMap)
copy the gridmap contents, but not all the options, from another map instance
size_t getSizeX() const
Returns the horizontal size of grid map in cells count.
Definition: CDynamicGrid.h:254
float aperture
(Default: M_PI) The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180...
double I
The target variable for absolute "information", defining I(x) = 1 - H(x)
TUpdateCellsInfoChangeOnly(bool enabled=false, double I_change=0, int cellsUpdated=0)
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
Definition: bimap.h:34
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:32
A RGB color - 8bit.
Definition: TColor.h:25
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:19
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...
unsigned char getBasisCell(int x, int y) const
Reads a cell in the "basis" maps.Used for Voronoi calculation.
void sonarSimulator(mrpt::obs::CObservationRange &inout_observation, const mrpt::poses::CPose2D &robotPose, float threshold=0.5f, float rangeNoiseStd=0.f, float angleNoiseStd=mrpt::utils::DEG2RAD(0.f)) const
Simulates the observations of a sonar rig into the current grid map.
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,...
bool LF_useSquareDist
[LikelihoodField] (Default:false) Use exp(dist^2/std^2) instead of exp(dist^2/std^2) ...
GLsizei const GLchar ** string
Definition: glext.h:4101
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:234
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) ...
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...
static bool saveAsEMFTwoMapsWithCorrespondences(const std::string &fileName, const COccupancyGridMap2D *m1, const COccupancyGridMap2D *m2, const mrpt::utils::TMatchingPairList &corrs)
Saves a composite image with two gridmaps and numbers for the correspondences between them...
A class for storing an occupancy grid map.
float angleNoiseStd
(Default: 0) The sigma of an optional Gaussian noise added to the angles at which ranges are measured...
#define MRPT_START
__int32 int32_t
Definition: rptypes.h:46
void getAsImageFiltered(utils::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 ...
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.
#define ASSERT_ABOVEEQ_(__A, __B)
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:55
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
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:88
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:41
int cellsUpdated
The cummulative updated cells count: This is updated only from the "updateCell" method.
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).
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.
T square(const T x)
Inline function for the square of a number.
unsigned char GetNeighborhood(int cx, int cy) const
Returns a byte with the occupancy of the 8 sorrounding cells.
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.
int x2idx(float x, float x_min) const
Transform a coordinate value into a cell index, using a diferent "x_min" value.
void setVoroniClearance(int cx, int cy, uint16_t dist)
Used to set the clearance of a cell, while building the Voronoi diagram.
bool loadFromBitmap(const mrpt::utils::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).
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
float getYMax() const
Returns the "y" coordinate of bottom side of grid map.
struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList CriticalPointsList
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
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...
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
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...
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.
class mrpt::maps::COccupancyGridMap2D::TLikelihoodOutput likelihoodOutputs
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.
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
int16_t cellType
The type of the map cells:
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 dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void setPos(float x, float y, float value)
Change the contents [0,1] of a cell, given its coordinates.
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
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...
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