Main MRPT website > C++ reference for MRPT 1.9.9
TMetricMapInitializer.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 
10 #pragma once
11 
13 #include <mrpt/rtti/CObject.h> // For TRuntimeClassId
16 #include <deque>
17 
18 namespace mrpt
19 {
20 namespace maps
21 {
22 class TSetOfMetricMapInitializers;
23 
24 /** Virtual base for specifying the kind and parameters of one map (normally, to
25  * be inserted into mrpt::maps::CMultiMetricMap)
26  * See `mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile()` as an
27  * easy way of initialize this object, or
28  * construct with the factory methods `<metric_map_class>::MapDefinition()`
29  * and `TMetricMapInitializer::factory()`
30  *
31  * \sa TSetOfMetricMapInitializers, mrpt::maps::CMultiMetricMap
32  * \ingroup mrpt_obs_grp
33  */
35 {
37  /** Smart pointer to TMetricMapInitializer */
38  using Ptr = std::shared_ptr<TMetricMapInitializer>;
39 
40  /** Common params for all maps: These are automatically set in
41  * TMetricMapTypesRegistry::factoryMapObjectFromDefinition() */
43 
44  /** Load all params from a config file/source. For examples and format, read
45  * the docs of mrpt::maps::CMultiMetricMap
46  * Typical section names:
47  * - `<sectionNamePrefix>_creationOpts`
48  * - `<sectionNamePrefix>_insertOpts`
49  * - `<sectionNamePrefix>_likelihoodOpts`
50  */
51  void loadFromConfigFile(
53  const std::string& sectionNamePrefix) override; // See base docs
54  void saveToConfigFile(
56  const std::string& section) const override;
57  void dumpToTextStream(std::ostream& out) const override; // See base docs
58 
59  /** Query the map type (C++ class), as set by the factory method
60  * MapDefinition() */
62  {
63  return metricMapClassType;
64  }
65 
66  /** Looks up in the registry of known map types and call the corresponding
67  * `<metric_map_class>::MapDefinition()`. */
68  static TMetricMapInitializer* factory(const std::string& mapClassName);
69 
70  protected:
72  /** Derived classes set this to CLASS_ID(< class >) where < class > is any
73  * CMetricMap derived class. */
75 
76  /** Load all map-specific params*/
79  const std::string& sectionNamePrefix) = 0;
80  virtual void dumpToTextStream_map_specific(std::ostream& out) const = 0;
81 }; // end TMetricMapInitializer
82 
83 /** A set of TMetricMapInitializer structures, passed to the constructor
84  * CMultiMetricMap::CMultiMetricMap
85  * See the comments for TSetOfMetricMapInitializers::loadFromConfigFile, and
86  * "CMultiMetricMap::setListOfMaps" for
87  * effectively creating the list of desired maps.
88  * \sa CMultiMetricMap::CMultiMetricMap, CLoadableOptions
89  * \ingroup mrpt_obs_grp
90  */
92 {
93  protected:
94  std::deque<TMetricMapInitializer::Ptr> m_list;
95 
96  public:
98  template <typename MAP_DEFINITION>
99  void push_back(const MAP_DEFINITION& o)
100  {
101  m_list.push_back(TMetricMapInitializer::Ptr(new MAP_DEFINITION(o)));
102  }
103 
104  void push_back(const TMetricMapInitializer::Ptr& o) { m_list.push_back(o); }
105  size_t size() const { return m_list.size(); }
107  using const_iterator =
109  iterator begin() { return m_list.begin(); }
110  iterator end() { return m_list.end(); }
111  const_iterator begin() const { return m_list.begin(); }
112  const_iterator end() const { return m_list.end(); }
113  void clear() { m_list.clear(); }
114  /** Loads the configuration for the set of internal maps from a textual
115  *definition in an INI-like file.
116  * The format of the ini file is defined in CConfigFile. The list
117  *of maps and their options
118  * will be loaded from a handle of sections:
119  *
120  * \code
121  * [<sectionName>]
122  * // Creation of maps:
123  * occupancyGrid_count=<Number of mrpt::maps::COccupancyGridMap2D maps>
124  * octoMap_count=<Number of mrpt::maps::COctoMap maps>
125  * colourOctoMap_count=<Number of mrpt::slam::CColourOctoMap maps>
126  * gasGrid_count=<Number of mrpt::maps::CGasConcentrationGridMap2D maps>
127  * wifiGrid_count=<Number of mrpt::maps::CWirelessPowerGridMap2D maps>
128  * landmarksMap_count=<0 or 1, for creating a mrpt::maps::CLandmarksMap
129  *map>
130  * beaconMap_count=<0 or 1, for creating a mrpt::maps::CBeaconMap map>
131  * pointsMap_count=<Number of mrpt::maps::CSimplePointsMap map>
132  * heightMap_count=<Number of mrpt::maps::CHeightGridMap2D maps>
133  * reflectivityMap_count=<Number of mrpt::maps::CReflectivityGridMap2D
134  *maps>
135  * colourPointsMap_count=<0 or 1, for creating a
136  *mrpt::maps::CColouredPointsMap map>
137  * weightedPointsMap_count=<0 or 1, for creating a
138  *mrpt::maps::CWeightedPointsMap map>
139  *
140  * // ====================================================
141  * // Creation Options for OccupancyGridMap ##:
142  * [<sectionName>+"_occupancyGrid_##_creationOpts"]
143  * min_x=<value>
144  * max_x=<value>
145  * min_y=<value>
146  * max_y=<value>
147  * resolution=<value>
148  * # Common params for all maps:
149  * #enableSaveAs3DObject = {true|false}
150  * #enableObservationLikelihood = {true|false}
151  * #enableObservationInsertion = {true|false}
152  *
153  * // Insertion Options for OccupancyGridMap ##:
154  * [<sectionName>+"_occupancyGrid_##_insertOpts"]
155  * <See COccupancyGridMap2D::TInsertionOptions>
156  *
157  * // Likelihood Options for OccupancyGridMap ##:
158  * [<sectionName>+"_occupancyGrid_##_likelihoodOpts"]
159  * <See COccupancyGridMap2D::TLikelihoodOptions>
160  *
161  * // ====================================================
162  * // Creation Options for OctoMap ##:
163  * [<sectionName>+"_octoMap_##_creationOpts"]
164  * resolution=<value>
165  *
166  * // Insertion Options for OctoMap ##:
167  * [<sectionName>+"_octoMap_##_insertOpts"]
168  * <See COctoMap::TInsertionOptions>
169  *
170  * // Likelihood Options for OctoMap ##:
171  * [<sectionName>+"_octoMap_##_likelihoodOpts"]
172  * <See COctoMap::TLikelihoodOptions>
173  *
174  * // ====================================================
175  * // Creation Options for ColourOctoMap ##:
176  * [<sectionName>+"_colourOctoMap_##_creationOpts"]
177  * resolution=<value>
178  *
179  * // Insertion Options for ColourOctoMap ##:
180  * [<sectionName>+"_colourOctoMap_##_insertOpts"]
181  * <See CColourOctoMap::TInsertionOptions>
182  *
183  * // Likelihood Options for ColourOctoMap ##:
184  * [<sectionName>+"_colourOctoMap_##_likelihoodOpts"]
185  * <See CColourOctoMap::TLikelihoodOptions>
186  *
187  *
188  * // ====================================================
189  * // Insertion Options for mrpt::maps::CSimplePointsMap ##:
190  * [<sectionName>+"_pointsMap_##_insertOpts"]
191  * <See CPointsMap::TInsertionOptions>
192  *
193  * // Likelihood Options for mrpt::maps::CSimplePointsMap ##:
194  * [<sectionName>+"_pointsMap_##_likelihoodOpts"]
195  * <See CPointsMap::TLikelihoodOptions>
196  *
197  *
198  * // ====================================================
199  * // Creation Options for CGasConcentrationGridMap2D ##:
200  * [<sectionName>+"_gasGrid_##_creationOpts"]
201  * mapType= <0-1> ; See
202  *CGasConcentrationGridMap2D::CGasConcentrationGridMap2D
203  * min_x=<value>
204  * max_x=<value>
205  * min_y=<value>
206  * max_y=<value>
207  * resolution=<value>
208  *
209  * // Insertion Options for CGasConcentrationGridMap2D ##:
210  * [<sectionName>+"_gasGrid_##_insertOpts"]
211  * <See CGasConcentrationGridMap2D::TInsertionOptions>
212  *
213  * // ====================================================
214  * // Creation Options for CWirelessPowerGridMap2D ##:
215  * [<sectionName>+"_wifiGrid_##_creationOpts"]
216  * mapType= <0-1> ; See CWirelessPowerGridMap2D::CWirelessPowerGridMap2D
217  * min_x=<value>
218  * max_x=<value>
219  * min_y=<value>
220  * max_y=<value>
221  * resolution=<value>
222  *
223  * // Insertion Options for CWirelessPowerGridMap2D ##:
224  * [<sectionName>+"_wifiGrid_##_insertOpts"]
225  * <See CWirelessPowerGridMap2D::TInsertionOptions>
226  *
227  *
228  * // ====================================================
229  * // Creation Options for CLandmarksMap ##:
230  * [<sectionName>+"_landmarksMap_##_creationOpts"]
231  * nBeacons=<# of beacons>
232  * beacon_001_ID=67 ; The ID and 3D coordinates of each beacon
233  * beacon_001_X=<x>
234  * beacon_001_Y=<x>
235  * beacon_001_Z=<x>
236  *
237  * // Insertion Options for CLandmarksMap ##:
238  * [<sectionName>+"_landmarksMap_##_insertOpts"]
239  * <See CLandmarksMap::TInsertionOptions>
240  *
241  * // Likelihood Options for CLandmarksMap ##:
242  * [<sectionName>+"_landmarksMap_##_likelihoodOpts"]
243  * <See CLandmarksMap::TLikelihoodOptions>
244  *
245  *
246  * // ====================================================
247  * // Insertion Options for CBeaconMap ##:
248  * [<sectionName>+"_beaconMap_##_insertOpts"]
249  * <See CBeaconMap::TInsertionOptions>
250  *
251  * // Likelihood Options for CBeaconMap ##:
252  * [<sectionName>+"_beaconMap_##_likelihoodOpts"]
253  * <See CBeaconMap::TLikelihoodOptions>
254  *
255  * // ====================================================
256  * // Creation Options for HeightGridMap ##:
257  * [<sectionName>+"_heightGrid_##_creationOpts"]
258  * mapType= <0-1> // See CHeightGridMap2D::CHeightGridMap2D
259  * min_x=<value>
260  * max_x=<value>
261  * min_y=<value>
262  * max_y=<value>
263  * resolution=<value>
264  *
265  * // Insertion Options for HeightGridMap ##:
266  * [<sectionName>+"_heightGrid_##_insertOpts"]
267  * <See CHeightGridMap2D::TInsertionOptions>
268  *
269  *
270  * // ====================================================
271  * // Creation Options for ReflectivityGridMap ##:
272  * [<sectionName>+"_reflectivityMap_##_creationOpts"]
273  * min_x=<value> // See CReflectivityGridMap2D::CReflectivityGridMap2D
274  * max_x=<value>
275  * min_y=<value>
276  * max_y=<value>
277  * resolution=<value>
278  *
279  * // Insertion Options for HeightGridMap ##:
280  * [<sectionName>+"_reflectivityMap_##_insertOpts"]
281  * <See CReflectivityGridMap2D::TInsertionOptions>
282  *
283  *
284  * // ====================================================
285  * // Insertion Options for CColouredPointsMap ##:
286  * [<sectionName>+"_colourPointsMap_##_insertOpts"]
287  * <See CPointsMap::TInsertionOptions>
288  *
289  *
290  * // Color Options for CColouredPointsMap ##:
291  * [<sectionName>+"_colourPointsMap_##_colorOpts"]
292  * <See CColouredPointsMap::TColourOptions>
293  *
294  * // Likelihood Options for mrpt::maps::CSimplePointsMap ##:
295  * [<sectionName>+"_colourPointsMap_##_likelihoodOpts"]
296  * <See CPointsMap::TLikelihoodOptions>
297  *
298  *
299  * // ====================================================
300  * // Insertion Options for CWeightedPointsMap ##:
301  * [<sectionName>+"_weightedPointsMap_##_insertOpts"]
302  * <See CPointsMap::TInsertionOptions>
303  *
304  *
305  * // Likelihood Options for CWeightedPointsMap ##:
306  * [<sectionName>+"_weightedPointsMap_##_likelihoodOpts"]
307  * <See CPointsMap::TLikelihoodOptions>
308  *
309  * \endcode
310  *
311  * Where:
312  * - ##: Represents the index of the map (e.g. "00","01",...)
313  * - By default, the variables into each "TOptions" structure of the
314  *maps
315  *are defined in textual form by the same name of the corresponding C++
316  *variable (e.g. "float resolution;" -> "resolution=0.10")
317  *
318  * \note Examples of map definitions can be found in the '.ini' files
319  *provided in the demo directories: "share/mrpt/config-files/"
320  */
321  void loadFromConfigFile(
323  const std::string& sectionName) override;
324  void saveToConfigFile(
326  const std::string& section) const override;
327  /** This method dumps the options of the multi-metric map AND those of every
328  * internal map. */
329  void dumpToTextStream(std::ostream& out) const override;
330 };
331 
332 } // namespace maps
333 } // namespace mrpt
CObject.h
mrpt::maps::TMetricMapInitializer::saveToConfigFile
void saveToConfigFile(mrpt::config::CConfigFileBase &target, const std::string &section) const override
This method saves the options to a ".ini"-like file or memory-stored string list.
Definition: TMetricMapInitializer.cpp:51
mrpt::maps::TSetOfMetricMapInitializers::size
size_t size() const
Definition: TMetricMapInitializer.h:105
const_iterator
const Scalar * const_iterator
Definition: eigen_plugins.h:27
mrpt::maps::TMetricMapInitializer::metricMapClassType
const mrpt::rtti::TRuntimeClassId::Ptr metricMapClassType
Derived classes set this to CLASS_ID(< class >) where < class > is any CMetricMap derived class.
Definition: TMetricMapInitializer.h:74
mrpt::rtti::TRuntimeClassId
A structure that holds runtime class type information.
Definition: CObject.h:30
mrpt::maps::TMetricMapInitializer::TMetricMapInitializer
TMetricMapInitializer(const mrpt::rtti::TRuntimeClassId *classID)
Definition: TMetricMapInitializer.cpp:30
mrpt::maps::TMetricMapInitializer::dumpToTextStream_map_specific
virtual void dumpToTextStream_map_specific(std::ostream &out) const =0
mrpt::maps::TSetOfMetricMapInitializers::begin
iterator begin()
Definition: TMetricMapInitializer.h:109
mrpt::maps::TSetOfMetricMapInitializers::const_iterator
std::deque< TMetricMapInitializer::Ptr >::const_iterator const_iterator
Definition: TMetricMapInitializer.h:108
mrpt::maps::TSetOfMetricMapInitializers::begin
const_iterator begin() const
Definition: TMetricMapInitializer.h:111
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::maps::TMetricMapInitializer
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
Definition: TMetricMapInitializer.h:34
mrpt::maps::TMapGenericParams
Common params to all maps derived from mrpt::maps::CMetricMap
Definition: metric_map_types.h:88
mrpt::maps::TMetricMapInitializer::genericMapParams
mrpt::maps::TMapGenericParams genericMapParams
Common params for all maps: These are automatically set in TMetricMapTypesRegistry::factoryMapObjectF...
Definition: TMetricMapInitializer.h:42
mrpt::maps::TMetricMapInitializer::dumpToTextStream
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
Definition: TMetricMapInitializer.cpp:59
mrpt::maps::TSetOfMetricMapInitializers::end
const_iterator end() const
Definition: TMetricMapInitializer.h:112
source
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
mrpt::maps::TSetOfMetricMapInitializers
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Definition: TMetricMapInitializer.h:91
mrpt::maps::TMetricMapInitializer::factory
static TMetricMapInitializer * factory(const std::string &mapClassName)
Looks up in the registry of known map types and call the corresponding <metric_map_class>::MapDefinit...
Definition: TMetricMapInitializer.cpp:22
TMetricMapTypesRegistry.h
mrpt::maps::TMetricMapInitializer::Ptr
std::shared_ptr< TMetricMapInitializer > Ptr
Smart pointer to TMetricMapInitializer.
Definition: TMetricMapInitializer.h:38
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::maps::TSetOfMetricMapInitializers::TSetOfMetricMapInitializers
TSetOfMetricMapInitializers()
Definition: TMetricMapInitializer.h:97
mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &sectionName) override
Loads the configuration for the set of internal maps from a textual definition in an INI-like file.
Definition: TMetricMapInitializer.cpp:69
mrpt::config::CLoadableOptions
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Definition: config/CLoadableOptions.h:28
mrpt::maps::TSetOfMetricMapInitializers::m_list
std::deque< TMetricMapInitializer::Ptr > m_list
Definition: TMetricMapInitializer.h:94
CLoadableOptions.h
mrpt::maps::TSetOfMetricMapInitializers::saveToConfigFile
void saveToConfigFile(mrpt::config::CConfigFileBase &target, const std::string &section) const override
This method saves the options to a ".ini"-like file or memory-stored string list.
Definition: TMetricMapInitializer.cpp:117
mrpt::maps::TSetOfMetricMapInitializers::iterator
std::deque< TMetricMapInitializer::Ptr >::iterator iterator
Definition: TMetricMapInitializer.h:106
mrpt::maps::TSetOfMetricMapInitializers::push_back
void push_back(const MAP_DEFINITION &o)
Definition: TMetricMapInitializer.h:99
mrpt::maps::TMetricMapInitializer::loadFromConfigFile_map_specific
virtual void loadFromConfigFile_map_specific(const mrpt::config::CConfigFileBase &source, const std::string &sectionNamePrefix)=0
Load all map-specific params.
metric_map_types.h
mrpt::maps::TMetricMapInitializer::getMetricMapClassType
const mrpt::rtti::TRuntimeClassId::Ptr & getMetricMapClassType() const
Query the map type (C++ class), as set by the factory method MapDefinition()
Definition: TMetricMapInitializer.h:61
string
GLsizei const GLchar ** string
Definition: glext.h:4101
iterator
Scalar * iterator
Definition: eigen_plugins.h:26
mrpt::maps::TSetOfMetricMapInitializers::dumpToTextStream
void dumpToTextStream(std::ostream &out) const override
This method dumps the options of the multi-metric map AND those of every internal map.
Definition: TMetricMapInitializer.cpp:125
mrpt::maps::TSetOfMetricMapInitializers::end
iterator end()
Definition: TMetricMapInitializer.h:110
mrpt::maps::TMetricMapInitializer::loadFromConfigFile
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &sectionNamePrefix) override
Load all params from a config file/source.
Definition: TMetricMapInitializer.cpp:38
mrpt::maps::TSetOfMetricMapInitializers::push_back
void push_back(const TMetricMapInitializer::Ptr &o)
Definition: TMetricMapInitializer.h:104
mrpt::maps::TSetOfMetricMapInitializers::clear
void clear()
Definition: TMetricMapInitializer.h:113
mrpt::safe_ptr
A wrapper class for pointers that can be safely copied with "=" operator without problems.
Definition: safe_pointers.h:71



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST