Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Public Member Functions | Public Attributes | Protected Member Functions | Private Member Functions | Private Attributes
mrpt::maps::CMetricMap Class Referenceabstract

Detailed Description

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::utils::CObservable interface, emitting the following events:

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).

Checkout each derived class documentation to learn which mrpt::obs::CObservation-derived classes are supported by CMetricMap::insertObservation()

Note
All derived class must implement a static class factory <metric_map_class>::MapDefinition() that builds a default TMetricMapInitializer [New in MRPT 1.3.0]
See also
CObservation, CSensoryFrame, CMultiMetricMap

Definition at line 52 of file maps/CMetricMap.h.

#include <mrpt/maps/CMetricMap.h>

Inheritance diagram for mrpt::maps::CMetricMap:
Inheritance graph

Public Member 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.
 
void loadFromProbabilisticPosesAndObservations (const mrpt::maps::CSimpleMap &Map)
 Load the map contents from a CSimpleMap object, erasing all previous content of the map.
 
void loadFromSimpleMap (const mrpt::maps::CSimpleMap &Map)
 Load the map contents from a CSimpleMap object, erasing all previous content of the map.
 
bool insertObservation (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
 Insert the observation information into this map.
 
bool insertObservationPtr (const mrpt::obs::CObservationPtr &obs, const mrpt::poses::CPose3D *robotPose=NULL)
 A wrapper for smart pointers, just calls the non-smart pointer version.
 
double computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)
 Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
 
double computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
virtual bool canComputeObservationLikelihood (const mrpt::obs::CObservation *obs)
 Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.
 
bool canComputeObservationLikelihood (const mrpt::obs::CObservationPtr &obs)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
double computeObservationsLikelihood (const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose2D &takenFrom)
 Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.
 
bool canComputeObservationsLikelihood (const mrpt::obs::CSensoryFrame &sf)
 Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.
 
 CMetricMap ()
 Constructor.
 
virtual ~CMetricMap ()
 Destructor.
 
virtual void determineMatching2D (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
 Computes the matching between this and another 2D point map, which includes finding:
 
virtual void determineMatching3D (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
 Computes the matchings between this and another 3D points map - method used in 3D-ICP.
 
virtual float compute3DMatchingRatio (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) 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.
 
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).
 
virtual void getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const =0
 Returns a 3D object representing the map.
 
virtual void auxParticleFilterCleanUp ()
 This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
 
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.
 
virtual const mrpt::maps::CSimplePointsMapgetAsSimplePointsMap () 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.
 
virtual mrpt::maps::CSimplePointsMapgetAsSimplePointsMap ()
 

Public Attributes

TMapGenericParams genericMapParams
 Common params to all maps.
 

Protected Member Functions

void publishEvent (const mrptEvent &e) const
 Called when you want this object to emit an event to all the observers currently subscribed to this object.
 
bool hasSubscribers () const
 Can be called by a derived class before preparing an event for publishing with publishEvent to determine if there is no one subscribed, so it can save the wasted time preparing an event that will be not read.
 

Private Member Functions

virtual void internal_clear ()=0
 Internal method called by clear()
 
virtual bool internal_insertObservation (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)=0
 Internal method called by insertObservation()
 
virtual double internal_computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)=0
 Internal method called by computeObservationLikelihood()
 
virtual bool internal_canComputeObservationLikelihood (const mrpt::obs::CObservation *obs)
 Internal method called by canComputeObservationLikelihood()
 
virtual void OnPostSuccesfulInsertObs (const mrpt::obs::CObservation *)
 Hook for each time a "internal_insertObservation" returns "true" This is called automatically from insertObservation() when internal_insertObservation returns true.
 
void internal_observer_begin (CObserver *)
 
void internal_observer_end (CObserver *)
 

Private Attributes

std::set< CObserver * > m_subscribers
 

RTTI stuff <br>

static const mrpt::utils::TRuntimeClassId classCMetricMap
 
class mrpt::utils::CStream
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 

Constructor & Destructor Documentation

◆ CMetricMap()

mrpt::maps::CMetricMap::CMetricMap ( )

Constructor.

◆ ~CMetricMap()

virtual mrpt::maps::CMetricMap::~CMetricMap ( )
virtual

Destructor.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId * mrpt::maps::CMetricMap::_GetBaseClass ( )
staticprotected

◆ auxParticleFilterCleanUp()

virtual void mrpt::maps::CMetricMap::auxParticleFilterCleanUp ( )
inlinevirtual

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.

Reimplemented in mrpt::maps::CMultiMetricMap, and mrpt::maps::CLandmarksMap.

Definition at line 235 of file maps/CMetricMap.h.

◆ canComputeObservationLikelihood() [1/2]

virtual bool mrpt::maps::CMetricMap::canComputeObservationLikelihood ( const mrpt::obs::CObservation obs)
virtual

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).

