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.
Definition at line 38 of file CGridMapAligner.h.
#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 , 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. | |
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. | |
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. | |
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. | |
Static Public Member Functions | |
static void | printf_debug (const char *frmt,...) |
Sends a formated text to "debugOut" if not NULL, or to cout otherwise. | |
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. | |
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. | |
Private Attributes | |
COccupancyGridMapFeatureExtractor | m_grid_feat_extr |
Grid map features extractor. | |
The type for selecting the grid-map alignment algorithm.
Enumerator | |
---|---|
amRobustMatch | |
amCorrelation | |
amModifiedRANSAC |
Definition at line 68 of file CGridMapAligner.h.
|
inline |
Definition at line 62 of file CGridMapAligner.h.
|
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.
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. |
|
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.
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. |
|
virtual |
Not applicable in this class, will launch an exception.
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.
|
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::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. |
Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.
|
private |
Private member, implements one the algorithms.
|
private |
Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms.
|
staticinherited |
Sends a formated text to "debugOut" if not NULL, or to cout otherwise.
Referenced by mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute().
|
private |
Grid map features extractor.
Definition at line 59 of file CGridMapAligner.h.
mrpt::slam::CGridMapAligner::TConfigParams mrpt::slam::CGridMapAligner::options |
Page generated by Doxygen 1.9.6 for MRPT 1.4.0 SVN: at Wed Mar 22 06:16:42 UTC 2023 |