MRPT logo

mrpt::slam::CGasConcentrationGridMap2D Class Reference

CGasConcentrationGridMap2D represents a PDF of gas concentrations over a 2D area. More...

#include <mrpt/slam/CGasConcentrationGridMap2D.h>

Inheritance diagram for mrpt::slam::CGasConcentrationGridMap2D:

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

List of all members.

Classes

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

Public Types

enum  TMapRepresentation { mrAchim = 0, mrKalmanFilter, mrKalmanApproximate }
 The type of map representation to be used. More...

Public Member Functions

float cell2float (const TGasConcentrationCell &c) const
 CGasConcentrationGridMap2D (TMapRepresentation mapType=mrAchim, 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.
void saveAsBitmapFile (const std::string &filName) const
 Save the current map as a graphical file (BMP,PNG,.
void resize (float new_x_min, float new_x_max, float new_y_min, float new_y_max, const TGasConcentrationCell &defaultValueNewCells, float additionalMarginMeters=1.0f)
 Changes the size of the grid, maintaining previous contents.
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 saveAsMatlab3DGraph (const std::string &filName) const
 Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the concentration of each cell.
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.
void predictMeasurement (const double &x, const double &y, double &out_predict_response, double &out_predict_response_variance)
 Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form of the expected variance).

Public Attributes

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

Protected Member Functions

void insertObservation_Achim (float normReading, const CPose3D &sensorPose)
 The implementation of "insertObservation" for the Achim's map model.
void insertObservation_KF (float normReading, const CPose3D &sensorPose)
 The implementation of "insertObservation" for the (whole) Kalman Filter map model.
void insertObservation_KF2 (float normReading, const CPose3D &sensorPose)
 The implementation of "insertObservation" for the Efficient Kalman Filter map model.
void recoverMeanAndCov () const
 In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std values.

Static Protected Member Functions

static float computeAchimCellValue (const TGasConcentrationCell *cell)
 Computes the average cell concentration, or 0 if it has never been observed:.

Protected Attributes

TMapRepresentation m_mapType
 The map representation type of this map.
CMatrixD m_cov
 The whole covariance matrix, used for the Kalman Filter map representation.
CMatrixD m_stackedCov
 The compressed band diagonal matrix for the KF2 implementation.
bool m_hasToRecoverMeanAndCov
 Only for the KF2 implementation.


Detailed Description

CGasConcentrationGridMap2D represents a PDF of gas concentrations over a 2D area.

Definition at line 76 of file CGasConcentrationGridMap2D.h.


Member Enumeration Documentation

The type of map representation to be used.

Enumerator:
mrAchim 
mrKalmanFilter 
mrKalmanApproximate 

Definition at line 90 of file CGasConcentrationGridMap2D.h.


Constructor & Destructor Documentation

mrpt::slam::CGasConcentrationGridMap2D::CGasConcentrationGridMap2D ( TMapRepresentation  mapType = mrAchim,
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::CGasConcentrationGridMap2D::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::CGasConcentrationGridMap2D::cell2float ( const TGasConcentrationCell c  )  const [inline]

void mrpt::slam::CGasConcentrationGridMap2D::clear (  )  [virtual]

Erase all the contents of the map.

Implements mrpt::slam::CMetricMap.

float mrpt::slam::CGasConcentrationGridMap2D::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.

static float mrpt::slam::CGasConcentrationGridMap2D::computeAchimCellValue ( const TGasConcentrationCell cell  )  [static, protected]

Computes the average cell concentration, or 0 if it has never been observed:.

double mrpt::slam::CGasConcentrationGridMap2D::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::CGasConcentrationGridMap2D::getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &  outObj  )  const [virtual]

Returns a 3D object representing the map.

Implements mrpt::slam::CMetricMap.

TMapRepresentation mrpt::slam::CGasConcentrationGridMap2D::getMapType (  ) 

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

bool mrpt::slam::CGasConcentrationGridMap2D::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.

void mrpt::slam::CGasConcentrationGridMap2D::insertObservation_Achim ( float  normReading,
const CPose3D sensorPose 
) [protected]

The implementation of "insertObservation" for the Achim's map model.

Parameters:
normReading Is a [0,1] normalized concentration reading.
sensorPose Is the sensor pose

void mrpt::slam::CGasConcentrationGridMap2D::insertObservation_KF ( float  normReading,
const CPose3D sensorPose 
) [protected]

The implementation of "insertObservation" for the (whole) Kalman Filter map model.

Parameters:
normReading Is a [0,1] normalized concentration reading.
sensorPose Is the sensor pose

void mrpt::slam::CGasConcentrationGridMap2D::insertObservation_KF2 ( float  normReading,
const CPose3D sensorPose 
) [protected]

The implementation of "insertObservation" for the Efficient Kalman Filter map model.

Parameters:
normReading Is a [0,1] normalized concentration reading.
sensorPose Is the sensor pose

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

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

Implements mrpt::slam::CMetricMap.

void mrpt::slam::CGasConcentrationGridMap2D::predictMeasurement ( const double &  x,
const double &  y,
double &  out_predict_response,
double &  out_predict_response_variance 
)

Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form of the expected variance).

This methods is implemented differently for the different gas map types.

void mrpt::slam::CGasConcentrationGridMap2D::recoverMeanAndCov (  )  const [protected]

In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std values.

See also:
m_hasToRecoverMeanAndCov

void mrpt::slam::CGasConcentrationGridMap2D::resize ( float  new_x_min,
float  new_x_max,
float  new_y_min,
float  new_y_max,
const TGasConcentrationCell defaultValueNewCells,
float  additionalMarginMeters = 1.0f 
)

Changes the size of the grid, maintaining previous contents.

See also:
setSize

void mrpt::slam::CGasConcentrationGridMap2D::saveAsBitmapFile ( const std::string &  filName  )  const

Save the current map as a graphical file (BMP,PNG,.

..). The file format will be derived from the file extension (see CMRPTImage::saveToFile ) It depends on the map representation model: mrAchim: Each pixel is the ratio $ \sum{\frac{wR}{w}} $ mrKalmanFilter: Each pixel is the mean value of the Gaussian that represents each cell. mrInformationFilter: Id.

void mrpt::slam::CGasConcentrationGridMap2D::saveAsMatlab3DGraph ( const std::string &  filName  )  const

Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the concentration of each cell.

This method can only be called in a KF map model.

void mrpt::slam::CGasConcentrationGridMap2D::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 whole covariance matrix, used for the Kalman Filter map representation.

Definition at line 265 of file CGasConcentrationGridMap2D.h.

Only for the KF2 implementation.

Definition at line 302 of file CGasConcentrationGridMap2D.h.

The map representation type of this map.

Definition at line 261 of file CGasConcentrationGridMap2D.h.

The compressed band diagonal matrix for the KF2 implementation.

The format is a Nx(W^2+2W+1) matrix, one row per cell in the grid map with the cross-covariances between each cell and half of the window around it in the grid.

Definition at line 300 of file CGasConcentrationGridMap2D.h.




Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN: at Thu Feb 26 02:18:33 EST 2009