MRPT  2.0.4
CHeightGridMap2D.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
14 #include <mrpt/img/color_maps.h>
16 #include <mrpt/maps/CMetricMap.h>
17 #include <mrpt/obs/obs_frwds.h>
18 #include <mrpt/poses/poses_frwds.h>
21 
22 namespace mrpt
23 {
24 namespace maps
25 {
26 /** The contents of each cell in a CHeightGridMap2D map */
28 {
29  /** The current average height (in meters) */
30  float h{};
31  /** The current standard deviation of the height (in meters) */
32  float var{};
33  /** Auxiliary variable for storing the incremental mean value (in meters).
34  */
35  float u{};
36  /** Auxiliary (in meters) */
37  float v{};
38  /** [For mrSimpleAverage model] The accumulated weight: initially zero if
39  * un-observed, increased by one for each observation */
40  uint32_t w{};
41 
42  THeightGridmapCell() = default;
43 };
44 
45 /** Digital Elevation Model (DEM), a mesh or grid representation of a surface
46  * which keeps the estimated height for each (x,y) location.
47  * Important implemented features are the insertion of 2D laser scans (from
48  * arbitrary 6D poses) and the exportation as 3D scenes.
49  *
50  * Each cell contains the up-to-date average height from measured falling in
51  * that cell. Algorithms that can be used:
52  * - mrSimpleAverage: Each cell only stores the current average value.
53  *
54  * This class implements generic version of
55  * mrpt::maps::CMetric::insertObservation() accepting these types of sensory
56  * data:
57  * - mrpt::obs::CObservation2DRangeScan: 2D range scans
58  * - mrpt::obs::CObservationVelodyneScan
59  *
60  * \ingroup mrpt_maps_grp
61  */
63  : public mrpt::maps::CMetricMap,
64  public mrpt::containers::CDynamicGrid<THeightGridmapCell>,
66 {
68  public:
69  /** Calls the base CMetricMap::clear
70  * Declared here to avoid ambiguity between the two clear() in both base
71  * classes.
72  */
73  inline void clear() { CMetricMap::clear(); }
74  float cell2float(const THeightGridmapCell& c) const override
75  {
76  return float(c.h);
77  }
78 
79  /** The type of map representation to be used.
80  * See mrpt::maps::CHeightGridMap2D for discussion.
81  */
83  {
85  };
86 
87  /** Constructor */
89  TMapRepresentation mapType = mrSimpleAverage, double x_min = -2,
90  double x_max = 2, double y_min = -2, double y_max = 2,
91  double resolution = 0.1);
92 
93  /** Returns true if the map is empty/no observation has been inserted. */
94  bool isEmpty() const override;
95 
96  /** Parameters related with inserting observations into the map */
98  {
99  /** Default values loader */
101 
102  void loadFromConfigFile(
103  const mrpt::config::CConfigFileBase& source,
104  const std::string& section) override; // See base docs
105  void dumpToTextStream(
106  std::ostream& out) const override; // See base docs
107 
108  /** Whether to perform filtering by z-coordinate (default=false):
109  * coordinates are always RELATIVE to the robot for this filter.vvv */
110  bool filterByHeight{false};
111  /** Only when filterByHeight is true: coordinates are always RELATIVE to
112  * the robot for this filter. */
113  float z_min{-0.5}, z_max{0.5};
114 
117 
118  /** See docs in base class: in this class it always returns 0 */
120  const mrpt::maps::CMetricMap* otherMap,
121  const mrpt::poses::CPose3D& otherMapPose,
122  const TMatchingRatioParams& params) const override;
123 
124  void saveMetricMapRepresentationToFile(const std::string& filNamePrefix)
125  const override; // See base class docs
126 
127  /** Returns a 3D object representing the map: by default, it will be a
128  * mrpt::opengl::CMesh object, unless
129  * it is specified otherwise in
130  * mrpt::global_settings::HEIGHTGRIDMAP_EXPORT3D_AS_MESH */
131  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
132 
133  /** Return the type of the gas distribution map, according to parameters
134  * passed on construction */
136 
137  /** Return the number of cells with at least one height data inserted. */
138  size_t countObservedCells() const;
139 
141  const double x, const double y, const double z,
144  double dem_get_resolution() const override;
145  size_t dem_get_size_x() const override;
146  size_t dem_get_size_y() const override;
147  bool dem_get_z_by_cell(
148  const size_t cx, const size_t cy, double& z_out) const override;
149  bool dem_get_z(
150  const double x, const double y, double& z_out) const override;
151  void dem_update_map() override;
152 
153  /** The map representation type of this map */
155 
156  // See docs in base class
157  void internal_clear() override;
159  const mrpt::obs::CObservation& obs,
160  const mrpt::poses::CPose3D* robotPose = nullptr) override;
162  const mrpt::obs::CObservation& obs,
163  const mrpt::poses::CPose3D& takenFrom) override;
164 
166  /** See CHeightGridMap2D::CHeightGridMap2D */
167  double min_x{-2}, max_x{2}, min_y{-2}, max_y{2}, resolution{0.10f};
168  /** The kind of map representation (see CHeightGridMap2D::CHeightGridMap2D)
169  */
174 };
175 
176 } // namespace maps
177 
178 namespace global_settings
179 {
180 /** If set to true (default), mrpt::maps::CHeightGridMap2D will be exported as a
181  *opengl::CMesh, otherwise, as a opengl::CPointCloudColoured
182  * Affects to:
183  * - CHeightGridMap2D::getAs3DObject
184  */
185 void HEIGHTGRIDMAP_EXPORT3D_AS_MESH(bool value);
187 } // namespace global_settings
188 } // namespace mrpt
189 
190 MRPT_ENUM_TYPE_BEGIN(maps::CHeightGridMap2D::TMapRepresentation)
192  maps::CHeightGridMap2D::TMapRepresentation, mrSimpleAverage);
Digital Elevation Model (DEM), a mesh or grid representation of a surface which keeps the estimated h...
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:30
float var
The current standard deviation of the height (in meters)
float h
The current average height (in meters)
Parameters for CMetricMap::compute3DMatchingRatio()
TColormap
Different colormaps for use in mrpt::img::colormap()
Definition: color_maps.h:30
Extra params for insertIndividualPoint()
A 2D grid of dynamic size which stores any kind of data at each cell.
Definition: CDynamicGrid.h:38
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.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
CHeightGridMap2D(TMapRepresentation mapType=mrSimpleAverage, double x_min=-2, double x_max=2, double y_min=-2, double y_max=2, double resolution=0.1)
Constructor.
void dem_update_map() override
Ensure that all observations are reflected in the map estimate.
TMapRepresentation
The type of map representation to be used.
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
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 it always returns 0.
The contents of each cell in a CHeightGridMap2D map.
bool dem_get_z_by_cell(const size_t cx, const size_t cy, double &z_out) const override
Get cell &#39;z&#39; by (cx,cy) cell indices.
mrpt::vision::TStereoCalibParams params
bool dem_get_z(const double x, const double y, double &z_out) const override
Get cell &#39;z&#39; (x,y) by metric coordinates.
MRPT_FILL_ENUM_MEMBER(maps::CHeightGridMap2D::TMapRepresentation, mrSimpleAverage)
uint32_t w
[For mrSimpleAverage model] The accumulated weight: initially zero if un-observed, increased by one for each observation
float v
Auxiliary (in meters)
void clear()
Calls the base CMetricMap::clear Declared here to avoid ambiguity between the two clear() in both bas...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::maps::CHeightGridMap2D::TInsertionOptions insertionOptions
size_t dem_get_size_x() const override
This class allows loading and storing values and vectors of different types from a configuration text...
bool insertIndividualPoint(const double x, const double y, const double z, const CHeightGridMap2D_Base::TPointInsertParams &params=CHeightGridMap2D_Base::TPointInsertParams()) override
Update the DEM with one new point.
float z_min
Only when filterByHeight is true: coordinates are always RELATIVE to the robot for this filter...
Parameters related with inserting observations into the map.
double dem_get_resolution() const override
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
float u
Auxiliary variable for storing the incremental mean value (in meters).
TMapRepresentation getMapType()
Return the type of the gas distribution map, according to parameters passed on construction.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
size_t dem_get_size_y() const override
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
bool filterByHeight
Whether to perform filtering by z-coordinate (default=false): coordinates are always RELATIVE to the ...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::vision::TStereoCalibResults out
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
Virtual base class for Digital Elevation Model (DEM) maps.
void internal_clear() override
Internal method called by clear()
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map: by default, it will be a mrpt::opengl::CMesh object...
TMapRepresentation m_mapType
The map representation type of this map.
float cell2float(const THeightGridmapCell &c) const override
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
mrpt::maps::CHeightGridMap2D::TInsertionOptions insertionOpts
bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
size_t countObservedCells() const
Return the number of cells with at least one height data inserted.
#define MAP_DEFINITION_END(_CLASS_NAME_)
void HEIGHTGRIDMAP_EXPORT3D_AS_MESH(bool value)
If set to true (default), mrpt::maps::CHeightGridMap2D will be exported as a opengl::CMesh, otherwise, as a opengl::CPointCloudColoured Affects to:



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020