submodules
mp2p_icp
mp2p_icp
src
Solver.cpp
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
* ------------------------------------------------------------------------- */
13
#include <
mp2p_icp/Solver.h
>
14
#include <mrpt/core/exceptions.h>
15
16
IMPLEMENTS_VIRTUAL_MRPT_OBJECT
(
Solver
, mrpt::rtti::CObject,
mp2p_icp
)
17
18
using namespace
mp2p_icp
;
19
20
void
Solver::initialize
(
const
mrpt::containers::yaml& params)
21
{
22
MCP_LOAD_OPT(params,
runFromIteration
);
23
MCP_LOAD_OPT(params,
runUpToIteration
);
24
}
25
26
bool
Solver::optimal_pose
(
27
const
Pairings
& pairings,
OptimalTF_Result
&
out
,
28
const
SolverContext
& sc)
const
29
{
30
const
auto
iter = sc.
icpIteration
;
31
if
(iter.has_value() && *iter <
runFromIteration
)
return
false
;
32
if
(iter.has_value() &&
runUpToIteration
> 0 && *iter >
runUpToIteration
)
33
return
false
;
34
35
return
impl_optimal_pose
(pairings, out, sc);
36
}
mp2p_icp::SolverContext::icpIteration
std::optional< uint32_t > icpIteration
Definition:
Solver.h:34
mp2p_icp::Pairings
Definition:
Pairings.h:94
mp2p_icp::Solver
Definition:
Solver.h:46
mp2p_icp::Solver::runUpToIteration
uint32_t runUpToIteration
0: no limit
Definition:
Solver.h:65
mp2p_icp::Solver::optimal_pose
virtual bool optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const
Definition:
Solver.cpp:26
mp2p_icp::Solver::initialize
virtual void initialize(const mrpt::containers::yaml ¶ms)
Definition:
Solver.cpp:20
Solver.h
Virtual base class for optimal alignment solvers (one step in ICP).
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::OptimalTF_Result
Definition:
OptimalTF_Result.h:24
kitti-batch-convert.out
string out
Definition:
kitti-batch-convert.py:7
mp2p_icp::Solver::impl_optimal_pose
virtual bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const =0
IMPLEMENTS_VIRTUAL_MRPT_OBJECT
IMPLEMENTS_VIRTUAL_MRPT_OBJECT(FilterBase, mrpt::rtti::CObject, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::SolverContext
Definition:
Solver.h:30
mp2p_icp::Solver::runFromIteration
uint32_t runFromIteration
Definition:
Solver.h:64
mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43