MRPT  2.0.0
List of all members | Public Member Functions | Public Attributes | Static Protected Member Functions
mrpt::slam::CICP::TConfigParams Class Reference

Detailed Description

The ICP algorithm configuration data.

Definition at line 69 of file CICP.h.

#include <mrpt/slam/CICP.h>

Inheritance diagram for mrpt::slam::CICP::TConfigParams:

Public Member Functions

void loadFromConfigFile (const mrpt::config::CConfigFileBase &source, const std::string &section) override
 This method load the options from a ".ini"-like file or memory-stored string list. More...
 
void saveToConfigFile (mrpt::config::CConfigFileBase &c, const std::string &s) const override
 This method saves the options to a ".ini"-like file or memory-stored string list. More...
 
void loadFromConfigFileName (const std::string &config_file, const std::string &section)
 Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More...
 
void saveToConfigFileName (const std::string &config_file, const std::string &section) const
 Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More...
 
void dumpToConsole () const
 Just like dumpToTextStream() but sending the text to the console (std::cout) More...
 
virtual void dumpToTextStream (std::ostream &out) const
 This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. More...
 

Public Attributes

double thresholdDist {0.75}
 Initial threshold distance for two points to become a correspondence. More...
 
double thresholdAng {0.15 * M_PI / 180.0}
 
double ALFA {0.5}
 The scale factor for thresholds every time convergence is achieved. More...
 
double smallestThresholdDist {0.1}
 The size for threshold such that iterations will stop, since it is considered precise enough. More...
 
double covariance_varPoints {0.02 * 0.02}
 This is the normalization constant $ \sigma^2_p $ that is used to scale the whole 3x3 covariance. More...
 
bool doRANSAC {false}
 Perform a RANSAC step, mrpt::tfest::se2_l2_robust(), after the ICP convergence, to obtain a better estimation of the pose PDF. More...
 
double kernel_rho {0.07}
 Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0.07m) More...
 
bool use_kernel {true}
 Whether to use kernel_rho to smooth distances, or use distances directly (default=true) More...
 
double Axy_aprox_derivatives {0.05}
 [LM method only] The size of the perturbance in x & y used to estimate the Jacobians of the square error (default=0.05) More...
 
double LM_initial_lambda {1e-4}
 [LM method only] The initial value of the lambda parameter in the LM method (default=1e-4) More...
 
bool skip_cov_calculation {false}
 Skip the computation of the covariance (saves some time) (default=false) More...
 
bool skip_quality_calculation {true}
 Skip the (sometimes) expensive evaluation of the term 'quality' at ICP output (Default=true) More...
 
uint32_t corresponding_points_decimation {5}
 Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to have the older (MRPT <0.9.5) behavior of not approximating ICP by ignoring the correspondence of some points. More...
 
Algorithms selection
TICPAlgorithm ICP_algorithm {icpClassic}
 The algorithm to use (default: icpClassic). More...
 
TICPCovarianceMethod ICP_covariance_method {icpCovFiniteDifferences}
 The method to use for covariance estimation (Default: icpCovFiniteDifferences) More...
 
Correspondence-finding criteria
bool onlyUniqueRobust {false}
 
Termination criteria

if this option is enabled only the closest correspondence for each reference point will be kept (default=false).

unsigned int maxIterations {40}
 Maximum number of iterations to run. More...
 
double minAbsStep_trans {1e-6}
 If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters), iterations are terminated (Default:1e-6) More...
 
double minAbsStep_rot {1e-6}
 If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians), iterations are terminated (Default:1e-6) More...
 
RANSAC-step options for mrpt::tfest::se2_l2_robust() if \a

doRANSAC=true

unsigned int ransac_minSetSize {3}
 
unsigned int ransac_maxSetSize {20}
 
unsigned int ransac_nSimulations {100}
 
double ransac_mahalanobisDistanceThreshold {3.0}
 
double normalizationStd {0.02}
 RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used to compute covariances in the SoG) More...
 
bool ransac_fuseByCorrsMatch {true}
 
double ransac_fuseMaxDiffXY {0.01}
 
double ransac_fuseMaxDiffPhi {0.1 * M_PI / 180.0}
 

Static Protected Member Functions

