mp2p_icp
include
mp2p_icp
Parameters.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
* ------------------------------------------------------------------------- */
6
7
#pragma once
8
9
#include <
mp2p_icp/WeightParameters.h
>
10
#include <mrpt/containers/yaml.h>
11
#include <mrpt/core/bits_math.h>
// DEG2RAD()
12
#include <mrpt/serialization/CSerializable.h>
13
14
#include <cstdint>
15
#include <functional>
16
#include <string>
17
18
namespace
mp2p_icp
19
{
20
class
metric_map_t;
// Frwd decl
21
26
struct
Parameters
:
public
mrpt::serialization::CSerializable
27
{
28
DEFINE_SERIALIZABLE(
Parameters
,
mp2p_icp
)
29
30
public
:
34
uint32_t
maxIterations
{40};
35
39
double
minAbsStep_trans
{5e-4};
40
44
double
minAbsStep_rot
{1e-4};
58
bool
generateDebugFiles
=
false
;
59
64
bool
saveIterationDetails
=
false
;
65
70
uint32_t
decimationIterationDetails
= 10;
71
75
uint32_t
decimationDebugFiles
= 1;
76
78
std::string
debugFileNameFormat
=
79
"icp-run-$UNIQUE_ID-local-$LOCAL_ID$LOCAL_LABEL-"
80
"global-$GLOBAL_ID$GLOBAL_LABEL.icplog"
;
81
85
std::function<void(
mp2p_icp::metric_map_t
&)>
functor_before_logging_local
,
86
functor_before_logging_global
;
87
88
bool
debugPrintIterationProgress
=
false
;
89
92
std::map<uint32_t, double>
quality_checkpoints
= {
93
{50U, 0.05}, {100U, 0.10}};
94
97
void
load_from
(
const
mrpt::containers::yaml& p);
98
void
save_to
(mrpt::containers::yaml& p)
const
;
99
};
100
101
}
// namespace mp2p_icp
mp2p_icp::Parameters::functor_before_logging_local
std::function< void(mp2p_icp::metric_map_t &)> functor_before_logging_local
Definition:
Parameters.h:85
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::Parameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition:
Parameters.cpp:103
mp2p_icp::Parameters::saveIterationDetails
bool saveIterationDetails
Definition:
Parameters.h:64
mp2p_icp::Parameters::minAbsStep_trans
double minAbsStep_trans
Definition:
Parameters.h:39
mp2p_icp::Parameters::functor_before_logging_global
std::function< void(mp2p_icp::metric_map_t &)> functor_before_logging_global
Definition:
Parameters.h:86
mp2p_icp::Parameters::generateDebugFiles
bool generateDebugFiles
Definition:
Parameters.h:58
mp2p_icp::Parameters::debugFileNameFormat
std::string debugFileNameFormat
Definition:
Parameters.h:78
testing::internal::string
::std::string string
Definition:
gtest.h:1979
mp2p_icp::Parameters::maxIterations
uint32_t maxIterations
Definition:
Parameters.h:34
mp2p_icp::Parameters::decimationDebugFiles
uint32_t decimationDebugFiles
Definition:
Parameters.h:75
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::Parameters::decimationIterationDetails
uint32_t decimationIterationDetails
Definition:
Parameters.h:70
mp2p_icp::Parameters::minAbsStep_rot
double minAbsStep_rot
Definition:
Parameters.h:44
mp2p_icp::Parameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition:
Parameters.cpp:58
mp2p_icp::Parameters::quality_checkpoints
std::map< uint32_t, double > quality_checkpoints
Definition:
Parameters.h:92
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition:
metricmap.h:49
mp2p_icp::Parameters::debugPrintIterationProgress
bool debugPrintIterationProgress
Definition:
Parameters.h:88
mp2p_icp::Parameters
Definition:
Parameters.h:26
mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:40