Main MRPT website > C++ reference
MRPT logo
Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes

mrpt::slam::CMetricMapBuilderICP Class Reference


Detailed Description

A class for very simple 2D SLAM based on ICP.

This is a non-probabilistic pose tracking algorithm. Map are stored as in files as binary dumps of "mrpt::slam::CSimpleMap" objects. The methods are thread-safe.

Definition at line 46 of file CMetricMapBuilderICP.h.

#include <mrpt/slam/CMetricMapBuilderICP.h>

Inheritance diagram for mrpt::slam::CMetricMapBuilderICP:
Inheritance graph
[legend]

List of all members.

Classes

struct  TConfigParams
 Algorithm configuration params. More...
struct  TDist
 Traveled distances from last map update / ICP-based localization. More...

Public Member Functions

 CMetricMapBuilderICP ()
 Default constructor - Upon construction, you can set the parameters in ICP_options, then call "initialize".
 CMetricMapBuilderICP (TSetOfMetricMapInitializers *mapInitializers, float insertionLinDistance=1.0f, float insertionAngDistance=DEG2RAD(30), CICP::TConfigParams *icpParams=NULL)
 *DEPRECATED* Constructor with arguments - use the default constructor, then set the parameters in the "ICP_options" member.
virtual ~CMetricMapBuilderICP ()
 Destructor:
void initialize (const CSimpleMap &initialMap=CSimpleMap(), CPosePDF *x0=NULL)
 Initialize the method, starting with a known location PDF "x0"(if supplied, set to NULL to left unmodified) and a given fixed, past map.
CPose3DPDFPtr getCurrentPoseEstimation () const
 Returns a copy of the current best pose estimation as a pose PDF.
void setCurrentMapFile (const char *mapFile)
 Sets the "current map file", thus that map will be loaded if it exists or a new one will be created if it does not, and the updated map will be save to that file when destroying the object.
void processActionObservation (CActionCollection &action, CSensoryFrame &in_SF)
 Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description.
void processObservation (const CObservationPtr &obs)
 The main method of this class: Process one odometry or sensor observation.
void getCurrentlyBuiltMap (CSimpleMap &out_map) const
 Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map.
void getCurrentMapPoints (mrpt::vector< float > &x, mrpt::vector< float > &y)
 Returns the 2D points of current local map.
CMultiMetricMapgetCurrentlyBuiltMetricMap ()
 Returns the map built so far.
unsigned int getCurrentlyBuiltMapSize ()
 Returns just how many sensory-frames are stored in the currently build map.
void saveCurrentEstimationToImage (const std::string &file, bool formatEMF_BMP=true)
 A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file.

Public Attributes

TConfigParams ICP_options
 Options for the ICP-SLAM application.
CICP::TConfigParams ICP_params
 Options for the ICP algorithm itself.

Private Member Functions

void accumulateRobotDisplacementCounters (const CPose2D &Apose)

Private Attributes

CSimpleMap SF_Poses_seq
 The set of observations that leads to current map:
CMultiMetricMap metricMap
 The metric map representation as a points map:
std::string currentMapFile
 Current map file.
mrpt::poses::CRobot2DPoseEstimator m_lastPoseEst
 The pose estimation by the alignment algorithm (ICP).
mrpt::math::CMatrixDouble33 m_lastPoseEst_cov
 Last pose estimation (covariance)
std::deque< mrpt::math::TPose2Dm_estRobotPath
 The estimated robot path:
mrpt::poses::CPose2D m_auxAccumOdometry
TDist m_distSinceLastICP
std::map< std::string, TDistm_distSinceLastInsertion
 Indexed by sensor label.
bool m_there_has_been_an_odometry

Constructor & Destructor Documentation

mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP ( )

Default constructor - Upon construction, you can set the parameters in ICP_options, then call "initialize".

mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP ( TSetOfMetricMapInitializers mapInitializers,
float  insertionLinDistance = 1.0f,
float  insertionAngDistance = DEG2RAD(30),
CICP::TConfigParams icpParams = NULL 
)

*DEPRECATED* Constructor with arguments - use the default constructor, then set the parameters in the "ICP_options" member.

Parameters:
mapInitializersWhat maps to create (at least one points map and/or a grid map are needed).
insertionLinDistanceMinimum robot linear displacement for a new observation to be inserted in the map.
insertionAngDistanceMinimum robot angular displacement for a new observation to be inserted in the map.
virtual mrpt::slam::CMetricMapBuilderICP::~CMetricMapBuilderICP ( ) [virtual]