static void dumpVar_int (std::ostream &out, const char *varName, int v)
 Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More...
 
static void dumpVar_float (std::ostream &out, const char *varName, float v)
 
static void dumpVar_double (std::ostream &out, const char *varName, double v)
 
static void dumpVar_bool (std::ostream &out, const char *varName, bool v)
 
static void dumpVar_string (std::ostream &out, const char *varName, const std::string &v)
 

Member Function Documentation

◆ dumpToConsole()

void CLoadableOptions::dumpToConsole ( ) const
inherited

Just like dumpToTextStream() but sending the text to the console (std::cout)

Definition at line 43 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::dumpToTextStream().

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::ros1bridge::MapHdl::loadMap(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::printParams(), and mrpt::apps::CGridMapAlignerApp::run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dumpToTextStream()

void CLoadableOptions::dumpToTextStream ( std::ostream &  out) const
virtualinherited

This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.

The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.

Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions, mrpt::maps::COccupancyGridMap2D::TInsertionOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams, mrpt::vision::TMatchingOptions, mrpt::hmtslam::CHMTSLAM::TOptions, mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams, mrpt::maps::CLandmarksMap::TLikelihoodOptions, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::CPointsMap::TRenderOptions, mrpt::maps::CPointsMap::TLikelihoodOptions, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions, mrpt::vision::TStereoSystemParams, mrpt::maps::CLandmarksMap::TInsertionOptions, mrpt::maps::CPointsMap::TInsertionOptions, mrpt::maps::CColouredPointsMap::TColourOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams, mrpt::slam::CRangeBearingKFSLAM::TOptions, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams, mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams, mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams, mrpt::maps::CBeaconMap::TInsertionOptions, mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams, mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions, mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams, mrpt::maps::CMultiMetricMapPDF::TPredictionParams, mrpt::maps::CBeaconMap::TLikelihoodOptions, mrpt::slam::CRangeBearingKFSLAM2D::TOptions, mrpt::maps::CHeightGridMap2D::TInsertionOptions, mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions, mrpt::vision::CFeatureExtraction::TOptions, mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams, mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions, mrpt::bayes::TKF_options, mrpt::graphslam::TSlidingWindow, mrpt::maps::CReflectivityGridMap2D::TInsertionOptions, mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions, mrpt::slam::CGridMapAligner::TConfigParams, mrpt::hmtslam::CTopLCDetector_FabMap::TOptions, mrpt::graphslam::TUncertaintyPath< GRAPH_T >, mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions, mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions, mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions, mrpt::maps::TMetricMapInitializer, mrpt::slam::CMetricMapBuilderICP::TConfigParams, and mrpt::slam::TKLDParams.

Definition at line 76 of file CLoadableOptions.cpp.

References mrpt::config::CConfigFileMemory::getContent(), out, and mrpt::config::CLoadableOptions::saveToConfigFile().

Referenced by mrpt::config::CLoadableOptions::dumpToConsole(), mrpt::maps::TMetricMapInitializer::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::COccupancyGridMap3D::TMapDefinition::dumpToTextStream_map_specific(), and mrpt::apps::ICP_SLAM_App_Base::run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dumpVar_bool()

void CLoadableOptions::dumpVar_bool ( std::ostream &  out,
const char *  varName,
bool  v 
)
staticprotectedinherited

Definition at line 62 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_double()

void CLoadableOptions::dumpVar_double ( std::ostream &  out,
const char *  varName,
double  v 
)
staticprotectedinherited

Definition at line 56 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_float()

void CLoadableOptions::dumpVar_float ( std::ostream &  out,
const char *  varName,
float  v 
)
staticprotectedinherited

Definition at line 50 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_int()

void CLoadableOptions::dumpVar_int ( std::ostream &  out,
const char *  varName,
int  v 
)
staticprotectedinherited

Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.

Definition at line 44 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_string()

void CLoadableOptions::dumpVar_string ( std::ostream &  out,
const char *  varName,
const std::string &  v 
)
staticprotectedinherited

Definition at line 69 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ loadFromConfigFile()

void CICP::TConfigParams::loadFromConfigFile ( const mrpt::config::CConfigFileBase source,
const std::string &  section 
)
overridevirtual

This method load the options from a ".ini"-like file or memory-stored string list.

Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" file:

[section]
resolution = 0.10 // blah blah...
modeSelection = 1 // 0=blah, 1=blah,...
See also
loadFromConfigFileName, saveToConfigFile

Implements mrpt::config::CLoadableOptions.

Definition at line 80 of file CICP.cpp.

References mrpt::DEG2RAD(), iniFile(), MRPT_LOAD_CONFIG_VAR, normalizationStd, mrpt::RAD2DEG(), and ransac_mahalanobisDistanceThreshold.

Referenced by mrpt::apps::ICP_SLAM_App_Base::run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadFromConfigFileName()

void CLoadableOptions::loadFromConfigFileName ( const std::string &  config_file,
const std::string &  section 
)
inherited

Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.

See also
loadFromConfigFile

Definition at line 22 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::loadFromConfigFile().

Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ saveToConfigFile()

void CICP::TConfigParams::saveToConfigFile ( mrpt::config::CConfigFileBase target,
const std::string &  section 
) const
overridevirtual

This method saves the options to a ".ini"-like file or memory-stored string list.

See also
loadFromConfigFile, saveToConfigFileName

Reimplemented from mrpt::config::CLoadableOptions.

Definition at line 126 of file CICP.cpp.

References MRPT_SAVE_CONFIG_VAR_COMMENT, normalizationStd, and ransac_mahalanobisDistanceThreshold.

◆ saveToConfigFileName()

void CLoadableOptions::saveToConfigFileName ( const std::string &  config_file,
const std::string &  section 
) const
inherited

Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.

See also
saveToConfigFile, loadFromConfigFileName

Definition at line 36 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::saveToConfigFile().

Here is the call graph for this function:

Member Data Documentation

◆ ALFA

double mrpt::slam::CICP::TConfigParams::ALFA {0.5}

The scale factor for thresholds every time convergence is achieved.

Definition at line 117 of file CICP.h.

Referenced by ICPTests::align2scans(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal().

◆ Axy_aprox_derivatives

double mrpt::slam::CICP::TConfigParams::Axy_aprox_derivatives {0.05}

[LM method only] The size of the perturbance in x & y used to estimate the Jacobians of the square error (default=0.05)

Definition at line 158 of file CICP.h.

◆ corresponding_points_decimation

uint32_t mrpt::slam::CICP::TConfigParams::corresponding_points_decimation {5}

Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to have the older (MRPT <0.9.5) behavior of not approximating ICP by ignoring the correspondence of some points.

The speed-up comes from a decimation of the number of KD-tree queries, the most expensive step in ICP

Definition at line 176 of file CICP.h.

◆ covariance_varPoints

double mrpt::slam::CICP::TConfigParams::covariance_varPoints {0.02 * 0.02}

This is the normalization constant $ \sigma^2_p $ that is used to scale the whole 3x3 covariance.

This has a default value of $ (0.02)^2 $, that is, a 2cm sigma. See paper: J.L. Blanco, J. Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "A Robust, Multi-Hypothesis Approach to Matching Occupancy Grid Maps", Robotica, vol. 31, no. 5, pp. 687-701, 2013.

Definition at line 129 of file CICP.h.

◆ doRANSAC

bool mrpt::slam::CICP::TConfigParams::doRANSAC {false}

Perform a RANSAC step, mrpt::tfest::se2_l2_robust(), after the ICP convergence, to obtain a better estimation of the pose PDF.

Definition at line 133 of file CICP.h.

Referenced by ICPTests::align2scans(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal().

◆ ICP_algorithm

TICPAlgorithm mrpt::slam::CICP::TConfigParams::ICP_algorithm {icpClassic}

The algorithm to use (default: icpClassic).

See https://www.mrpt.org/tutorials/programming/scan-matching-and-icp/ for details

Definition at line 84 of file CICP.h.

Referenced by ICPTests::align2scans().

◆ ICP_covariance_method

TICPCovarianceMethod mrpt::slam::CICP::TConfigParams::ICP_covariance_method {icpCovFiniteDifferences}

The method to use for covariance estimation (Default: icpCovFiniteDifferences)

Definition at line 87 of file CICP.h.

◆ kernel_rho

double mrpt::slam::CICP::TConfigParams::kernel_rho {0.07}

Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0.07m)

Definition at line 152 of file CICP.h.

◆ LM_initial_lambda

double mrpt::slam::CICP::TConfigParams::LM_initial_lambda {1e-4}

[LM method only] The initial value of the lambda parameter in the LM method (default=1e-4)

Definition at line 161 of file CICP.h.

◆ maxIterations

unsigned int mrpt::slam::CICP::TConfigParams::maxIterations {40}

Maximum number of iterations to run.

Definition at line 101 of file CICP.h.

Referenced by ICPTests::align2scans(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal().

◆ minAbsStep_rot

double mrpt::slam::CICP::TConfigParams::minAbsStep_rot {1e-6}

If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians), iterations are terminated (Default:1e-6)

Definition at line 109 of file CICP.h.

◆ minAbsStep_trans

double mrpt::slam::CICP::TConfigParams::minAbsStep_trans {1e-6}

If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters), iterations are terminated (Default:1e-6)

Definition at line 105 of file CICP.h.

◆ normalizationStd

double mrpt::slam::CICP::TConfigParams::normalizationStd {0.02}

RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used to compute covariances in the SoG)

