#include <optimal_tf_gauss_newton.h>
| Public Member Functions | |
| OptimalTF_GN_Parameters ()=default | |
| Public Attributes | |
| RobustKernel | kernel = RobustKernel::None | 
| double | kernelParam = 1.0 | 
| std::optional< mrpt::poses::CPose3D > | linearizationPoint | 
| double | maxCost = 0 | 
| uint32_t | maxInnerLoopIterations = 6 | 
| double | minDelta = 1e-7 | 
| PairWeights | pairWeights | 
| std::optional< mrpt::poses::CPose3DPDFGaussianInf > | prior | 
| bool | verbose = false | 
Definition at line 24 of file optimal_tf_gauss_newton.h.
| 
 | default | 
| RobustKernel mp2p_icp::OptimalTF_GN_Parameters::kernel = RobustKernel::None | 
Definition at line 49 of file optimal_tf_gauss_newton.h.
| double mp2p_icp::OptimalTF_GN_Parameters::kernelParam = 1.0 | 
Definition at line 50 of file optimal_tf_gauss_newton.h.
| std::optional<mrpt::poses::CPose3D> mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint | 
The linerization point (the current relative pose guess)
Definition at line 29 of file optimal_tf_gauss_newton.h.
| double mp2p_icp::OptimalTF_GN_Parameters::maxCost = 0 | 
Maximum cost function; when reached, stop iterating.
Definition at line 42 of file optimal_tf_gauss_newton.h.
| uint32_t mp2p_icp::OptimalTF_GN_Parameters::maxInnerLoopIterations = 6 | 
Maximum number of iterations trying to solve for the optimal pose
Definition at line 47 of file optimal_tf_gauss_newton.h.
| double mp2p_icp::OptimalTF_GN_Parameters::minDelta = 1e-7 | 
Minimum SE(3) change to stop iterating.
Definition at line 39 of file optimal_tf_gauss_newton.h.
| PairWeights mp2p_icp::OptimalTF_GN_Parameters::pairWeights | 
Definition at line 44 of file optimal_tf_gauss_newton.h.
| std::optional<mrpt::poses::CPose3DPDFGaussianInf> mp2p_icp::OptimalTF_GN_Parameters::prior | 
Optional prior guess of the SE(3) solution, including a mean value and an inverse covariance (information) matrix, i.e. zeros in the diagonal mean that those prior coordinates should be ignored, a large value means the solution must be close to those coordinates.
Definition at line 36 of file optimal_tf_gauss_newton.h.
| bool mp2p_icp::OptimalTF_GN_Parameters::verbose = false | 
Definition at line 52 of file optimal_tf_gauss_newton.h.