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



Page generated by Doxygen 1.8.12 for MRPT 1.3.2 SVN: at Thu Nov 10 13:46:27 UTC 2016