Parameters
obsThe observation.
See also
computeObservationLikelihood, genericMapParams.enableObservationLikelihood

◆ canComputeObservationLikelihood() [2/2]

bool mrpt::maps::CMetricMap::canComputeObservationLikelihood ( const mrpt::obs::CObservationPtr obs)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ canComputeObservationsLikelihood()

bool mrpt::maps::CMetricMap::canComputeObservationsLikelihood ( const mrpt::obs::CSensoryFrame sf)

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).

Parameters
sfThe observations.
See also
canComputeObservationLikelihood

◆ clear()

void mrpt::maps::CMetricMap::clear ( )

Erase all the contents of the map.

Referenced by mrpt::maps::CRandomFieldGridMap2D::clear(), and mrpt::maps::CReflectivityGridMap2D::clear().

◆ compute3DMatchingRatio()

virtual float mrpt::maps::CMetricMap::compute3DMatchingRatio ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose3D otherMapPose,
const TMatchingRatioParams params 
) const
virtual

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.

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]
See also
determineMatching2D

Reimplemented in mrpt::maps::CBeaconMap, mrpt::maps::CHeightGridMap2D, mrpt::maps::COccupancyGridMap2D, mrpt::maps::CPointsMap, mrpt::maps::CRandomFieldGridMap2D, mrpt::maps::CReflectivityGridMap2D, mrpt::maps::CMultiMetricMap, and mrpt::maps::CLandmarksMap.

◆ computeObservationLikelihood() [1/2]

double mrpt::maps::CMetricMap::computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose2D takenFrom 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ computeObservationLikelihood() [2/2]

double mrpt::maps::CMetricMap::computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D takenFrom 
)

Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.

Parameters
takenFromThe robot's pose the observation is supposed to be taken from.
obsThe observation.
Returns
This method returns a log-likelihood.
See also
Used in particle filter algorithms, see: CMultiMetricMapPDF::update

◆ computeObservationsLikelihood()

double mrpt::maps::CMetricMap::computeObservationsLikelihood ( const mrpt::obs::CSensoryFrame sf,
const mrpt::poses::CPose2D takenFrom 
)

Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.

Parameters
takenFromThe robot's pose the observation is supposed to be taken from.
sfThe set of observations in a CSensoryFrame.
Returns
This method returns a log-likelihood.
See also
canComputeObservationsLikelihood

◆ determineMatching2D()

virtual void mrpt::maps::CMetricMap::determineMatching2D ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose2D otherMapPose,
mrpt::utils::TMatchingPairList correspondences,
const TMatchingParams params,
TMatchingExtraResults extraResults 
) const
virtual

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.

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.
See also
compute3DMatchingRatio

Reimplemented in mrpt::maps::CMultiMetricMap, mrpt::maps::CBeaconMap, mrpt::maps::COccupancyGridMap2D, and mrpt::maps::CPointsMap.

◆ determineMatching3D()

virtual void mrpt::maps::CMetricMap::determineMatching3D ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose3D otherMapPose,
mrpt::utils::TMatchingPairList correspondences,
const TMatchingParams params,
TMatchingExtraResults extraResults 
) const
virtual

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.
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.
See also
compute3DMatchingRatio

Reimplemented in mrpt::maps::CPointsMap.

◆ getAs3DObject()

virtual void mrpt::maps::CMetricMap::getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr outObj) const
pure virtual

◆ getAsSimplePointsMap() [1/2]

virtual mrpt::maps::CSimplePointsMap * mrpt::maps::CMetricMap::getAsSimplePointsMap ( )
inlinevirtual

◆ getAsSimplePointsMap() [2/2]

virtual const mrpt::maps::CSimplePointsMap * mrpt::maps::CMetricMap::getAsSimplePointsMap ( ) const
inlinevirtual

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 NULL

Reimplemented in mrpt::maps::CMultiMetricMap, mrpt::maps::CPointsMap, and mrpt::maps::CSimplePointsMap.

Definition at line 243 of file maps/CMetricMap.h.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId * mrpt::maps::CMetricMap::GetRuntimeClass ( ) const
virtual

◆ hasSubscribers()

bool mrpt::utils::CObservable::hasSubscribers ( ) const
inlineprotectedinherited

Can be called by a derived class before preparing an event for publishing with publishEvent to determine if there is no one subscribed, so it can save the wasted time preparing an event that will be not read.

Definition at line 52 of file CObservable.h.

◆ insertObservation()

bool mrpt::maps::CMetricMap::insertObservation ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D robotPose = NULL 
)

Insert the observation information into this map.

This method must be implemented in derived classes.

Parameters
obsThe observation
robotPoseThe 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.
See also
CObservation::insertObservationInto

◆ insertObservationPtr()

bool mrpt::maps::CMetricMap::insertObservationPtr ( const mrpt::obs::CObservationPtr obs,
const mrpt::poses::CPose3D robotPose = NULL 
)

