Main MRPT website > C++ reference for MRPT 1.5.9
List of all members | Classes | Public Types | 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 39 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...
 

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 69 of file CGridMapAligner.h.

Constructor & Destructor Documentation

◆ CGridMapAligner()

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

Definition at line 63 of file CGridMapAligner.h.

Member Function Documentation

◆ Align()

CPosePDFPtr 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

Definition at line 26 of file CMetricMapsAlignmentAlgorithm.cpp.

References info.

Referenced by ICPTests::align2scans(), AlignPDF_robustMatch(), mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), and mrpt::slam::CMetricMapBuilderICP::processObservation().

◆ Align3D()

CPose3DPDFPtr 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

Definition at line 40 of file CMetricMapsAlignmentAlgorithm.cpp.

References info, and mrpt::poses::CPose3DPDFGaussian::mean.

Referenced by TEST_F().

◆ Align3DPDF()

CPose3DPDFPtr 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.

Definition at line 1125 of file CGridMapAligner.cpp.

References info, MRPT_UNUSED_PARAM, and THROW_EXCEPTION.

◆ AlignPDF()

CPosePDFPtr 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 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.

Definition at line 55 of file CGridMapAligner.cpp.

References info, MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ AlignPDF_correlation()

CPosePDFPtr 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

◆ AlignPDF_robustMatch()

CPosePDFPtr 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.

Definition at line 90 of file CGridMapAligner.cpp.

References mrpt::slam::CMetricMapsAlignmentAlgorithm::Align(), ASSERT_, mrpt::math::chi2inv(), mrpt::poses::CPoint2DPDFGaussian::cov, mrpt::poses::CPosePDFGaussian::cov, mrpt::poses::CPosePDFSOG::TGaussianMode::cov, mrpt::poses::CPosePDFSOG::Create(), mrpt::system::createDirectory(), DEG2RAD, mrpt::system::deleteFilesInDirectory(), mrpt::math::distanceBetweenPoints(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo(), mrpt::utils::CCanvas::drawImage(), mrpt::random::CRandomGenerator::drawUniform32bit(), mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER >::empty(), mrpt::utils::CCanvas::filledRectangle(), mrpt::format(), mrpt::mrpt::format(), mrpt::maps::COccupancyGridMap2D::getArea(), mrpt::utils::CImage::getHeight(), mrpt::maps::CPointsMap::getPoint(), mrpt::maps::COccupancyGridMap2D::getResolution(), mrpt::maps::COccupancyGridMap2D::getSizeX(), mrpt::maps::COccupancyGridMap2D::getSizeY(), mrpt::utils::CImage::getWidth(), mrpt::slam::CICP::TReturnInfo::goodness, info, mrpt::maps::CPointsMap::insertPoint(), IS_CLASS, mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint2DIdx(), mrpt::tfest::TSE2RobustResult::largestSubSet, mrpt::poses::CPosePDFSOG::TGaussianMode::log_w, mrpt::maps::CMultiMetricMap::m_gridMaps, mrpt::maps::CMultiMetricMap::m_pointsMaps, mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPosePDFGaussian::mahalanobisDistanceTo(), mrpt::slam::CICP::TConfigParams::maxIterations, mrpt::poses::CPoint2DPDFGaussian::mean, mrpt::poses::CPosePDFGaussian::mean, mrpt::poses::CPosePDFSOG::TGaussianMode::mean, mrpt::math::mean(), min, mrpt::math::minimum(), MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_INFO, MRPT_LOG_INFO_STREAM, MRPT_START, MRPT_TODO, myVectorOrder(), mrpt::slam::CICP::options, mrpt::utils::TMatchingPair::other_idx, mrpt::utils::TMatchingPair::other_x, mrpt::utils::TMatchingPair::other_y, mrpt::utils::TMatchingPair::other_z, mrpt::poses::CPose2D::phi(), mrpt::tfest::TSE2RobustParams::probability_find_good_model, mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), RAD2DEG, mrpt::random::randomGenerator, mrpt::tfest::TSE2RobustParams::ransac_algorithmForLandmarks, mrpt::tfest::TSE2RobustParams::ransac_fuseByCorrsMatch, mrpt::tfest::TSE2RobustParams::ransac_fuseMaxDiffPhi, mrpt::tfest::TSE2RobustParams::ransac_fuseMaxDiffXY, mrpt::tfest::TSE2RobustParams::ransac_mahalanobisDistanceThreshold, mrpt::tfest::TSE2RobustParams::ransac_maxSetSize, mrpt::tfest::TSE2RobustParams::ransac_minSetSize, mrpt::tfest::TSE2RobustParams::ransac_nSimulations, mrpt::maps::CSimplePointsMap::reserve(), mrpt::utils::round(), mrpt::utils::CImage::saveToFile(), mrpt::tfest::se2_l2(), mrpt::tfest::se2_l2_robust(), mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER >::size(), mrpt::slam::CICP::TConfigParams::smallestThresholdDist, mrpt::math::square(), mrpt::utils::CTicTac::Tac(), mrpt::utils::TMatchingPair::this_idx, mrpt::utils::TMatchingPair::this_x, mrpt::utils::TMatchingPair::this_y, mrpt::utils::TMatchingPair::this_z, mrpt::slam::CICP::TConfigParams::thresholdDist, THROW_EXCEPTION, mrpt::utils::CTicTac::Tic(), mrpt::tfest::TSE2RobustResult::transformation, mrpt::tfest::TSE2RobustParams::verbose, mrpt::math::TPoint2D::x, mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), mrpt::math::TPoint2D::y, and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().

Member Data Documentation

◆ m_grid_feat_extr

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

Grid map features extractor.

Definition at line 60 of file CGridMapAligner.h.

◆ options

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



Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020