submodules
mp2p_icp
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-2021 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
18
namespace
mp2p_icp
19
{
23
struct
OptimalTF_GN_Parameters
24
{
25
bool
verbose
=
false
;
26
28
uint32_t
maxInnerLoopIterations
= 6;
29
31
double
minDelta
= 1e-7;
32
34
double
maxCost
= 0;
35
37
std::optional<mrpt::poses::CPose3D>
linearizationPoint
;
38
39
PairWeights
pairWeights
;
40
};
41
51
[[nodiscard]]
bool
optimal_tf_gauss_newton
(
52
const
Pairings
& in,
OptimalTF_Result
& result,
53
const
OptimalTF_GN_Parameters
& gnParams =
OptimalTF_GN_Parameters
());
54
57
}
// namespace mp2p_icp
mp2p_icp::Pairings
Definition:
Pairings.h:94
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::PairWeights
Definition:
PairWeights.h:26
OptimalTF_Result.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition:
optimal_tf_gauss_newton.h:37
mp2p_icp::OptimalTF_GN_Parameters::pairWeights
PairWeights pairWeights
Definition:
optimal_tf_gauss_newton.h:39
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::OptimalTF_Result
Definition:
OptimalTF_Result.h:24
mp2p_icp::OptimalTF_GN_Parameters::verbose
bool verbose
Definition:
optimal_tf_gauss_newton.h:25
mp2p_icp::OptimalTF_GN_Parameters::minDelta
double minDelta
Definition:
optimal_tf_gauss_newton.h:31
mp2p_icp::OptimalTF_GN_Parameters
Definition:
optimal_tf_gauss_newton.h:23
mp2p_icp::OptimalTF_GN_Parameters::maxCost
double maxCost
Definition:
optimal_tf_gauss_newton.h:34
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:22
PairWeights.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:28
mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43