Go to the documentation of this file.
163 mrpt::poses::CPosePDFPtr AlignPDF(
167 float *runningTime = NULL,
171 mrpt::poses::CPose3DPDFPtr Align3DPDF(
175 float *runningTime = NULL,
184 float kernel(
const float &x2,
const float &rho2);
186 mrpt::poses::CPosePDFPtr ICP_Method_Classic(
191 mrpt::poses::CPosePDFPtr ICP_Method_LM(
196 mrpt::poses::CPose3DPDFPtr ICP3D_Method_Classic(
float covariance_varPoints
This is the normalization constant that is used to scale the whole 3x3 covariance.
uint32_t corresponding_points_decimation
Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to ha...
A base class for any algorithm able of maps alignment.
TConfigParams options
The options employed by the ICP align.
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.
Declares a class that represents a Probability Density function (PDF) of a 3D pose .
float minAbsStep_trans
If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters),...
The ICP algorithm configuration data.
TICPCovarianceMethod
ICP covariance estimation methods, used in mrpt::slam::CICP::options.
CICP()
Constructor with the default options.
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
float minAbsStep_rot
If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians),...
CICP(const TConfigParams &icpParams)
Constructor that directly set the ICP params from a given struct.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool ransac_fuseByCorrsMatch
float ransac_mahalanobisDistanceThreshold
static void fill(bimap< enum_t, std::string > &m_map)
The ICP algorithm return information.
float quality
A measure of the 'quality' of the local minimum of the sqr. error found by the method....
float smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough.
Declares a virtual base class for all metric maps storage classes.
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
float ransac_fuseMaxDiffXY
bool onlyClosestCorrespondences
The usual approach: to consider only the closest correspondence for each local point (Default to true...
float Axy_aprox_derivatives
[LM method only] The size of the perturbance in x & y used to estimate the Jacobians of the square er...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
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...
float normalizationStd
RANSAC-step option: The standard deviation in X,Y of landmarks/points which are being matched (used t...
TICPCovarianceMethod ICP_covariance_method
The method to use for covariance estimation (Default: icpCovFiniteDifferences)
float LM_initial_lambda
[LM method only] The initial value of the lambda parameter in the LM method (default=1e-4)
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
float ALFA
The scale factor for threshold everytime convergence is achieved.
bool skip_quality_calculation
Skip the (sometimes) expensive evaluation of the term 'quality' at ICP output (Default=true)
slam::TICPCovarianceMethod enum_t
unsigned int maxIterations
Maximum number of iterations to run.
bool doRANSAC
Perform a RANSAC step, mrpt::tfest::se2_l2_robust(), after the ICP convergence, to obtain a better es...
bool skip_cov_calculation
Skip the computation of the covariance (saves some time) (default=false)
bool use_kernel
Whether to use kernel_rho to smooth distances, or use distances directly (default=true)
@ icpCovLinealMSE
Use the covariance of the optimal registration, disregarding uncertainty in data association.
unsigned int ransac_nSimulations
unsigned short nIterations
The number of executed iterations until convergence.
float kernel_rho
Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0....
TICPAlgorithm
The ICP algorithm selection, used in mrpt::slam::CICP::options.
@ icpCovFiniteDifferences
Covariance of a least-squares optimizer (includes data association uncertainty)
Declares a class that represents a Probability Density function (PDF) of a 2D pose .
static void fill(bimap< enum_t, std::string > &m_map)
slam::TICPAlgorithm enum_t
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Only specializations of this class are defined for each enum type of interest.
TICPAlgorithm ICP_algorithm
The algorithm to use (default: icpClassic). See http://www.mrpt.org/tutorials/programming/scan-matchi...
Page generated by Doxygen 1.8.17 for MRPT 1.4.0 SVN: at Sat Jan 18 22:37:07 UTC 2020 | | |