A wrapper for smart pointers, just calls the non-smart pointer version.

◆ internal_canComputeObservationLikelihood()

virtual bool mrpt::maps::CMetricMap::internal_canComputeObservationLikelihood ( const mrpt::obs::CObservation obs)
inlineprivatevirtual

Internal method called by canComputeObservationLikelihood()

Reimplemented in mrpt::maps::CMultiMetricMap, and mrpt::maps::COccupancyGridMap2D.

Definition at line 71 of file maps/CMetricMap.h.

References MRPT_UNUSED_PARAM.

◆ internal_clear()

virtual void mrpt::maps::CMetricMap::internal_clear ( )
privatepure virtual

◆ internal_computeObservationLikelihood()

virtual double mrpt::maps::CMetricMap::internal_computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D takenFrom 
)
privatepure virtual

◆ internal_insertObservation()

virtual bool mrpt::maps::CMetricMap::internal_insertObservation ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D robotPose = NULL 
)
privatepure virtual

◆ internal_observer_begin()

void mrpt::utils::CObservable::internal_observer_begin ( CObserver )
privateinherited

◆ internal_observer_end()

void mrpt::utils::CObservable::internal_observer_end ( CObserver )
privateinherited

◆ isEmpty()

virtual bool mrpt::maps::CMetricMap::isEmpty ( ) const
pure virtual

◆ loadFromProbabilisticPosesAndObservations()

void mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations ( const mrpt::maps::CSimpleMap Map)

Load the map contents from a CSimpleMap object, erasing all previous content of the map.

This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as given by the "poses::CPosePDF" in the CSimpleMap object.

See also
insertObservation, CSimpleMap
Exceptions
std::exceptionSome internal steps in invoked methods can raise exceptions on invalid parameters, etc...

◆ loadFromSimpleMap()

void mrpt::maps::CMetricMap::loadFromSimpleMap ( const mrpt::maps::CSimpleMap Map)
inline

Load the map contents from a CSimpleMap object, erasing all previous content of the map.

This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as given by the "poses::CPosePDF" in the CSimpleMap object.

See also
insertObservation, CSimpleMap
Exceptions
std::exceptionSome internal steps in invoked methods can raise exceptions on invalid parameters, etc...

Definition at line 105 of file maps/CMetricMap.h.

◆ OnPostSuccesfulInsertObs()

virtual void mrpt::maps::CMetricMap::OnPostSuccesfulInsertObs ( const mrpt::obs::CObservation )
inlineprivatevirtual

Hook for each time a "internal_insertObservation" returns "true" This is called automatically from insertObservation() when internal_insertObservation returns true.

Reimplemented in mrpt::maps::COccupancyGridMap2D.

Definition at line 79 of file maps/CMetricMap.h.

◆ publishEvent()

void mrpt::utils::CObservable::publishEvent ( const mrptEvent e) const
protectedinherited

Called when you want this object to emit an event to all the observers currently subscribed to this object.

◆ saveMetricMapRepresentationToFile()

virtual void mrpt::maps::CMetricMap::saveMetricMapRepresentationToFile ( const std::string &  filNamePrefix) const
pure virtual

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).

Implemented in mrpt::maps::CBeaconMap, mrpt::maps::CHeightGridMap2D, mrpt::maps::COccupancyGridMap2D, mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >, mrpt::maps::COctoMapBase< octomap::ColorOcTree, octomap::ColorOcTreeNode >, mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >, mrpt::maps::CPointsMap, mrpt::maps::CRandomFieldGridMap2D, mrpt::maps::CReflectivityGridMap2D, mrpt::maps::CMultiMetricMap, and mrpt::maps::CLandmarksMap.

◆ squareDistanceToClosestCorrespondence()

virtual float mrpt::maps::CMetricMap::squareDistanceToClosestCorrespondence ( float  x0,
float  y0 
) const
virtual

Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.

Reimplemented in mrpt::maps::CPointsMap.

Friends And Related Symbol Documentation

◆ mrpt::utils::CStream

friend class mrpt::utils::CStream
friend

Definition at line 57 of file maps/CMetricMap.h.

Member Data Documentation

◆ classCMetricMap

const mrpt::utils::TRuntimeClassId mrpt::maps::CMetricMap::classCMetricMap
static

Definition at line 57 of file maps/CMetricMap.h.

◆ genericMapParams

TMapGenericParams mrpt::maps::CMetricMap::genericMapParams

Common params to all maps.

Definition at line 230 of file maps/CMetricMap.h.

◆ m_subscribers

std::set<CObserver*> mrpt::utils::CObservable::m_subscribers
privateinherited

Definition at line 42 of file CObservable.h.




Page generated by Doxygen 1.9.7 for MRPT 1.4.0 SVN: at Tue Jun 13 14:27:49 UTC 2023