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

Detailed Description

The ICP algorithm configuration data.

Definition at line 55 of file CGridMapAligner.h.

#include <mrpt/slam/CGridMapAligner.h>

Inheritance diagram for mrpt::slam::CGridMapAligner::TConfigParams:

Public Member Functions

 TConfigParams ()
 Initializer for default values: More...
 
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 dumpToTextStream (std::ostream &out) const override
 This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. 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...
 
virtual void saveToConfigFile (mrpt::config::CConfigFileBase &target, const std::string &section) const
 This method saves the options to a ".ini"-like file or memory-stored string list. 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...
 

Public Attributes

TAlignerMethod methodSelection {CGridMapAligner::amModifiedRANSAC}
 The aligner method: More...
 
mrpt::vision::TDescriptorType feature_descriptor
 The feature descriptor to use: 0=detector already has descriptor, 1= SIFT, 2=SURF, 4=Spin images, 8=Polar images, 16=log-polar images. More...
 
mrpt::vision::CFeatureExtraction::TOptions feature_detector_options
 All the parameters for the feature detector. More...
 
float ransac_minSetSizeRatio {0.20f}
 RANSAC-step options: More...
 
float ransac_SOG_sigma_m {0.10f}
 The square root of the uncertainty normalization variance var_m (see papers...) More...
 
float ransac_mahalanobisDistanceThreshold {6.0f}
 [amRobustMatch method only] RANSAC-step options: More...
 
double ransac_chi2_quantile {0.99}
 [amModifiedRANSAC method only] The quantile used for chi-square thresholding (default=0.99) More...
 
double ransac_prob_good_inliers {0.9999}
 Probability of having a good inliers (def:0,9999), used for automatic number of iterations. More...
 
float featsPerSquareMeter {0.015f}
 Features extraction from grid map: How many features to extract. More...
 
float threshold_max {0.15f}
 Correspondences are considered if their distances are below this threshold (in the range [0,1]) (default=0.15). More...
 
float threshold_delta {0.10f}
 Correspondences are considered if their distances to the best match are below this threshold (in the range [0,1]) (default=0.15). More...
 
float min_ICP_goodness {0.30f}
 The minimum goodness (0-1) of the post-matching ICP to accept a hypothesis as good (default=0.30) More...
 
double max_ICP_mahadist {10.0}
 The maximum Mahalanobis distance between the initial and final poses in the ICP not to discard the hypothesis (default=10) More...
 
double maxKLd_for_merge {0.9}
 Maximum KL-divergence for merging modes of the SOG (default=0.9) More...
 
bool save_feat_coors {false}
 DEBUG - Dump all feature correspondences in a directory "grid_feats". More...
 
bool debug_show_corrs {false}
 DEBUG - Show graphs with the details of each feature correspondences. More...
 
bool debug_save_map_pairs {false}
 DEBUG - Save the pair of maps with all the pairings. More...
 

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)
 

Constructor & Destructor Documentation

◆ TConfigParams()

CGridMapAligner::TConfigParams::TConfigParams ( )

Initializer for default values:

Definition at line 1094 of file CGridMapAligner.cpp.

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 CGridMapAligner::TConfigParams::dumpToTextStream ( std::ostream &  out) const
overridevirtual

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 from mrpt::config::CLoadableOptions.

Definition at line 1098 of file CGridMapAligner.cpp.

References LOADABLEOPTS_DUMP_VAR, out, and ransac_mahalanobisDistanceThreshold.

◆ 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 CGridMapAligner::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 1128 of file CGridMapAligner.cpp.

References iniFile(), MRPT_LOAD_CONFIG_VAR, MRPT_LOAD_CONFIG_VAR_NO_DEFAULT, and ransac_mahalanobisDistanceThreshold.

Referenced by mrpt::apps::CGridMapAlignerApp::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 CLoadableOptions::saveToConfigFile ( mrpt::config::CConfigFileBase target,
const std::string &  section 
) const
virtualinherited

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

See also
loadFromConfigFile, saveToConfigFileName

Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::COccupancyGridMap3D::TLikelihoodOptions, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::maps::COccupancyGridMap3D::TInsertionOptions, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::bayes::CParticleFilter::TParticleFilterOptions, mrpt::nav::CHolonomicND::TOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::maps::TMapGenericParams, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::nav::CHolonomicVFF::TOptions, mrpt::slam::CICP::TConfigParams, mrpt::slam::CIncrementalMapPartitioner::TOptions, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, mrpt::maps::TMetricMapInitializer, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CMultiObjMotionOpt_Scalarization::TParams, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.

Definition at line 29 of file CLoadableOptions.cpp.

Referenced by mrpt::config::CLoadableOptions::dumpToTextStream(), and mrpt::config::CLoadableOptions::saveToConfigFileName().

Here is the caller graph for this function:

