Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
mrpt::slam::CGridMapAligner Class Reference

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 class can use three methods (see options.methodSelection):

See CGridMapAligner::Align for more instructions.

See also
CMetricMapsAlignmentAlgorithm

Definition at line 38 of file CGridMapAligner.h.

#include <mrpt/slam/CGridMapAligner.h>

Inheritance diagram for mrpt::slam::CGridMapAligner:
Inheritance graph

Classes

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

Public Types

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

Public Member Functions

 CGridMapAligner ()
 
mrpt::poses::CPosePDFPtr AlignPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 The method for aligning a pair of 2D points map. More...
 
mrpt::poses::CPose3DPDFPtr Align3DPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 Not applicable in this class, will launch an exception. More...
 
mrpt::poses::CPosePDFPtr Align (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, float *runningTime=NULL, void *info=NULL)
 The method for aligning a pair of metric maps, aligning only 2D + orientation. More...
 
mrpt::poses::CPose3DPDFPtr Align3D (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3D &grossEst, float *runningTime=NULL, void *info=NULL)
 The method for aligning a pair of metric maps, aligning the full 6D pose. More...
 

Static Public Member Functions

static void printf_debug (const char *frmt,...)
 Sends a formated text to "debugOut" if not NULL, or to cout otherwise. More...
 

Public Attributes

mrpt::slam::CGridMapAligner::TConfigParams options
 

Private Member Functions

mrpt::poses::CPosePDFPtr AlignPDF_correlation (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 Private member, implements one the algorithms. More...
 
mrpt::poses::CPosePDFPtr AlignPDF_robustMatch (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
 Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms. More...
 

Private Attributes

COccupancyGridMapFeatureExtractor m_grid_feat_extr
 Grid map features extractor. More...
 

Member Enumeration Documentation

◆ TAlignerMethod

The type for selecting the grid-map alignment algorithm.

Enumerator
amRobustMatch 
amCorrelation 
amModifiedRANSAC 

Definition at line 68 of file CGridMapAligner.h.

Constructor & Destructor Documentation

◆ CGridMapAligner()

mrpt::slam::CGridMapAligner::CGridMapAligner ( )
inline

Definition at line 62 of file CGridMapAligner.h.

Member Function Documentation

◆ Align()

mrpt::poses::CPosePDFPtr mrpt::slam::CMetricMapsAlignmentAlgorithm::Align ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose2D grossEst,
float *  runningTime = NULL,
void *  info = NULL 
)
inherited

The method for aligning a pair of metric maps, aligning only 2D + orientation.

The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into the 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.

Parameters
m1[IN] The first map
m2[IN] The second map. The pose of this map respect to m1 is to be estimated.
grossEst[IN] An initial gross estimation for the displacement. If a given algorithm doesn't need it, set to CPose2D(0,0,0) for example.
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.
Returns
A smart pointer to the output estimated pose PDF.
See also
CICP

◆ Align3D()

mrpt::poses::CPose3DPDFPtr mrpt::slam::CMetricMapsAlignmentAlgorithm::Align3D ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose3D grossEst,
float *  runningTime = NULL,
void *  info = NULL 
)
inherited

The method for aligning a pair of metric maps, aligning the full 6D pose.

The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into the 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.

Parameters
m1[IN] The first map
m2[IN] The second map. The pose of this map respect to m1 is to be estimated.
grossEst[IN] An initial gross estimation for the displacement. If a given algorithm doesn't need it, set to CPose3D(0,0,0) for example.
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.
Returns
A smart pointer to the output estimated pose PDF.
See also
CICP

◆ Align3DPDF()

mrpt::poses::CPose3DPDFPtr mrpt::slam::CGridMapAligner::Align3DPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose3DPDFGaussian initialEstimationPDF,
float *  runningTime = NULL,
void *  info = NULL 
)
virtual

Not applicable in this class, will launch an exception.

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

◆ AlignPDF()

mrpt::poses::CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::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::maps::CMultiMetricMap class)
m2[IN] The second map (Must be a mrpt::maps::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.

◆ AlignPDF_correlation()

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

Private member, implements one the algorithms.

◆ AlignPDF_robustMatch()

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

Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms.

◆ printf_debug()

static void mrpt::utils::CDebugOutputCapable::printf_debug ( const char *  frmt,
  ... 
)
staticinherited

Sends a formated text to "debugOut" if not NULL, or to cout otherwise.

Referenced by mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute().

Member Data Documentation

◆ m_grid_feat_extr

COccupancyGridMapFeatureExtractor mrpt::slam::CGridMapAligner::m_grid_feat_extr
private

Grid map features extractor.

Definition at line 59 of file CGridMapAligner.h.

◆ options

mrpt::slam::CGridMapAligner::TConfigParams mrpt::slam::CGridMapAligner::options



Page generated by Doxygen 1.8.20 for MRPT 1.4.0 SVN: at Thu Aug 27 02:40:23 UTC 2020