Class CMetricMap
Defined in File CMetricMap.h
Inheritance Relationships
Base Types
public mrpt::serialization::CSerializablepublic mrpt::system::CObservablepublic mrpt::Stringifyablepublic mrpt::viz::Visualizable
Class Documentation
-
class CMetricMap : public mrpt::serialization::CSerializable, public mrpt::system::CObservable, public mrpt::Stringifyable, public mrpt::viz::Visualizable
Declares a virtual base class for all metric maps storage classes. In this class virtual methods are provided to allow the insertion of any type of “CObservation” objects into the metric map, thus updating the map (doesn’t matter if it is a 2D/3D grid, a point map, etc.).
Observations don’t include any information about the robot pose, just the raw observation and information about the sensor pose relative to the robot mobile base coordinates origin.
Note that all metric maps implement this mrpt::system::CObservable interface, emitting the following events:
mrpt::obs::mrptEventMetricMapClear: Upon call of the ::clear() method.
mrpt::obs::mrptEventMetricMapInsert: Upon insertion of an observation that effectively modifies the map (e.g. inserting an image into a grid map will NOT raise an event, inserting a laser scan will).
To check what observations are supported by each metric map, see maps_observations.
See also
CObservation, CSensoryFrame, CMultiMetricMap
Note
All derived class must implement a static class factory
<metric_map_class>::MapDefinition()that builds a default TMetricMapInitializerPublic Functions
-
void clear()
Erase all the contents of the map
-
virtual bool isEmpty() const = 0
Returns true if the map is empty/no observation has been inserted.
-
inline virtual auto boundingBox() const -> mrpt::math::TBoundingBoxf
Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the default value of mrpt::math::TBoundingBoxf() if not implemented in the derived class or the map is empty.
-
void loadFromSimpleMap(const mrpt::maps::CSimpleMap &Map)
Load the map contents from a CSimpleMap object, erasing all previous content of the map. This is done invoking
insertObservation()for each observation at the mean 3D robot pose of each pose-observations pair in the CSimpleMap object.See also
- Throws:
std::exception – Some internal steps in invoked methods can raise exceptions on invalid parameters, etc…
-
bool insertObservation(const mrpt::obs::CObservation &obs, const std::optional<const mrpt::poses::CPose3D> &robotPose = std::nullopt)
Insert the observation information into this map. This method must be implemented in derived classes. See: maps_observations
See also
CObservation::insertObservationInto
- Parameters:
obs – The observation
robotPose – The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.
-
bool insertObservationPtr(const mrpt::obs::CObservation::Ptr &obs, const std::optional<const mrpt::poses::CPose3D> &robotPose = std::nullopt)
A wrapper for smart pointers, just calls the non-smart pointer version. See: maps_observations
-
double computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) const
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose. See: maps_observations
See also
Used in particle filter algorithms, see: CMultiMetricMapPDF::update
- Parameters:
takenFrom – The robot’s pose the observation is supposed to be taken from.
obs – The observation.
- Returns:
This method returns a log-likelihood.
-
virtual bool canComputeObservationLikelihood(const mrpt::obs::CObservation &obs) const
Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image). See: maps_observations
See also
computeObservationLikelihood, genericMapParams.enableObservationLikelihood
- Parameters:
obs – The observation.
-
double computeObservationsLikelihood(const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose3D &takenFrom)
Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame. See: maps_observations
See also
- Parameters:
takenFrom – The robot’s pose the observation is supposed to be taken from.
sf – The set of observations in a CSensoryFrame.
- Returns:
This method returns a log-likelihood.
-
bool canComputeObservationsLikelihood(const mrpt::obs::CSensoryFrame &sf) const
Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image). See: maps_observations
See also
- Parameters:
sf – The observations.
-
CMetricMap()
Constructor
-
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const
Computes the matching between this and another 2D point map, which includes finding:
The set of points pairs in each map
The mean squared distance between corresponding pairs.
The algorithm is:
For each point in “otherMap”:
Transform the point according to otherMapPose
Search with a KD-TREE the closest correspondences in “this” map.
Add to the set of candidate matchings, if it passes all the thresholds in params.
This method is the most time critical one into ICP-like algorithms.
See also
- Parameters:
otherMap – [IN] The other map to compute the matching with.
otherMapPose – [IN] The pose of the other map as seen from “this”.
params – [IN] Parameters for the determination of pairings.
correspondences – [OUT] The detected matchings pairs.
extraResults – [OUT] Other results.
-
virtual void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const
Computes the matchings between this and another 3D points map - method used in 3D-ICP. This method finds the set of point pairs in each map.
The method is the most time critical one into ICP-like algorithms.
The algorithm is:
For each point in “otherMap”:
Transform the point according to otherMapPose
Search with a KD-TREE the closest correspondences in “this” map.
Add to the set of candidate matchings, if it passes all the thresholds in params.
See also
- Parameters:
otherMap – [IN] The other map to compute the matching with.
otherMapPose – [IN] The pose of the other map as seen from “this”.
params – [IN] Parameters for the determination of pairings.
correspondences – [OUT] The detected matchings pairs.
extraResults – [OUT] Other results.
-
virtual float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const
Computes the ratio in [0,1] of correspondences between “this” and the “otherMap” map, whose 6D pose relative to “this” is “otherMapPose” In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps.
See also
- Parameters:
otherMap – [IN] The other map to compute the matching with.
otherMapPose – [IN] The 6D pose of the other map as seen from “this”.
params – [IN] Matching parameters
- Returns:
The matching ratio [0,1]
-
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const = 0
This virtual method saves the map to a file “filNamePrefix”+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).
-
inline virtual void auxParticleFilterCleanUp()
This method is called at the end of each “prediction-update-map
insertion” cycle within “mrpt::slam::CMetricMapBuilderRBPF::processActionObservation”. This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.
-
virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const
Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.
-
inline virtual const mrpt::maps::CSimplePointsMap *getAsSimplePointsMap() const
If the map is a simple points map or it’s a multi-metric map that contains EXACTLY one simple points map, return it. Otherwise, return nullptr
-
inline mrpt::maps::CSimplePointsMap *getAsSimplePointsMap()
Public Members
-
TMapGenericParams genericMapParams
Common params to all maps