#include <mrpt/slam/CGridMapAligner.h>
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. | |
CPose3DPDFPtr | Align3DPDF (const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL) |
The virtual method for aligning a pair of metric maps, aligning the full 6D pose. | |
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. |
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.
Definition at line 54 of file CGridMapAligner.h.
The type for selecting the grid-map alignment algorithm.
Definition at line 83 of file CGridMapAligner.h.
mrpt::slam::CGridMapAligner::CGridMapAligner | ( | ) | [inline] |
Definition at line 77 of file CGridMapAligner.h.
CPose3DPDFPtr mrpt::slam::CGridMapAligner::Align3DPDF | ( | const CMetricMap * | m1, | |
const CMetricMap * | m2, | |||
const CPose3DPDFGaussian & | initialEstimationPDF, | |||
float * | runningTime = NULL , |
|||
void * | info = NULL | |||
) | [inline, virtual] |
The virtual method for aligning a pair of metric maps, aligning the full 6D pose.
The meaning of some parameters are implementation dependant, so look at the derived classes for more details. The goal is to find a PDF for the pose displacement between maps, that is, the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.
m1 | [IN] The first map (MUST BE A COccupancyGridMap2D derived class) | |
m2 | [IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated. | |
initialEstimationPDF | [IN] An initial gross estimation for the displacement. | |
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] See derived classes for details, or NULL if it isn't needed. |
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.
Definition at line 266 of file CGridMapAligner.h.
References THROW_EXCEPTION.
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"
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. |
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.
The ICP algorithm configuration data.
Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN: at Thu Feb 26 02:19:01 EST 2009 |