mp2p_icp
include
mp2p_icp
optimal_tf_gauss_newton.h
Go to the documentation of this file.
1
/* -------------------------------------------------------------------------
2
* A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3
* Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4
* See LICENSE for license information.
5
* ------------------------------------------------------------------------- */
12
#pragma once
13
14
#include <
mp2p_icp/OptimalTF_Result.h
>
15
#include <
mp2p_icp/PairWeights.h
>
16
#include <
mp2p_icp/Pairings.h
>
17
#include <
mp2p_icp/robust_kernels.h
>
18
#include <mrpt/poses/CPose3DPDFGaussianInf.h>
19
20
namespace
mp2p_icp
21
{
24
struct
OptimalTF_GN_Parameters
25
{
26
OptimalTF_GN_Parameters
() =
default
;
27
29
std::optional<mrpt::poses::CPose3D>
linearizationPoint
;
30
36
std::optional<mrpt::poses::CPose3DPDFGaussianInf>
prior
;
37
39
double
minDelta
= 1e-7;
40
42
double
maxCost
= 0;
43
44
PairWeights
pairWeights
;
45
47
uint32_t
maxInnerLoopIterations
= 6;
48
49
RobustKernel
kernel
=
RobustKernel::None
;
50
double
kernelParam
= 1.0;
51
52
bool
verbose
=
false
;
53
};
54
64
[[nodiscard]]
bool
optimal_tf_gauss_newton
(
65
const
Pairings
& in,
OptimalTF_Result
& result,
66
const
OptimalTF_GN_Parameters
& gnParams =
OptimalTF_GN_Parameters
());
67
70
}
// namespace mp2p_icp
mp2p_icp::OptimalTF_GN_Parameters
Definition:
optimal_tf_gauss_newton.h:24
mp2p_icp::optimal_tf_gauss_newton
bool optimal_tf_gauss_newton(const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
Definition:
optimal_tf_gauss_newton.cpp:28
mp2p_icp::RobustKernel
RobustKernel
Definition:
robust_kernels.h:25
PairWeights.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OptimalTF_GN_Parameters::kernelParam
double kernelParam
Definition:
optimal_tf_gauss_newton.h:50
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::Pairings
Definition:
Pairings.h:78
mp2p_icp::OptimalTF_GN_Parameters::verbose
bool verbose
Definition:
optimal_tf_gauss_newton.h:52
mp2p_icp::OptimalTF_GN_Parameters::kernel
RobustKernel kernel
Definition:
optimal_tf_gauss_newton.h:49
OptimalTF_Result.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OptimalTF_Result
Definition:
OptimalTF_Result.h:24
mp2p_icp::OptimalTF_GN_Parameters::maxCost
double maxCost
Definition:
optimal_tf_gauss_newton.h:42
mp2p_icp::RobustKernel::None
@ None
None: plain least-squares.
mp2p_icp::OptimalTF_GN_Parameters::prior
std::optional< mrpt::poses::CPose3DPDFGaussianInf > prior
Definition:
optimal_tf_gauss_newton.h:36
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OptimalTF_GN_Parameters::maxInnerLoopIterations
uint32_t maxInnerLoopIterations
Definition:
optimal_tf_gauss_newton.h:47
mp2p_icp::OptimalTF_GN_Parameters::pairWeights
PairWeights pairWeights
Definition:
optimal_tf_gauss_newton.h:44
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition:
optimal_tf_gauss_newton.h:29
mp2p_icp::OptimalTF_GN_Parameters::OptimalTF_GN_Parameters
OptimalTF_GN_Parameters()=default
robust_kernels.h
Robust kernel types and functions, for common use in all solvers.
mp2p_icp::OptimalTF_GN_Parameters::minDelta
double minDelta
Definition:
optimal_tf_gauss_newton.h:39
mp2p_icp::PairWeights
Definition:
PairWeights.h:26
mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12