MRPT logo

mrpt::slam::CGridMapAligner::TConfigParams Class Reference

The ICP algorithm configuration data. More...

#include <mrpt/slam/CGridMapAligner.h>

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

mrpt::utils::CLoadableOptions

List of all members.

Public Member Functions

 TConfigParams ()
 Initializer for default values:.
void loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &section)
 See utils::CLoadableOptions.
void dumpToTextStream (CStream &out)
 See utils::CLoadableOptions.

Public Attributes

TAlignerMethod methodSelection
 The aligner method:.
unsigned int ransac_minSetSize
 RANSAC-step options:.
unsigned int ransac_maxSetSize
float ransac_SOG_sigma_m
 The square root of the uncertainty normalization variance var_m (see papers.
float ransac_mahalanobisDistanceThreshold
 RANSAC-step options:.
float featsPerSquareMeter
 Features extraction from grid map: How many features to extract.
unsigned int feats_DirectionSectors
 Features extraction from grid map: Number of directions sectors.
unsigned int feats_RangeSectors
 Features extraction from grid map: Number of range sectors.
float feats_startDist
 Features extraction from grid map: Closer distance.
float feats_endDist
 Features extraction from grid map: Farthest distance.
float threshold
 Correspondences are considered if their distances are below this threshold (in the range 0-0.5) (default=0.13).
float min_ICP_goodness
 The minimum goodness (0-1) of the post-matching ICP to accept a hypothesis as good (default=0.25).
double maxKLd_for_merge
 Maximum KL-divergence for merging modes of the SOG (default=0.9).
bool save_feat_coors
 Dump all feature correspondences in a directory "grid_feats".
bool debug_show_corrs
 Show graphs with the details of each feature correspondences.
bool debug_save_map_pairs
 Save the pair of maps with all the pairings.


Detailed Description

The ICP algorithm configuration data.

Definition at line 91 of file CGridMapAligner.h.


Constructor & Destructor Documentation

mrpt::slam::CGridMapAligner::TConfigParams::TConfigParams (  ) 

Initializer for default values:.


Member Function Documentation

void mrpt::slam::CGridMapAligner::TConfigParams::dumpToTextStream ( CStream out  )  [virtual]

void mrpt::slam::CGridMapAligner::TConfigParams::loadFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string &  section 
) [virtual]


Member Data Documentation

Save the pair of maps with all the pairings.

Definition at line 160 of file CGridMapAligner.h.

Show graphs with the details of each feature correspondences.

Definition at line 159 of file CGridMapAligner.h.

Features extraction from grid map: Number of directions sectors.

Definition at line 134 of file CGridMapAligner.h.

Features extraction from grid map: Farthest distance.

Definition at line 146 of file CGridMapAligner.h.

Features extraction from grid map: Number of range sectors.

Definition at line 138 of file CGridMapAligner.h.

Features extraction from grid map: Closer distance.

Definition at line 142 of file CGridMapAligner.h.

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

Definition at line 130 of file CGridMapAligner.h.

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

Definition at line 156 of file CGridMapAligner.h.

The aligner method:.

Definition at line 112 of file CGridMapAligner.h.

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

Definition at line 153 of file CGridMapAligner.h.

RANSAC-step options:.

See also:
CICP::robustRigidTransformation

Definition at line 126 of file CGridMapAligner.h.

Definition at line 117 of file CGridMapAligner.h.

RANSAC-step options:.

See also:
CICP::robustRigidTransformation

Definition at line 117 of file CGridMapAligner.h.

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

..)

Definition at line 121 of file CGridMapAligner.h.

Dump all feature correspondences in a directory "grid_feats".

Definition at line 158 of file CGridMapAligner.h.

Correspondences are considered if their distances are below this threshold (in the range 0-0.5) (default=0.13).

Definition at line 150 of file CGridMapAligner.h.




Page generated by Doxygen 1.5.9 for MRPT 0.6.5 SVN:exported at Thu May 21 04:14:55 UTC 2009