Parameters.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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
7 #include <mp2p_icp/Parameters.h>
8 #include <mrpt/core/get_env.h>
9 #include <mrpt/serialization/CArchive.h>
10 #include <mrpt/serialization/stl_serialization.h>
11 #include <mrpt/version.h>
12 
13 IMPLEMENTS_MRPT_OBJECT(Parameters, mrpt::serialization::CSerializable, mp2p_icp)
14 
15 using namespace mp2p_icp;
16 
17 // this env var can be used to enforce generating files despite the actual
18 // parameter files.
20  mrpt::get_env<bool>("MP2P_ICP_GENERATE_DEBUG_FILES", false);
21 
22 // Implementation of the CSerializable virtual interface:
23 uint8_t Parameters::serializeGetVersion() const { return 2; }
24 void Parameters::serializeTo(mrpt::serialization::CArchive& out) const
25 {
31 }
32 void Parameters::serializeFrom(
33  mrpt::serialization::CArchive& in, uint8_t version)
34 {
35  *this = Parameters();
36 
37  switch (version)
38  {
39  case 0:
40  case 1:
41  case 2:
42  {
46  if (version >= 1) in >> decimationDebugFiles;
47  if (version >= 2)
49  }
50  break;
51  default:
52  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
53  };
54 
56 }
57 
58 void Parameters::load_from(const mrpt::containers::yaml& p)
59 {
60  MCP_LOAD_REQ(p, maxIterations);
61  MCP_LOAD_OPT(p, minAbsStep_trans);
62  MCP_LOAD_OPT(p, minAbsStep_rot);
63  MCP_LOAD_OPT(p, generateDebugFiles);
64  MCP_LOAD_OPT(p, debugFileNameFormat);
65  MCP_LOAD_OPT(p, debugPrintIterationProgress);
66  MCP_LOAD_OPT(p, decimationDebugFiles);
67  MCP_LOAD_OPT(p, saveIterationDetails);
68  MCP_LOAD_OPT(p, decimationIterationDetails);
69 
70  if (p.has("quality_checkpoints"))
71  {
72  ASSERT_(
73  p["quality_checkpoints"].isSequence() &&
74 #if MRPT_VERSION >= 0x020d00
75  !p["quality_checkpoints"].asSequenceRange().empty()
76 #else
77  !p["quality_checkpoints"].asSequence().empty()
78 #endif
79  );
80 
81  quality_checkpoints.clear();
82 #if MRPT_VERSION >= 0x020d00
83  for (const auto& e : p["quality_checkpoints"].asSequenceRange())
84 #else
85  for (const auto& e : p["quality_checkpoints"].asSequence())
86 #endif
87 
88  {
89  ASSERTMSG_(
90  e.isMap(),
91  "Entries within 'quality_checkpoints' must be a Map. See "
92  "mp2p_icp::Parameters docs.");
93 
94  quality_checkpoints.emplace(
95  e.asMap().at("iteration").as<size_t>(),
96  e.asMap().at("minimum_quality").as<double>());
97  }
98  }
99 
101 }
102 
103 void Parameters::save_to(mrpt::containers::yaml& p) const
104 {
105  MCP_SAVE(p, maxIterations);
106  MCP_SAVE(p, minAbsStep_trans);
107  MCP_SAVE(p, minAbsStep_rot);
108  MCP_SAVE(p, generateDebugFiles);
109  MCP_SAVE(p, debugFileNameFormat);
110  MCP_SAVE(p, debugPrintIterationProgress);
111  MCP_SAVE(p, decimationDebugFiles);
112  MCP_SAVE(p, saveIterationDetails);
113  MCP_SAVE(p, decimationIterationDetails);
114 }
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
Parameters
PM::Parameters Parameters
Definition: filterProfiler.cpp:20
mp2p_icp::Parameters::generateDebugFiles
bool generateDebugFiles
Definition: Parameters.h:58
mp2p_icp::Parameters::debugFileNameFormat
std::string debugFileNameFormat
Definition: Parameters.h:78
Parameters.h
mp2p_icp::Parameters::maxIterations
uint32_t maxIterations
Definition: Parameters.h:34
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Parameters::decimationDebugFiles
uint32_t decimationDebugFiles
Definition: Parameters.h:75
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
MP2P_ICP_GENERATE_DEBUG_FILES
const bool MP2P_ICP_GENERATE_DEBUG_FILES
Definition: Parameters.cpp:19
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