Class CMultiMetricMap
Defined in File CMultiMetricMap.h
Inheritance Relationships
Base Type
public mrpt::maps::CMetricMap
Class Documentation
-
class CMultiMetricMap : public mrpt::maps::CMetricMap
This class stores any customizable set of metric maps. The internal metric maps can be accessed directly by the user as smart pointers with CMultiMetricMap::mapByIndex() or via
iterators. The utility of this container is to operate on several maps simultaneously: update them by inserting observations, evaluate the likelihood of one observation by fusing (multiplying) the likelihoods over the different maps, etc.These kinds of metric maps can be kept inside (list may be incomplete, refer to classes derived from mrpt::maps::CMetricMap):
mrpt::maps::CSimplePointsMap: For 2D or 3D range scans, …
mrpt::maps::COccupancyGridMap2D: 2D, horizontal laser range scans, at different altitudes.
mrpt::maps::COccupancyGridMap3D: 3D occupancy voxel map.
mrpt::maps::COctoMap: For 3D occupancy grids of variable resolution, with octrees (based on the library
octomap).
mrpt::maps::CVoxelMap or mrpt::maps::CVoxelMapRGB: 3D sparse voxel maps.
mrpt::maps::CColouredOctoMap: The same than above, but nodes can store RGB data appart from occupancy.
mrpt::maps::CLandmarksMap: For visual landmarks,etc…
mrpt::maps::CGasConcentrationGridMap2D: For gas concentration maps.
mrpt::maps::CWirelessPowerGridMap2D: For wifi power maps.
mrpt::maps::CBeaconMap: For range-only SLAM.
mrpt::maps::CHeightGridMap2D: For elevation maps of height for each (x,y) location (Digital elevation model, DEM)
mrpt::maps::CHeightGridMap2D_MRF: DEMs as Markov Random Field (MRF)
mrpt::maps::CReflectivityGridMap2D: For maps of “reflectivity” for each (x,y) location.
mrpt::maps::CGenericPointsMap: For point clouds with arbitrary fields.
See CMultiMetricMap::setListOfMaps() for the method for initializing this class programmatically. See also TSetOfMetricMapInitializers::loadFromConfigFile for a template of “.ini”-like configuration file that can be used to define which maps to create and all their parameters. Alternatively, the list of maps is public so it can be directly manipulated/accessed in CMultiMetricMap::maps
Access to list of maps
-
using TListMaps = std::deque<mrpt::maps::CMetricMap::Ptr>
-
TListMaps maps
The list of metric maps in this object. Use dynamic_cast or smart pointer-based downcast to access maps by their actual type. You can directly manipulate this list. Helper methods to initialize it are described in the docs of CMultiMetricMap
-
inline const_iterator begin() const
-
inline const_iterator end() const
-
mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const
Gets the i-th map
- Throws:
std::runtime_error – On out-of-bounds
-
template<typename T>
inline T::Ptr mapByClass(size_t ith = 0) const Returns the i’th map of a given class (or of a derived class), or empty smart pointer if there is no such map. Example:
By default (ith=0), the first match is returned.COccupancyGridMap2D::Ptr obs = multimap.mapByClass<COccupancyGridMap2D>();
-
template<typename T>
inline std::size_t countMapsByClass() const Count how many maps exist of the given class (or derived class)
Public Functions
-
CMultiMetricMap() = default
Default ctor: empty list of maps
-
CMultiMetricMap(const TSetOfMetricMapInitializers &initializers)
Constructor with a list of map initializers.
- Parameters:
initializers – One internal map will be created for each entry in this “TSetOfMetricMapInitializers” struct.
-
CMultiMetricMap(const CMultiMetricMap &o)
Creates a deep copy
-
CMultiMetricMap &operator=(const CMultiMetricMap &o)
Creates a deep copy
-
CMultiMetricMap(CMultiMetricMap&&) = default
Move ctor
-
CMultiMetricMap &operator=(CMultiMetricMap&&) = default
Move operator
-
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &init)
Sets the list of internal map according to the passed list of map initializers (current maps will be deleted)
-
void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const mrpt::maps::TMatchingParams ¶ms, mrpt::maps::TMatchingExtraResults &extraResults) const override
-
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const override
-
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
-
void auxParticleFilterCleanUp() override
-
void getVisualizationInto(mrpt::viz::CSetOfObjects &outObj) const override
-
const mrpt::maps::CSimplePointsMap *getAsSimplePointsMap() const override
-
std::string asString() const override
Returns a short description of the map.