Definition at line 144 of file CICP.h.

◆ onlyUniqueRobust

bool mrpt::slam::CICP::TConfigParams::onlyUniqueRobust {false}

Definition at line 92 of file CICP.h.

◆ ransac_fuseByCorrsMatch

bool mrpt::slam::CICP::TConfigParams::ransac_fuseByCorrsMatch {true}

Definition at line 145 of file CICP.h.

◆ ransac_fuseMaxDiffPhi

double mrpt::slam::CICP::TConfigParams::ransac_fuseMaxDiffPhi {0.1 * M_PI / 180.0}

Definition at line 147 of file CICP.h.

◆ ransac_fuseMaxDiffXY

double mrpt::slam::CICP::TConfigParams::ransac_fuseMaxDiffXY {0.01}

Definition at line 146 of file CICP.h.

◆ ransac_mahalanobisDistanceThreshold

double mrpt::slam::CICP::TConfigParams::ransac_mahalanobisDistanceThreshold {3.0}

Definition at line 140 of file CICP.h.

◆ ransac_maxSetSize

unsigned int mrpt::slam::CICP::TConfigParams::ransac_maxSetSize {20}

Definition at line 138 of file CICP.h.

◆ ransac_minSetSize

unsigned int mrpt::slam::CICP::TConfigParams::ransac_minSetSize {3}

