237 float* runningTime =
nullptr,
void* info =
nullptr);
243 float* runningTime =
nullptr,
void* info =
nullptr);
250 float kernel(
const float& x2,
const float& rho2);
273 using namespace
mrpt::slam;
Use the covariance of the optimal registration, disregarding uncertainty in data association.
float quality
A measure of the 'quality' of the local minimum of the sqr.
The ICP algorithm configuration data.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
float kernel(const float &x2, const float &rho2)
Computes: or just return the input if options.useKernel = false.
TICPAlgorithm ICP_algorithm
The algorithm to use (default: icpClassic).
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
double LM_initial_lambda
[LM method only] The initial value of the lambda parameter in the LM method (default=1e-4) ...
bool skip_quality_calculation
Skip the (sometimes) expensive evaluation of the term 'quality' at ICP output (Default=true) ...
unsigned int ransac_nSimulations
double smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough...
TConfigParams options
The options employed by the ICP align.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::poses::CPose3DPDF::Ptr ICP3D_Method_Classic(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
uint32_t corresponding_points_decimation
Decimation of the point cloud being registered against the reference one (default=5) - set to 1 to ha...
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
double ransac_fuseMaxDiffXY
bool ransac_fuseByCorrsMatch
This class allows loading and storing values and vectors of different types from a configuration text...
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
unsigned int maxIterations
Maximum number of iterations to run.
double 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)
bool doRANSAC
Perform a RANSAC step, mrpt::tfest::se2_l2_robust(), after the ICP convergence, to obtain a better es...
CICP(const TConfigParams &icpParams)
Constructor that directly set the ICP params from a given struct.
#define MRPT_ENUM_TYPE_END()
mrpt::poses::CPosePDF::Ptr ICP_Method_LM(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
unsigned short nIterations
The number of executed iterations until convergence.
bool use_kernel
Whether to use kernel_rho to smooth distances, or use distances directly (default=true) ...
GLsizei const GLchar ** string
void saveToConfigFile(mrpt::config::CConfigFileBase &c, const std::string &s) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
TICPAlgorithm
The ICP algorithm selection, used in mrpt::slam::CICP::options mrpt_slam_grp.
double ransac_mahalanobisDistanceThreshold
CICP()
Constructor with the default options.
double kernel_rho
Cauchy kernel rho, for estimating the optimal transformation covariance, in meters (default = 0...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double minAbsStep_trans
If the correction in all translation coordinates (X,Y,Z) is below this threshold (in meters)...
bool skip_cov_calculation
Skip the computation of the covariance (saves some time) (default=false)
Declares a virtual base class for all metric maps storage classes.
A base class for any algorithm able of maps alignment.
double ALFA
The scale factor for thresholds everytime convergence is achieved.
The ICP algorithm return information.
GLsizei GLsizei GLchar * source
unsigned int ransac_minSetSize
mrpt::poses::CPosePDF::Ptr AlignPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, float *runningTime=nullptr, void *info=nullptr)
An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
virtual ~CICP()
Destructor.
unsigned int ransac_maxSetSize
double covariance_varPoints
This is the normalization constant that is used to scale the whole 3x3 covariance.
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
TICPCovarianceMethod
ICP covariance estimation methods, used in mrpt::slam::CICP::options.
unsigned __int32 uint32_t
double thresholdDist
Initial threshold distance for two points to become a correspondence.
double ransac_fuseMaxDiffPhi
MRPT_FILL_ENUM(icpClassic)
double Axy_aprox_derivatives
[LM method only] The size of the perturbance in x & y used to estimate the Jacobians of the square er...
mrpt::poses::CPose3DPDF::Ptr Align3DPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=nullptr, void *info=nullptr)
The virtual method for aligning a pair of metric maps, aligning the full 6D pose. ...
mrpt::poses::CPosePDF::Ptr ICP_Method_Classic(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
Covariance of a least-squares optimizer (includes data association uncertainty)
double minAbsStep_rot
If the correction in all rotation coordinates (yaw,pitch,roll) is below this threshold (in radians)...