Destructor:


Member Function Documentation

void mrpt::slam::CMetricMapBuilderICP::accumulateRobotDisplacementCounters ( const CPose2D Apose) [private]
void mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMap ( CSimpleMap out_map) const [virtual]

Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map.

Implements mrpt::slam::CMetricMapBuilder.

unsigned int mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMapSize ( ) [virtual]

Returns just how many sensory-frames are stored in the currently build map.

Implements mrpt::slam::CMetricMapBuilder.

CMultiMetricMap* mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMetricMap ( ) [virtual]

Returns the map built so far.

NOTE that for efficiency a pointer to the internal object is passed, DO NOT delete nor modify the object in any way, if desired, make a copy of ir with "duplicate()".

Implements mrpt::slam::CMetricMapBuilder.

void mrpt::slam::CMetricMapBuilderICP::getCurrentMapPoints ( mrpt::vector< float > &  x,
mrpt::vector< float > &  y 
)

Returns the 2D points of current local map.

CPose3DPDFPtr mrpt::slam::CMetricMapBuilderICP::getCurrentPoseEstimation ( ) const [virtual]

Returns a copy of the current best pose estimation as a pose PDF.

Implements mrpt::slam::CMetricMapBuilder.

void mrpt::slam::CMetricMapBuilderICP::initialize ( const CSimpleMap initialMap = CSimpleMap(),
CPosePDF x0 = NULL 
) [virtual]

Initialize the method, starting with a known location PDF "x0"(if supplied, set to NULL to left unmodified) and a given fixed, past map.

This method MUST be called if using the default constructor, after loading the configuration into ICP_options. In particular, TConfigParams::mapInitializers

Implements mrpt::slam::CMetricMapBuilder.

void mrpt::slam::CMetricMapBuilderICP::processActionObservation ( CActionCollection action,
CSensoryFrame in_SF 
) [virtual]

Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description.

Parameters:
actionThe estimation of the incremental pose change in the robot pose.
in_SFThe set of observations that robot senses at the new pose. See params in CMetricMapBuilder::options and CMetricMapBuilderICP::ICP_options
See also:
processObservation

Implements mrpt::slam::CMetricMapBuilder.

void mrpt::slam::CMetricMapBuilderICP::processObservation ( const CObservationPtr obs)

The main method of this class: Process one odometry or sensor observation.

The new entry point of the algorithm (the old one was processActionObservation, which now is a wrapper to this method). See params in CMetricMapBuilder::options and CMetricMapBuilderICP::ICP_options

void mrpt::slam::CMetricMapBuilderICP::saveCurrentEstimationToImage ( const std::string &  file,
bool  formatEMF_BMP = true 
) [virtual]

A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file.

Parameters:
fileThe output file name
formatEMF_BMPOutput format = true:EMF, false:BMP

Implements mrpt::slam::CMetricMapBuilder.

void mrpt::slam::CMetricMapBuilderICP::setCurrentMapFile ( const char *  mapFile)

Sets the "current map file", thus that map will be loaded if it exists or a new one will be created if it does not, and the updated map will be save to that file when destroying the object.


Member Data Documentation

Current map file.

Definition at line 168 of file CMetricMapBuilderICP.h.

Options for the ICP-SLAM application.

See also:
ICP_params

Definition at line 97 of file CMetricMapBuilderICP.h.

Options for the ICP algorithm itself.

See also:
ICP_options

Definition at line 98 of file CMetricMapBuilderICP.h.

Definition at line 177 of file CMetricMapBuilderICP.h.

Definition at line 186 of file CMetricMapBuilderICP.h.

Indexed by sensor label.

Definition at line 187 of file CMetricMapBuilderICP.h.

The estimated robot path:

Definition at line 176 of file CMetricMapBuilderICP.h.

The pose estimation by the alignment algorithm (ICP).

Last pose estimation (Mean)

Definition at line 171 of file CMetricMapBuilderICP.h.

Last pose estimation (covariance)

Definition at line 172 of file CMetricMapBuilderICP.h.

Definition at line 188 of file CMetricMapBuilderICP.h.

The metric map representation as a points map:

Definition at line 164 of file CMetricMapBuilderICP.h.

The set of observations that leads to current map:

Definition at line 160 of file CMetricMapBuilderICP.h.




Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN:exported at Tue Jan 25 21:56:31 UTC 2011