The hierarchical model of metric maps
1. About maps in the MRPT
All metric maps have a common interface to ease polymorphism and generic programming. To see these common methods, refer to the C++ class CMetricMap. All the map classes are within the namespace mrpt::slam, which is omitted here for readability.
See also the documentation of the library mrpt-maps.
To ease even more the implementation of generic algorithms, there exists one very important kind of map, the multi-metric map.
This class offers the interface of a normal metric map, but it holds internally an arbitrary number of other metric maps.
To realize of the power and simplicity of this approach, imagine programming a method which insert scans from 3 laser range finders into a 3D point map (so, a point cloud is built incrementally).
By just replacing the point map by a multi-metric map, we can now build the point cloud and, at our choice, three occupancy grid maps, once for each height. The original code would need no changes at all.
This is the reason of calling the MRPT map model “hierarchical”, in the sense that one map (the “multi-metric map”) propagates all the calls to the “child maps”.
2. The maps
2.1. The generic map container: “Multi-metric map”
See the reference for CMultiMetricMap.
2.2. Beacon maps
A map of 3D beacons with an ID, used for range-only localization and SLAM.
See the reference for CBeaconMap.
2.3. 2D gas concentration maps
A planar lattice of gas concentrations, used for gas concentration mapping.
See the reference for CGasConcentrationGridMap2D.
2.4. 2D Height (or elevation) maps
A lattice where each cells keep the average elevation (”z” coordinate) of the points sensed within its square area.
See the reference for CHeightGridMap2D.
2.5. Landmark maps
A set of 3D landmarks with IDs and a 3D Gaussian distribution for its position. Used mainly for visual SLAM.
See the reference for CLandmarksMap.
2.6. Occupancy grid maps
A planar occupancy grid map. See this page for more details on its implementation and offered operations. It is used in many SLAM and particle filter-based localization programs.
See the reference for COccupancyGridMap2D.
2.7. Point maps
A virtual class for maps of 2D or 3D points. It implements efficient look-up methods based on KD-trees (see CPointsMap::kdTreeClosestPoint3D).
Point maps use mrpt::math::KDTreeCapable to provide efficient KDTree-based search of points in either 2D or 3D. There are plans to also implement QuadTrees and OctTrees.
See the reference for CPointsMap.
2.7.1. Simple point maps
A type of point map where each point only have (x,y,z) coordinates.
See the reference for CSimplePointsMap.
2.7.2. Colored point maps
A type of point map where each point have (x,y,z) coordinates, plus RGB color data.
See the reference for CColouredPointsMap.
3. Configuration block for a multi-metric map
Typically, all the parameters to configure a multi-metric map can be loaded from a INI-like configuration file
(or any other textual input, such as an input box in a GUI). Of course, they can be also hard-coded.
The key structure here is TSetOfMetricMapInitializers.
The format of the configuration files will be always explained and up-to-date in TSetOfMetricMapInitializers::loadFromConfigFile.
For practical examples, refer to the .ini files in MRPT/share/mrpt/config_files/*-slam
[Examples for icp-slam, rbpf-slam].
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 |
/** Loads the configuration for the set of internal maps from a textual definition in an INI-like file. * The format of the ini file is defined in utils::CConfigFile. The list of maps and their options * will be loaded from a handle of sections: * * \code * [] * ; Creation of maps: * occupancyGrid_count= * gasGrid_count= * landmarksMap_count= * beaconMap_count= * pointsMap_count= * heightMap_count= * colourPointsMap_count= * * ; Selection of map for likelihood: (fuseAll=-1, occGrid=0, points=1,landmarks=2,gasGrid=3,4=landmarks SOG, 5=beacon map, 6=height map) * likelihoodMapSelection=[-1, 6] * * ; Enables (1) / Disables (0) insertion into specific maps: * enableInsertion_pointsMap= * enableInsertion_landmarksMap= * enableInsertion_gridMaps= * enableInsertion_gasGridMaps= * enableInsertion_beaconMap= * enableInsertion_heightMap= * enableInsertion_colourPointsMap= * * ; Creation Options for OccupancyGridMap ##: * [+"_occupancyGrid_##_creationOpts"] * min_x= * max_x= * min_y= * max_y= * resolution= * * ; Insertion Options for OccupancyGridMap ##: * [+"_occupancyGrid_##_insertOpts"] * * * ; Likelihood Options for OccupancyGridMap ##: * [+"_occupancyGrid_##_likelihoodOpts"] * * * * * ; Insertion Options for CSimplePointsMap ##: * [+"_pointsMap_##_insertOpts"] * * * * ; Creation Options for CGasConcentrationGridMap2D ##: * [+"_gasGrid_##_creationOpts"] * mapType= ; See CGasConcentrationGridMap2D::CGasConcentrationGridMap2D * min_x= * max_x= * min_y= * max_y= * resolution= * * ; Insertion Options for CGasConcentrationGridMap2D ##: * [+"_gasGrid_##_insertOpts"] * * * * ; Creation Options for CLandmarksMap ##: * [+"_landmarksMap_##_creationOpts"] * nBeacons= * beacon_001_ID=67 ; The ID and 3D coordinates of each beacon * beacon_001_X= * beacon_001_Y= * beacon_001_Z= * * ; Insertion Options for CLandmarksMap ##: * [+"_landmarksMap_##_insertOpts"] * * * ; Likelihood Options for CLandmarksMap ##: * [+"_landmarksMap_##_likelihoodOpts"] * * * * ; Insertion Options for CBeaconMap ##: * [+"_beaconMap_##_insertOpts"] * * * ; Likelihood Options for CBeaconMap ##: * [+"_beaconMap_##_likelihoodOpts"] * * * ; Creation Options for HeightGridMap ##: * [+"_heightGrid_##_creationOpts"] * mapType= ; See CHeightGridMap2D::CHeightGridMap2D * min_x= * max_x= * min_y= * max_y= * resolution= * * ; Insertion Options for HeightGridMap ##: * [+"_heightGrid_##_insertOpts"] * * * * ; Insertion Options for CColouredPointsMap ##: * [+"_colourPointsMap_##_insertOpts"] * * * * ; Color Options for CColouredPointsMap ##: * [+"_colourPointsMap_##_colorOpts"] * * * * \endcode * * Where: * - ##: Represents the index of the map (e.g. "00","01",...) * - 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") */ void loadFromConfigFile( const mrpt::utils::CConfigFileBase &source, const std::string &sectionName); |