MRPT logo

mrpt::slam::CHeightGridMap2D Class Reference

A mesh representation of a surface which keeps the estimated height for each (x,y) location. More...

#include <mrpt/slam/CHeightGridMap2D.h>

Inheritance diagram for mrpt::slam::CHeightGridMap2D:

mrpt::slam::CMetricMap mrpt::utils::CDynamicGrid< T > mrpt::utils::CSerializable

List of all members.

Classes

struct  TInsertionOptions
 Parameters related with inserting observations into the map. More...

Public Types

enum  TMapRepresentation { mrSimpleAverage = 0, mrSlidingWindow }
 The type of map representation to be used. More...

Public Member Functions

float cell2float (const THeightGridmapCell &c) const
 CHeightGridMap2D (TMapRepresentation mapType=mrSimpleAverage, float x_min=-2, float x_max=2, float y_min=-2, float y_max=2, float resolution=0.1)
 Constructor.
void clear ()
 Erase all the contents of the map.
bool isEmpty () const
 Returns true if the map is empty/no observation has been inserted.
bool insertObservation (const CObservation *obs, const CPose3D *robotPose=NULL)
 Insert the observation information into this map.
double computeObservationLikelihood (const CObservation *obs, const CPose3D &takenFrom)
 Computes the likelihood that a given observation was taken from a given pose in the world being modeled with this map.
size_t removeObservationsByTimestamp (const mrpt::system::TTimeStamp &tim)
 Remove all the points from the average of each cell which were inserted at exactly the given timestamp.
float compute3DMatchingRatio (const CMetricMap *otherMap, const CPose3D &otherMapPose, float minDistForCorr=0.10f, float minMahaDistForCorr=2.0f) 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.
void saveMetricMapRepresentationToFile (const std::string &filNamePrefix) const
 The implementation in this class just calls all the corresponding method of the contained metric maps.
void getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const
 Returns a 3D object representing the map.
void auxParticleFilterCleanUp ()
 This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
TMapRepresentation getMapType ()
 Return the type of the gas distribution map, according to parameters passed on construction.

Public Attributes

mrpt::slam::CHeightGridMap2D::TInsertionOptions insertionOptions
 Parameters related with inserting observations into the map.

Protected Attributes

TMapRepresentation m_mapType
 The map representation type of this map.


Detailed Description

A mesh representation of a surface which keeps the estimated height for each (x,y) location.

Important implemented features are the insertion of 2D laser scans (from arbitrary 6D poses) and the exportation as 3D scenes.

Each cell contains the up-to-date average height from measured falling in that cell. Two algorithms can be used here:

Definition at line 97 of file CHeightGridMap2D.h.


Member Enumeration Documentation

The type of map representation to be used.

See mrpt::slam::CHeightGridMap2D for discussion.

Enumerator:
mrSimpleAverage 
mrSlidingWindow 

Definition at line 111 of file CHeightGridMap2D.h.


Constructor & Destructor Documentation

mrpt::slam::CHeightGridMap2D::CHeightGridMap2D ( TMapRepresentation  mapType = mrSimpleAverage,
float  x_min = -2,
float  x_max = 2,
float  y_min = -2,
float  y_max = 2,
float  resolution = 0.1 
)

Constructor.


Member Function Documentation

void mrpt::slam::CHeightGridMap2D::auxParticleFilterCleanUp (  )  [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.

Implements mrpt::slam::CMetricMap.

float mrpt::slam::CHeightGridMap2D::cell2float ( const THeightGridmapCell c  )  const [inline]

Definition at line 103 of file CHeightGridMap2D.h.

References mrpt::slam::THeightGridmapCell::h.

void mrpt::slam::CHeightGridMap2D::clear (  ) 

Erase all the contents of the map.

Reimplemented from mrpt::utils::CDynamicGrid< T >.

float mrpt::slam::CHeightGridMap2D::compute3DMatchingRatio ( const CMetricMap otherMap,
const CPose3D otherMapPose,
float  minDistForCorr = 0.10f,
float  minMahaDistForCorr = 2.0f 
) 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".
minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence.
minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence.
Returns:
The matching ratio [0,1]
See also:
computeMatchingWith2D

Implements mrpt::slam::CMetricMap.

double mrpt::slam::CHeightGridMap2D::computeObservationLikelihood ( const CObservation obs,
const CPose3D takenFrom 
) [virtual]

Computes the likelihood that a given observation was taken from a given pose in the world being modeled with this map.

Parameters:
takenFrom The robot's pose the observation is supposed to be taken from.
obs The observation.
Returns:
This method returns a likelihood in the range [0,1].
See also:
Used in particle filter algorithms, see: CMultiMetricMapPDF::update

Implements mrpt::slam::CMetricMap.

void mrpt::slam::CHeightGridMap2D::getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &  outObj  )  const [virtual]

Returns a 3D object representing the map.

Implements mrpt::slam::CMetricMap.

TMapRepresentation mrpt::slam::CHeightGridMap2D::getMapType (  ) 

Return the type of the gas distribution map, according to parameters passed on construction.

bool mrpt::slam::CHeightGridMap2D::insertObservation ( const CObservation obs,
const CPose3D robotPose = NULL 
) [virtual]

Insert the observation information into this map.

This method must be implemented in derived classes.

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 CPose2D(0,0,deg)
See also:
CObservation::insertObservationInto

Implements mrpt::slam::CMetricMap.

bool mrpt::slam::CHeightGridMap2D::isEmpty (  )  const [virtual]

Returns true if the map is empty/no observation has been inserted.

Implements mrpt::slam::CMetricMap.

size_t mrpt::slam::CHeightGridMap2D::removeObservationsByTimestamp ( const mrpt::system::TTimeStamp tim  ) 

Remove all the points from the average of each cell which were inserted at exactly the given timestamp.

Returns:
The number of points removed.

void mrpt::slam::CHeightGridMap2D::saveMetricMapRepresentationToFile ( const std::string &  filNamePrefix  )  const [virtual]

The implementation in this class just calls all the corresponding method of the contained metric maps.

Implements mrpt::slam::CMetricMap.


Member Data Documentation

Parameters related with inserting observations into the map.

The map representation type of this map.

Definition at line 231 of file CHeightGridMap2D.h.




Page generated by Doxygen 1.5.7.1 for MRPT 0.6.5 SVN: at Mon Feb 23 13:24:51 EST 2009