◆ 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

◆ debug_save_map_pairs

bool mrpt::slam::CGridMapAligner::TConfigParams::debug_save_map_pairs {false}

DEBUG - Save the pair of maps with all the pairings.

Definition at line 126 of file CGridMapAligner.h.

◆ debug_show_corrs

bool mrpt::slam::CGridMapAligner::TConfigParams::debug_show_corrs {false}

DEBUG - Show graphs with the details of each feature correspondences.

Definition at line 124 of file CGridMapAligner.h.

◆ featsPerSquareMeter

float mrpt::slam::CGridMapAligner::TConfigParams::featsPerSquareMeter {0.015f}

Features extraction from grid map: How many features to extract.

Definition at line 102 of file CGridMapAligner.h.

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

◆ feature_descriptor

mrpt::vision::TDescriptorType mrpt::slam::CGridMapAligner::TConfigParams::feature_descriptor
Initial value:

The feature descriptor to use: 0=detector already has descriptor, 1= SIFT, 2=SURF, 4=Spin images, 8=Polar images, 16=log-polar images.

Definition at line 73 of file CGridMapAligner.h.

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

◆ feature_detector_options

mrpt::vision::CFeatureExtraction::TOptions mrpt::slam::CGridMapAligner::TConfigParams::feature_detector_options

All the parameters for the feature detector.

Definition at line 77 of file CGridMapAligner.h.

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

◆ max_ICP_mahadist

double mrpt::slam::CGridMapAligner::TConfigParams::max_ICP_mahadist {10.0}

The maximum Mahalanobis distance between the initial and final poses in the ICP not to discard the hypothesis (default=10)

Definition at line 115 of file CGridMapAligner.h.

◆ maxKLd_for_merge

double mrpt::slam::CGridMapAligner::TConfigParams::maxKLd_for_merge {0.9}

Maximum KL-divergence for merging modes of the SOG (default=0.9)

Definition at line 117 of file CGridMapAligner.h.

◆ methodSelection

TAlignerMethod mrpt::slam::CGridMapAligner::TConfigParams::methodSelection {CGridMapAligner::amModifiedRANSAC}

The aligner method:

Definition at line 69 of file CGridMapAligner.h.

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

◆ min_ICP_goodness

float mrpt::slam::CGridMapAligner::TConfigParams::min_ICP_goodness {0.30f}

The minimum goodness (0-1) of the post-matching ICP to accept a hypothesis as good (default=0.30)

Definition at line 112 of file CGridMapAligner.h.

◆ ransac_chi2_quantile

double mrpt::slam::CGridMapAligner::TConfigParams::ransac_chi2_quantile {0.99}

[amModifiedRANSAC method only] The quantile used for chi-square thresholding (default=0.99)

Definition at line 96 of file CGridMapAligner.h.

◆ ransac_mahalanobisDistanceThreshold

float mrpt::slam::CGridMapAligner::TConfigParams::ransac_mahalanobisDistanceThreshold {6.0f}

[amRobustMatch method only] RANSAC-step options:

See also
CICP::robustRigidTransformation

Definition at line 92 of file CGridMapAligner.h.

◆ ransac_minSetSizeRatio

float mrpt::slam::CGridMapAligner::TConfigParams::ransac_minSetSizeRatio {0.20f}

RANSAC-step options:

See also
CICP::robustRigidTransformation The ratio of landmarks that must be inliers to accepto an hypotheses (typ: 0.20)

Definition at line 84 of file CGridMapAligner.h.

◆ ransac_prob_good_inliers

double mrpt::slam::CGridMapAligner::TConfigParams::ransac_prob_good_inliers {0.9999}

Probability of having a good inliers (def:0,9999), used for automatic number of iterations.

Definition at line 100 of file CGridMapAligner.h.

◆ ransac_SOG_sigma_m

float mrpt::slam::CGridMapAligner::TConfigParams::ransac_SOG_sigma_m {0.10f}

The square root of the uncertainty normalization variance var_m (see papers...)

Definition at line 87 of file CGridMapAligner.h.

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

◆ save_feat_coors

bool mrpt::slam::CGridMapAligner::TConfigParams::save_feat_coors {false}

DEBUG - Dump all feature correspondences in a directory "grid_feats".

Definition at line 121 of file CGridMapAligner.h.

◆ threshold_delta

float mrpt::slam::CGridMapAligner::TConfigParams::threshold_delta {0.10f}

Correspondences are considered if their distances to the best match are below this threshold (in the range [0,1]) (default=0.15).

Definition at line 108 of file CGridMapAligner.h.

◆ threshold_max

float mrpt::slam::CGridMapAligner::TConfigParams::threshold_max {0.15f}

Correspondences are considered if their distances are below this threshold (in the range [0,1]) (default=0.15).

Definition at line 105 of file CGridMapAligner.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