Definition at line 138 of file CICP.h.

◆ ransac_nSimulations

unsigned int mrpt::slam::CICP::TConfigParams::ransac_nSimulations {100}

Definition at line 139 of file CICP.h.

◆ skip_cov_calculation

bool mrpt::slam::CICP::TConfigParams::skip_cov_calculation {false}

Skip the computation of the covariance (saves some time) (default=false)

Definition at line 165 of file CICP.h.

◆ skip_quality_calculation

bool mrpt::slam::CICP::TConfigParams::skip_quality_calculation {true}

Skip the (sometimes) expensive evaluation of the term 'quality' at ICP output (Default=true)

Definition at line 168 of file CICP.h.

◆ smallestThresholdDist

double mrpt::slam::CICP::TConfigParams::smallestThresholdDist {0.1}

The size for threshold such that iterations will stop, since it is considered precise enough.

Definition at line 120 of file CICP.h.

Referenced by ICPTests::align2scans(), and mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal().

◆ thresholdAng

double mrpt::slam::CICP::TConfigParams::thresholdAng {0.15 * M_PI / 180.0}

◆ thresholdDist

double mrpt::slam::CICP::TConfigParams::thresholdDist {0.75}

Initial threshold distance for two points to become a correspondence.

Definition at line 114 of file CICP.h.

Referenced by ICPTests::align2scans(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), and TEST_F().

◆ use_kernel

bool mrpt::slam::CICP::TConfigParams::use_kernel {true}

Whether to use kernel_rho to smooth distances, or use distances directly (default=true)

Definition at line 155 of file CICP.h.




Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020