mp2p_icp
include
mp2p_icp
Solver_GaussNewton.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/PairWeights.h
>
15
#include <
mp2p_icp/Solver.h
>
16
#include <
mp2p_icp/robust_kernels.h
>
17
18
namespace
mp2p_icp
19
{
25
class
Solver_GaussNewton
:
public
Solver
26
{
27
DEFINE_MRPT_OBJECT(
Solver_GaussNewton
,
mp2p_icp
)
28
29
public
:
30
uint32_t
maxIterations
= 5;
31
PairWeights
pairWeights
;
32
33
RobustKernel
robustKernel
=
RobustKernel::None
;
34
double
robustKernelParam
= 1.0;
35
bool
innerLoopVerbose
=
false
;
36
37
void
initialize
(
const
mrpt::containers::yaml& params)
override
;
38
39
protected
:
40
// See base class docs
41
bool
impl_optimal_pose
(
42
const
Pairings
& pairings,
OptimalTF_Result
&
out
,
43
const
SolverContext
& sc)
const override
;
44
};
45
46
}
// namespace mp2p_icp
mp2p_icp::RobustKernel
RobustKernel
Definition:
robust_kernels.h:25
PairWeights.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::Solver_GaussNewton
Definition:
Solver_GaussNewton.h:25
mp2p_icp::Pairings
Definition:
Pairings.h:78
mp2p_icp::Solver_GaussNewton::robustKernelParam
double robustKernelParam
Definition:
Solver_GaussNewton.h:34
mp2p_icp::Solver_GaussNewton::pairWeights
PairWeights pairWeights
Definition:
Solver_GaussNewton.h:31
mp2p_icp::Solver_GaussNewton::maxIterations
uint32_t maxIterations
Definition:
Solver_GaussNewton.h:30
mp2p_icp::SolverContext
Definition:
Solver.h:36
mp2p_icp::OptimalTF_Result
Definition:
OptimalTF_Result.h:24
mp2p_icp::Solver_GaussNewton::robustKernel
RobustKernel robustKernel
Definition:
Solver_GaussNewton.h:33
Solver.h
Virtual base class for optimal alignment solvers (one step in ICP).
mp2p_icp::RobustKernel::None
@ None
None: plain least-squares.
mp2p_icp::Solver_GaussNewton::innerLoopVerbose
bool innerLoopVerbose
Prints GN inner loop details.
Definition:
Solver_GaussNewton.h:35
kitti-batch-convert.out
string out
Definition:
kitti-batch-convert.py:7
mp2p_icp::Solver
Definition:
Solver.h:66
robust_kernels.h
Robust kernel types and functions, for common use in all solvers.
mp2p_icp::PairWeights
Definition:
PairWeights.h:26
mp2p_icp::Solver_GaussNewton::impl_optimal_pose
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
Definition:
Solver_GaussNewton.cpp:35
mp2p_icp::Solver_GaussNewton::initialize
void initialize(const mrpt::containers::yaml ¶ms) override
Definition:
Solver_GaussNewton.cpp:21
mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:41