This class stores any customizable set of metric maps.
The internal metric maps can be accessed directly by the user as smart pointers. The intended 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.
All these kinds of metric maps can be kept in a multi-metric map::
See CMultiMetricMap::setListOfMaps() for the method for initializing this class programatically. 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.
Definition at line 64 of file CMultiMetricMap.h.
#include <mrpt/slam/CMultiMetricMap.h>

Classes | |
| struct | TOptions |
| Some options for this class: More... | |
Public Types | |
| typedef std::pair< CPoint3D, unsigned int > | TPairIdBeacon |
Public Member Functions | |
| void * | operator new (size_t size) |
| void * | operator new[] (size_t size) |
| void | operator delete (void *ptr) throw () |
| void | operator delete[] (void *ptr) throw () |
| void | operator delete (void *memory, void *ptr) throw () |
| void * | operator new (size_t size, const std::nothrow_t &) throw () |
| void | operator delete (void *ptr, const std::nothrow_t &) throw () |
| bool | isEmpty () const |
| Returns true if the map is empty/no observation has been inserted. More... | |
| CMultiMetricMap (const mrpt::slam::TSetOfMetricMapInitializers *initializers=NULL, const TOptions *opts=NULL) | |
| Constructor. More... | |
| void | setListOfMaps (const mrpt::slam::TSetOfMetricMapInitializers *initializers) |
| Sets the list of internal map according to the passed list of map initializers (Current maps' content will be deleted!) More... | |
| CMultiMetricMap (const mrpt::slam::CMultiMetricMap &other) | |
| Copy constructor. More... | |
| mrpt::slam::CMultiMetricMap & | operator= (const mrpt::slam::CMultiMetricMap &other) |
| Copy operator from "other" object. More... | |
| virtual | ~CMultiMetricMap () |
| Destructor. More... | |
| double | computeObservationLikelihood (const CObservation *obs, const CPose3D &takenFrom) |
| Computes the log-likelihood of a given observation given an arbitrary robot 3D pose. More... | |
| float | getNewStaticPointsRatio (CPointsMap *points, CPose2D &takenFrom) |
| Returns the ratio of points in a map which are new to the point map while falling into yet static cells of gridmap. More... | |
| virtual void | determineMatching2D (const CMetricMap *otherMap, const CPose2D &otherMapPose, TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const |
| Computes the matching between this and another 2D point map, which includes finding: More... | |
| float | compute3DMatchingRatio (const CMetricMap *otherMap, const CPose3D &otherMapPose, float maxDistForCorr=0.10f, float maxMahaDistForCorr=2.0f) const |
| See the definition in the base class: Calls in this class become a call to every single map in this set. More... | |
| void | saveMetricMapRepresentationToFile (const std::string &filNamePrefix) const |
| The implementation in this class just calls all the corresponding method of the contained metric maps. More... | |
| void | auxParticleFilterCleanUp () |
| This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation". More... | |
| void | getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const |
| Returns a 3D object representing the map. More... | |
| bool | canComputeObservationLikelihood (const CObservation *obs) |
| Returns true if any of the inner maps is able to compute a sensible likelihood function for this observation. More... | |
| virtual const CSimplePointsMap * | getAsSimplePointsMap () const |
| If the map is a simple point map or it's a multi-metric map that contains EXACTLY one simple point map, return it. More... | |
| virtual CSimplePointsMap * | getAsSimplePointsMap () |
| void | clear () |
| Erase all the contents of the map. More... | |
| void | loadFromProbabilisticPosesAndObservations (const CSimpleMap &Map) |
| Load the map contents from a CSimpleMap object, erasing all previous content of the map. More... | |
| void | loadFromSimpleMap (const CSimpleMap &Map) |
| Load the map contents from a CSimpleMap object, erasing all previous content of the map. More... | |
| bool | insertObservation (const CObservation *obs, const CPose3D *robotPose=NULL) |
| Insert the observation information into this map. More... | |
| bool | insertObservationPtr (const CObservationPtr &obs, const CPose3D *robotPose=NULL) |
| A wrapper for smart pointers, just calls the non-smart pointer version. More... | |
| double | computeObservationLikelihood (const CObservation *obs, const CPose2D &takenFrom) |
| Computes the log-likelihood of a given observation given an arbitrary robot 2D pose. More... | |
| bool | canComputeObservationLikelihood (const CObservationPtr &obs) |
| double | computeObservationsLikelihood (const CSensoryFrame &sf, const CPose2D &takenFrom) |
| Returns the sum of the log-likelihoods of each individual observation within a mrpt::slam::CSensoryFrame. More... | |
| bool | canComputeObservationsLikelihood (const CSensoryFrame &sf) |
| Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. More... | |
| virtual void | determineMatching3D (const CMetricMap *otherMap, const CPose3D &otherMapPose, TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const |
| Computes the matchings between this and another 3D points map - method used in 3D-ICP. More... | |
| 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. More... | |
| mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
| Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More... | |
| CObject * | clone () const |
| Cloning interface for smart pointers. More... | |
Static Public Member Functions | |
| static void * | operator new (size_t size, void *ptr) |
Public Attributes | |
| mrpt::slam::CMultiMetricMap::TOptions | options |
| unsigned int | m_ID |
| An auxiliary variable that can be used freely by the users (this will be copied to other maps using the copy constructor, copy operator, streaming,etc) The default value is 0. More... | |
| bool | m_disableSaveAs3DObject |
| When set to true (default=false), calling "getAs3DObject" will have no effects. More... | |
Internal lists of maps | |
| std::deque< CSimplePointsMapPtr > | m_pointsMaps |
| std::deque < COccupancyGridMap2DPtr > | m_gridMaps |
| std::deque< COctoMapPtr > | m_octoMaps |
| std::deque< CColouredOctoMapPtr > | m_colourOctoMaps |
| std::deque < CGasConcentrationGridMap2DPtr > | m_gasGridMaps |
| std::deque < CWirelessPowerGridMap2DPtr > | m_wifiGridMaps |
| std::deque< CHeightGridMap2DPtr > | m_heightMaps |
| std::deque < CReflectivityGridMap2DPtr > | m_reflectivityMaps |
| CColouredPointsMapPtr | m_colourPointsMap |
| CWeightedPointsMapPtr | m_weightedPointsMap |
| CLandmarksMapPtr | m_landmarksMap |
| CBeaconMapPtr | m_beaconMap |
Static Public Attributes | |
| static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
| static const mrpt::utils::TRuntimeClassId | classCMetricMap |
RTTI stuff | |
| static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
| void | deleteAllMaps () |
| Deletes all maps and clears the internal lists of maps. More... | |
| virtual void | internal_clear () |
| Clear all elements of the map. More... | |
| virtual bool | internal_insertObservation (const CObservation *obs, const CPose3D *robotPose=NULL) |
| Insert the observation information into this map (see options) More... | |
| 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. More... | |
| 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. More... | |
CSerializable virtual methods | |
| void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
| Introduces a pure virtual method responsible for writing to a CStream. More... | |
| void | readFromStream (mrpt::utils::CStream &in, int version) |
| Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
RTTI stuff | |
| typedef CMultiMetricMapPtr | SmartPtr |
| static mrpt::utils::CLASSINIT | _init_CMultiMetricMap |
| static mrpt::utils::TRuntimeClassId | classCMultiMetricMap |
| static const mrpt::utils::TRuntimeClassId * | classinfo |
| static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
| virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
| Returns information about the class of an object in runtime. More... | |
| virtual mrpt::utils::CObject * | duplicate () const |
| Returns a copy of the object, indepently of its class. More... | |
| static mrpt::utils::CObject * | CreateObject () |
| static CMultiMetricMapPtr | Create () |
| typedef CMultiMetricMapPtr mrpt::slam::CMultiMetricMap::SmartPtr |
A typedef for the associated smart pointer
Definition at line 67 of file CMultiMetricMap.h.
| typedef std::pair<CPoint3D,unsigned int> mrpt::slam::CMultiMetricMap::TPairIdBeacon |
Definition at line 87 of file CMultiMetricMap.h.
| mrpt::slam::CMultiMetricMap::CMultiMetricMap | ( | const mrpt::slam::TSetOfMetricMapInitializers * | initializers = NULL, |
| const TOptions * | opts = NULL |
||
| ) |
Constructor.
| initializers | One internal map will be created for each entry in this "TSetOfMetricMapInitializers" struct, and each map will be initialized with the corresponding options. |
| opts | If provided (not NULL), the member "options" will be initialized with those values. If initializers is NULL, no internal map will be created. |
| mrpt::slam::CMultiMetricMap::CMultiMetricMap | ( | const mrpt::slam::CMultiMetricMap & | other | ) |
Copy constructor.
|
virtual |
Destructor.
|
staticprotected |
|
virtual |
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 from mrpt::slam::CMetricMap.
|
inherited |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
|
virtual |
Returns true if any of the inner maps is able to compute a sensible likelihood function for this observation.
| obs | The observation. |
Reimplemented from mrpt::slam::CMetricMap.
|
inherited |
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).
| sf | The observations. |
|
inherited |
Erase all the contents of the map.
Referenced by mrpt::slam::CReflectivityGridMap2D::clear(), mrpt::slam::CHeightGridMap2D::clear(), and mrpt::slam::CRandomFieldGridMap2D::clear().
|
inlineinherited |
|
virtual |
See the definition in the base class: Calls in this class become a call to every single map in this set.
Reimplemented from mrpt::slam::CMetricMap.
|
inherited |
Computes the log-likelihood of a given observation given an arbitrary robot 2D pose.
| takenFrom | The robot's pose the observation is supposed to be taken from. |
| obs | The observation. |
|
virtual |
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
| takenFrom | The robot's pose the observation is supposed to be taken from. |
| obs | The observation. |
Implements mrpt::slam::CMetricMap.
|
inherited |
Returns the sum of the log-likelihoods of each individual observation within a mrpt::slam::CSensoryFrame.
| takenFrom | The robot's pose the observation is supposed to be taken from. |
| sf | The set of observations in a CSensoryFrame. |
|
static |
|
static |
|
protected |
Deletes all maps and clears the internal lists of maps.
|
virtual |
Computes the matching between this and another 2D point map, which includes finding:
The algorithm is:
This method is the most time critical one into ICP-like algorithms.
| 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. |
Reimplemented from mrpt::slam::CMetricMap.
|
virtualinherited |
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:
| 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. |
Reimplemented in mrpt::slam::CPointsMap.
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
inlineinherited |
|
virtual |
Returns a 3D object representing the map.
Implements mrpt::slam::CMetricMap.
|
virtual |
If the map is a simple point map or it's a multi-metric map that contains EXACTLY one simple point map, return it.
Otherwise, return NULL
Reimplemented from mrpt::slam::CMetricMap.
|
virtual |
Reimplemented from mrpt::slam::CMetricMap.
| float mrpt::slam::CMultiMetricMap::getNewStaticPointsRatio | ( | CPointsMap * | points, |
| CPose2D & | takenFrom | ||
| ) |
Returns the ratio of points in a map which are new to the point map while falling into yet static cells of gridmap.
| points | The set of points to check. |
| takenFrom | The pose for the reference system of points, in global coordinates of this hybrid map. |
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::slam::CMetricMap.
|
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.
|
inherited |
Insert the observation information into this map.
This method must be implemented in derived classes.
| 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. |
|
inherited |
A wrapper for smart pointers, just calls the non-smart pointer version.
|
protectedvirtual |
Clear all elements of the map.
Implements mrpt::slam::CMetricMap.
|
protectedvirtual |
Insert the observation information into this map (see options)
| 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 CPose2D(0,0,deg) |
Implements mrpt::slam::CMetricMap.
|
virtual |
Returns true if the map is empty/no observation has been inserted.
Implements mrpt::slam::CMetricMap.
|
inherited |
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.
| std::exception | Some internal steps in invoked methods can raise exceptions on invalid parameters, etc... |
|
inlineinherited |
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.
| std::exception | Some internal steps in invoked methods can raise exceptions on invalid parameters, etc... |
Definition at line 131 of file CMetricMap.h.
|
inline | ||||||||||||||
Definition at line 67 of file CMultiMetricMap.h.
|
inline | ||||||||||||||||||||
Definition at line 67 of file CMultiMetricMap.h.
|
inline | ||||||||||||||||||||
Definition at line 67 of file CMultiMetricMap.h.
|
inline | ||||||||||||||
Definition at line 67 of file CMultiMetricMap.h.
|
inlinestatic |
Definition at line 67 of file CMultiMetricMap.h.
|
inline |
Definition at line 67 of file CMultiMetricMap.h.
|
inline | ||||||||||||||||||||
Definition at line 67 of file CMultiMetricMap.h.
|
inline |
Definition at line 67 of file CMultiMetricMap.h.
| mrpt::slam::CMultiMetricMap& mrpt::slam::CMultiMetricMap::operator= | ( | const mrpt::slam::CMultiMetricMap & | other | ) |
Copy operator from "other" object.
|
protectedinherited |
Called when you want this object to emit an event to all the observers currently subscribed to this object.
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
| in | The input binary stream where the object data must read from. |
| version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
| std::exception | On any error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
|
virtual |
The implementation in this class just calls all the corresponding method of the contained metric maps.
Implements mrpt::slam::CMetricMap.
| void mrpt::slam::CMultiMetricMap::setListOfMaps | ( | const mrpt::slam::TSetOfMetricMapInitializers * | initializers | ) |
Sets the list of internal map according to the passed list of map initializers (Current maps' content will be deleted!)
|
virtualinherited |
Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.
Reimplemented in mrpt::slam::CPointsMap.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
| out | The output binary stream where object must be dumped. |
| getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
| std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
|
staticprotected |
Definition at line 67 of file CMultiMetricMap.h.
|
staticinherited |
Definition at line 88 of file CMetricMap.h.
|
static |
Definition at line 67 of file CMultiMetricMap.h.
|
staticinherited |
|
staticinherited |
Definition at line 38 of file CSerializable.h.
|
static |
Definition at line 67 of file CMultiMetricMap.h.
| CBeaconMapPtr mrpt::slam::CMultiMetricMap::m_beaconMap |
Definition at line 162 of file CMultiMetricMap.h.
| std::deque<CColouredOctoMapPtr> mrpt::slam::CMultiMetricMap::m_colourOctoMaps |
Definition at line 154 of file CMultiMetricMap.h.
| CColouredPointsMapPtr mrpt::slam::CMultiMetricMap::m_colourPointsMap |
Definition at line 159 of file CMultiMetricMap.h.
|
inherited |
When set to true (default=false), calling "getAs3DObject" will have no effects.
Definition at line 279 of file CMetricMap.h.
| std::deque<CGasConcentrationGridMap2DPtr> mrpt::slam::CMultiMetricMap::m_gasGridMaps |
Definition at line 155 of file CMultiMetricMap.h.
| std::deque<COccupancyGridMap2DPtr> mrpt::slam::CMultiMetricMap::m_gridMaps |
Definition at line 152 of file CMultiMetricMap.h.
| std::deque<CHeightGridMap2DPtr> mrpt::slam::CMultiMetricMap::m_heightMaps |
Definition at line 157 of file CMultiMetricMap.h.
| unsigned int mrpt::slam::CMultiMetricMap::m_ID |
An auxiliary variable that can be used freely by the users (this will be copied to other maps using the copy constructor, copy operator, streaming,etc) The default value is 0.
Definition at line 247 of file CMultiMetricMap.h.
| CLandmarksMapPtr mrpt::slam::CMultiMetricMap::m_landmarksMap |
Definition at line 161 of file CMultiMetricMap.h.
| std::deque<COctoMapPtr> mrpt::slam::CMultiMetricMap::m_octoMaps |
Definition at line 153 of file CMultiMetricMap.h.
| std::deque<CSimplePointsMapPtr> mrpt::slam::CMultiMetricMap::m_pointsMaps |
Definition at line 151 of file CMultiMetricMap.h.
| std::deque<CReflectivityGridMap2DPtr> mrpt::slam::CMultiMetricMap::m_reflectivityMaps |
Definition at line 158 of file CMultiMetricMap.h.
| CWeightedPointsMapPtr mrpt::slam::CMultiMetricMap::m_weightedPointsMap |
Definition at line 160 of file CMultiMetricMap.h.
| std::deque<CWirelessPowerGridMap2DPtr> mrpt::slam::CMultiMetricMap::m_wifiGridMaps |
Definition at line 156 of file CMultiMetricMap.h.
| mrpt::slam::CMultiMetricMap::TOptions mrpt::slam::CMultiMetricMap::options |
| Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014 |