MRPT logo

mrpt::slam::CGridMapAligner Class Reference

A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching. More...

#include <mrpt/slam/CGridMapAligner.h>

Inheritance diagram for mrpt::slam::CGridMapAligner:

mrpt::slam::CMetricMapsAlignmentAlgorithm mrpt::utils::CDebugOutputCapable

List of all members.

Classes

class  TConfigParams
 The ICP algorithm configuration data. More...
struct  TReturnInfo
 The ICP algorithm return information. More...

Public Types

enum  TAlignerMethod { amRobustMatch = 0, amCorrelation }
 The type for selecting the grid-map alignment algorithm. More...

Public Member Functions

 CGridMapAligner ()
CPosePDFPtr AlignPDF (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 The method for aligning a pair of 2D points map.

Static Public Member Functions

static void landmarksMatchingCorrelation (mrpt::slam::CLandmark *lm1, mrpt::slam::CLandmark *lm2, float &minDistance, float &minDistAngle)
 Computes the matching between a pair of "panoramic images" landmarks, by the correlation method.

Public Attributes

mrpt::slam::CGridMapAligner::TConfigParams options
 The ICP algorithm configuration data.

Private Member Functions

CPosePDFPtr AlignPDF_correlation (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 Private member, implements one the algorithms.
CPosePDFPtr AlignPDF_robustMatch (const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 Private member, implements one the algorithms.


Detailed Description

A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching.

The matching pose is returned as a Sum of Gaussians (poses::CPosePDFSOG).

This method was reported in the paper:

See CGridMapAligner::Align for more instructions.

See also:
CMetricMapsAlignmentAlgorithm

Definition at line 54 of file CGridMapAligner.h.


Member Enumeration Documentation

The type for selecting the grid-map alignment algorithm.

Enumerator:
amRobustMatch 
amCorrelation 

Definition at line 83 of file CGridMapAligner.h.


Constructor & Destructor Documentation

mrpt::slam::CGridMapAligner::CGridMapAligner (  )  [inline]

Definition at line 77 of file CGridMapAligner.h.


Member Function Documentation

CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF ( const CMetricMap m1,
const CMetricMap m2,
const CPosePDFGaussian initialEstimationPDF,
float *  runningTime = NULL,
void *  info = NULL 
) [virtual]

The method for aligning a pair of 2D points map.

The meaning of some parameters are implementation dependant, so look for derived classes for instructions. The target is to find a PDF for the pose displacement between maps, thus the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.

NOTE: This method can be configurated with "options"

Parameters:
m1 [IN] The first map (Must be a mrpt::slam::CMultiMetricMap class)
m2 [IN] The second map (Must be a mrpt::slam::CMultiMetricMap class)
initialEstimationPDF [IN] (IGNORED IN THIS ALGORITHM!)
runningTime [OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it.
info [OUT] A pointer to a CAlignerFromMotionDraws::TReturnInfo struct, or NULL if result information are not required.
Note:
The returned PDF depends on the selected alignment method:
  • "amRobustMatch" --> A "poses::CPosePDFSOG" object.
  • "amCorrelation" --> A "poses::CPosePDFGrid" object.
Returns:
A smart pointer to the output estimated pose PDF.
See also:
CPointsMapAlignmentAlgorithm, options

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF_correlation ( const CMetricMap m1,
const CMetricMap m2,
const CPosePDFGaussian initialEstimationPDF,
float *  runningTime = NULL,
void *  info = NULL 
) [private]

Private member, implements one the algorithms.

CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF_robustMatch ( const CMetricMap m1,
const CMetricMap m2,
const CPosePDFGaussian initialEstimationPDF,
float *  runningTime = NULL,
void *  info = NULL 
) [private]

Private member, implements one the algorithms.

static void mrpt::slam::CGridMapAligner::landmarksMatchingCorrelation ( mrpt::slam::CLandmark lm1,
mrpt::slam::CLandmark lm2,
float &  minDistance,
float &  minDistAngle 
) [static]

Computes the matching between a pair of "panoramic images" landmarks, by the correlation method.


Member Data Documentation

The ICP algorithm configuration data.




Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN:exported at Mon Jan 12 13:00:16 UTC 2009