#include <mrpt/slam/CGridMapAligner.h>

Public Member Functions | |
| TConfigParams () | |
| Initializer for default values:. | |
| void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) |
| 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. | |
Definition at line 91 of file CGridMapAligner.h.
| mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::TConfigParams | ( | ) |
Initializer for default values:.
| void mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::dumpToTextStream | ( | CStream & | out | ) | [virtual] |
| void mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::loadFromConfigFile | ( | const mrpt::utils::CConfigFileBase & | source, | |
| const std::string & | section | |||
| ) | [virtual] |
| bool mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::debug_save_map_pairs |
| bool mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::debug_show_corrs |
Show graphs with the details of each feature correspondences.
Definition at line 159 of file CGridMapAligner.h.
| unsigned int mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::feats_DirectionSectors |
Features extraction from grid map: Number of directions sectors.
Definition at line 134 of file CGridMapAligner.h.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::feats_endDist |
Features extraction from grid map: Farthest distance.
Definition at line 146 of file CGridMapAligner.h.
| unsigned int mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::feats_RangeSectors |
Features extraction from grid map: Number of range sectors.
Definition at line 138 of file CGridMapAligner.h.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::feats_startDist |
Features extraction from grid map: Closer distance.
Definition at line 142 of file CGridMapAligner.h.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::featsPerSquareMeter |
Features extraction from grid map: How many features to extract.
Definition at line 130 of file CGridMapAligner.h.
| double mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::maxKLd_for_merge |
Maximum KL-divergence for merging modes of the SOG (default=0.9).
Definition at line 156 of file CGridMapAligner.h.
| TAlignerMethod mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::methodSelection |
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::min_ICP_goodness |
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.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::ransac_mahalanobisDistanceThreshold |
RANSAC-step options:.
Definition at line 126 of file CGridMapAligner.h.
| unsigned int mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::ransac_maxSetSize |
Definition at line 117 of file CGridMapAligner.h.
| unsigned int mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::ransac_minSetSize |
RANSAC-step options:.
Definition at line 117 of file CGridMapAligner.h.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::ransac_SOG_sigma_m |
The square root of the uncertainty normalization variance var_m (see papers.
..)
Definition at line 121 of file CGridMapAligner.h.
| bool mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::save_feat_coors |
Dump all feature correspondences in a directory "grid_feats".
Definition at line 158 of file CGridMapAligner.h.
| float mrpt::slam::CGridMapAligner::CGridMapAligner::TConfigParams::threshold |
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.8 for MRPT 0.6.5 SVN: at Thu Feb 26 02:07:47 EST 2009 |