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



Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020