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



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