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



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020