Go to the documentation of this file.
9 #ifndef CGridMapAligner_H
10 #define CGridMapAligner_H
43 mrpt::poses::CPosePDFPtr AlignPDF_correlation(
47 float *runningTime = NULL,
52 mrpt::poses::CPosePDFPtr AlignPDF_robustMatch(
56 float *runningTime = NULL,
154 mrpt::poses::CPosePDFSOGPtr sog1,sog2,
sog3;
165 idx_this(i1), idx_other(i2), dist(d)
198 mrpt::poses::CPosePDFPtr AlignPDF(
202 float *runningTime = NULL,
208 mrpt::poses::CPose3DPDFPtr Align3DPDF(
212 float *runningTime = NULL,
mrpt::poses::CPose2D noRobustEstimation
The "brute" estimation from using all the available correspondences, provided just for comparison pur...
A base class for any algorithm able of maps alignment.
Declares a class that represents a Probability Density function (PDF) of a 3D pose .
double ransac_prob_good_inliers
Probability of having a good inliers (def:0,9999), used for automatic number of iterations.
TDescriptorType
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...
double max_ICP_mahadist
The maximum Mahalanobis distance between the initial and final poses in the ICP not to discard the hy...
TPairPlusDistance(size_t i1, size_t i2, float d)
static void fill(bimap< enum_t, std::string > &m_map)
bool debug_show_corrs
DEBUG - Show graphs with the details of each feature correspondences.
mrpt::vision::CFeatureExtraction::TOptions feature_detector_options
All the parameters for the feature detector.
float threshold_max
Correspondences are considered if their distances are below this threshold (in the range [0,...
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
float ransac_SOG_sigma_m
The square root of the uncertainty normalization variance var_m (see papers...)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< double > icp_goodness_all_sog_modes
The ICP goodness of all potential SOG modes at the stage "sog2", thus before the removing of "bad" IC...
double ransac_chi2_quantile
[amModifiedRANSAC method only] The quantile used for chi-square thresholding (default=0....
mrpt::utils::TMatchingPairList correspondences
All the found correspondences (not consistent)
slam::CGridMapAligner::TAlignerMethod enum_t
Declares a virtual base class for all metric maps storage classes.
The ICP algorithm configuration data.
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
float featsPerSquareMeter
Features extraction from grid map: How many features to extract.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
TReturnInfo()
Initialization.
This class allows loading and storing values and vectors of different types from a configuration text...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
A class used to store a 2D pose.
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.
bool debug_save_map_pairs
DEBUG - Save the pair of maps with all the pairings.
float threshold_delta
Correspondences are considered if their distances to the best match are below this threshold (in the ...
float ransac_mahalanobisDistanceThreshold
[amRobustMatch method only] RANSAC-step options:
COccupancyGridMapFeatureExtractor m_grid_feat_extr
Grid map features extractor.
float ransac_minSetSizeRatio
RANSAC-step options:
size_t cbSize
Size of the structure, do not change, it's set automatically.
A class for aligning two multi-metric maps (with an occupancy grid maps and a points map,...
float min_ICP_goodness
The minimum goodness (0-1) of the post-matching ICP to accept a hypothesis as good (default=0....
TAlignerMethod methodSelection
The aligner method:
double maxKLd_for_merge
Maximum KL-divergence for merging modes of the SOG (default=0.9)
The ICP algorithm return information.
mrpt::maps::CLandmarksMapPtr CLandmarksMapPtr
Backward compatible typedef.
std::vector< TPairPlusDistance > correspondences_dists_maha
Mahalanobis distance for each potential correspondence.
Declares a class that represents a Probability Density function (PDF) of a 2D pose .
mrpt::maps::CLandmarksMapPtr landmarks_map2
mrpt::poses::CPosePDFSOGPtr sog3
mrpt::vision::TDescriptorType feature_descriptor
The feature descriptor to use: 0=detector already has descriptor, 1= SIFT, 2=SURF,...
TAlignerMethod
The type for selecting the grid-map alignment algorithm.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Only specializations of this class are defined for each enum type of interest.
bool save_feat_coors
DEBUG - Dump all feature correspondences in a directory "grid_feats".
Page generated by Doxygen 1.8.16 for MRPT 1.4.0 SVN: at Mon Oct 14 22:32:58 UTC 2019 | | |