Public Member Functions | Public Attributes | List of all members
mp2p_icp::WeightParameters Struct Reference

#include <WeightParameters.h>

Inheritance diagram for mp2p_icp::WeightParameters:
Inheritance graph
[legend]

Public Member Functions

void load_from (const mrpt::containers::yaml &p)
 
void save_to (mrpt::containers::yaml &p) const
 

Public Attributes

PairWeights pair_weights
 See docs for PairWeights. More...
 
double scale_outlier_threshold {1.20}
 
bool use_scale_outlier_detector = false
 
Robust kernel
RobustKernel robust_kernel = RobustKernel::None
 
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
 
double robust_kernel_param = 1.0
 

Detailed Description

Common weight parameters for OLAE and Horn's solvers.

Definition at line 26 of file WeightParameters.h.

Member Function Documentation

◆ load_from()

void WeightParameters::load_from ( const mrpt::containers::yaml &  p)

Definition at line 65 of file WeightParameters.cpp.

◆ save_to()

void WeightParameters::save_to ( mrpt::containers::yaml &  p) const

Definition at line 75 of file WeightParameters.cpp.

Member Data Documentation

◆ currentEstimateForRobust

std::optional<mrpt::poses::CPose3D> mp2p_icp::WeightParameters::currentEstimateForRobust

The current guess for the sought transformation. Must be supplied if use_robust_kernel==true.

Definition at line 54 of file WeightParameters.h.

◆ pair_weights

PairWeights mp2p_icp::WeightParameters::pair_weights

See docs for PairWeights.

Definition at line 46 of file WeightParameters.h.

◆ robust_kernel

RobustKernel mp2p_icp::WeightParameters::robust_kernel = RobustKernel::None

Definition at line 50 of file WeightParameters.h.

◆ robust_kernel_param

double mp2p_icp::WeightParameters::robust_kernel_param = 1.0

Definition at line 56 of file WeightParameters.h.

◆ scale_outlier_threshold

double mp2p_icp::WeightParameters::scale_outlier_threshold {1.20}

If use_scale_outlier_detector==true, discard a potential point-to-point pairing if the ratio between the norm of their final vectors is larger than this value. A value of "1.0" will only allow numerically perfect pairings, so a slightly larger value is required. The closer to 1, the stricter. A much larger threshold (e.g. 5.0) would only reject the most obvious outliers. Refer to the technical report.

Definition at line 43 of file WeightParameters.h.

◆ use_scale_outlier_detector

bool mp2p_icp::WeightParameters::use_scale_outlier_detector = false

Enables the use of the scale-based outlier detector. Refer to the technical report. This robustness feature is independent from use_robust_kernel.

Definition at line 35 of file WeightParameters.h.


The documentation for this struct was generated from the following files:


mp2p_icp
Author(s):
autogenerated on Fri Dec 20 2024 03:46:01