Main MRPT website > C++ reference for MRPT 1.3.2
maps/CReflectivityGridMap2D.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-2015, 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 CReflectivityGridMap2D_H
11 #define CReflectivityGridMap2D_H
12 
13 #include <mrpt/utils/CImage.h>
17 #include <mrpt/maps/CMetricMap.h>
19 #include <mrpt/obs/obs_frwds.h>
20 
21 #include <mrpt/maps/link_pragmas.h>
22 
23 namespace mrpt
24 {
25  namespace maps
26  {
27  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CReflectivityGridMap2D, CMetricMap, MAPS_IMPEXP )
28 
29  /** A 2D grid map representing the reflectivity of the environment (for example, measured with an IR proximity sensor).
30  *
31  * Important implemented features are:
32  * - Insertion of mrpt::obs::CObservationReflectivity observations.
33  * - Probability estimation of observations. See base class.
34  * - Rendering as 3D object: a 2D textured plane.
35  * - Automatic resizing of the map limits when inserting observations close to the border.
36  *
37  * Each cell contains the up-to-date average height from measured falling in that cell. Algorithms that can be used:
38  * - mrSimpleAverage: Each cell only stores the current average value.
39  * \ingroup mrpt_maps_grp
40  */
42  public CMetricMap,
43  public utils::CDynamicGrid<int8_t>,
44  public CLogOddsGridMap2D<int8_t>
45  {
46  // This must be added to any CSerializable derived class:
48 
49  protected:
50  static CLogOddsGridMapLUT<cell_t> m_logodd_lut; //!< Lookup tables for log-odds
51 
52  public:
53 
54  /** Calls the base CMetricMap::clear
55  * Declared here to avoid ambiguity between the two clear() in both base classes.
56  */
57  inline void clear() { CMetricMap::clear(); }
58 
59  float cell2float(const int8_t& c) const
60  {
61  return m_logodd_lut.l2p(c);
62  }
63 
64  /** Constructor
65  */
67  float x_min = -2,
68  float x_max = 2,
69  float y_min = -2,
70  float y_max = 2,
71  float resolution = 0.1
72  );
73 
74  /** Returns true if the map is empty/no observation has been inserted.
75  */
76  bool isEmpty() const;
77 
78 
79  /** Parameters related with inserting observations into the map.
80  */
82  {
83  /** Default values loader:
84  */
86 
87  /** See utils::CLoadableOptions
88  */
89  void loadFromConfigFile(
90  const mrpt::utils::CConfigFileBase &source,
91  const std::string &section);
92 
93  /** See utils::CLoadableOptions
94  */
95  void dumpToTextStream(mrpt::utils::CStream &out) const;
96 
97  } insertionOptions;
98 
99  /** See docs in base class: in this class this always returns 0 */
100  float compute3DMatchingRatio(
101  const mrpt::maps::CMetricMap *otherMap,
102  const mrpt::poses::CPose3D &otherMapPose,
103  float maxDistForCorr = 0.10f,
104  float maxMahaDistForCorr = 2.0f
105  ) const;
106 
107  /** The implementation in this class just calls all the corresponding method of the contained metric maps.
108  */
109  void saveMetricMapRepresentationToFile(
110  const std::string &filNamePrefix
111  ) const;
112 
113  /** Returns a 3D object representing the map: by default, it will be a mrpt::opengl::CMesh object, unless
114  * it is specified otherwise in mrpt::
115  */
116  void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const;
117 
118  /** Returns the grid as a 8-bit graylevel image, where each pixel is a cell (output image is RGB only if forceRGB is true)
119  */
120  void getAsImage( utils::CImage &img, bool verticalFlip = false, bool forceRGB=false) const;
121 
122  protected:
123 
124  // See docs in base class
125  void internal_clear() MRPT_OVERRIDE;
126  bool internal_insertObservation( const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose = NULL ) MRPT_OVERRIDE;
127  double internal_computeObservationLikelihood( const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom ) MRPT_OVERRIDE;
128 
130  float min_x,max_x,min_y,max_y,resolution; //!< See CReflectivityGridMap2DOptions::CReflectivityGridMap2DOptions
133  };
134  DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE( CReflectivityGridMap2D, CMetricMap, MAPS_IMPEXP )
135 
136 
137  } // End of namespace
138 
139 
140 } // End of namespace
141 
142 #endif
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:101
void clear()
Erase all the contents of the map.
A 2D grid map representing the reflectivity of the environment (for example, measured with an IR prox...
This class allows loading and storing values and vectors of different types from a configuration text...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
float cell2float(const int8_t &c) const
The user must implement this in order to provide "saveToTextFile" a way to convert each cell into a n...
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...
Parameters related with inserting observations into the map.
Declares a virtual base class for all metric maps storage classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:72
Declares a class that represents any robot&#39;s observation.
A generic provider of log-odds grid-map maintainance functions.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define MAP_DEFINITION_START(_CLASS_NAME_, _LINKAGE_)
Add a MAP_DEFINITION_START() ...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...



Page generated by Doxygen 1.8.11 for MRPT 1.3.2 SVN: at Mon May 9 06:50:38 UTC 2016