submodules
mp2p_icp
mp2p_icp
include
mp2p_icp
Solver.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/Pairings.h
>
16
#include <
mp2p_icp/WeightParameters.h
>
17
#include <mrpt/containers/yaml.h>
18
#include <mrpt/poses/CPose3D.h>
19
#include <mrpt/rtti/CObject.h>
20
#include <mrpt/system/COutputLogger.h>
21
22
#include <optional>
23
24
namespace
mp2p_icp
25
{
30
struct
SolverContext
31
{
32
SolverContext
() =
default
;
33
34
std::optional<uint32_t>
icpIteration
;
35
std::optional<mrpt::poses::CPose3D>
guessRelativePose
;
36
};
37
46
class
Solver
:
public
mrpt::system::COutputLogger,
public
mrpt::rtti::CObject
47
{
48
DEFINE_VIRTUAL_MRPT_OBJECT(
Solver
)
49
50
public
:
52
virtual
void
initialize
(
const
mrpt::containers::yaml& params);
53
60
virtual
bool
optimal_pose(
61
const
Pairings
& pairings,
OptimalTF_Result
&
out
,
62
const
SolverContext
& sc)
const
;
63
64
uint32_t runFromIteration = 0;
65
uint32_t runUpToIteration = 0;
66
67
protected
:
68
virtual
bool
impl_optimal_pose(
69
const
Pairings
& pairings,
OptimalTF_Result
& out,
70
const
SolverContext
& sc)
const
= 0;
71
};
72
73
}
// namespace mp2p_icp
mp2p_icp::SolverContext::icpIteration
std::optional< uint32_t > icpIteration
Definition:
Solver.h:34
initialize
ROSCONSOLE_DECL void initialize()
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::Pairings
Definition:
Pairings.h:94
mp2p_icp::SolverContext::guessRelativePose
std::optional< mrpt::poses::CPose3D > guessRelativePose
Definition:
Solver.h:35
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::Solver
Definition:
Solver.h:46
OptimalTF_Result.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::SolverContext::SolverContext
SolverContext()=default
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::SolverContext
Definition:
Solver.h:30
mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43