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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
7 #include <mp2p_icp/Parameters.h>
8 #include <mrpt/serialization/CArchive.h>
9 #include <mrpt/serialization/stl_serialization.h>
10 
11 IMPLEMENTS_MRPT_OBJECT(Parameters, mrpt::serialization::CSerializable, mp2p_icp)
12 
13 using namespace mp2p_icp;
14 
15 // Implementation of the CSerializable virtual interface:
16 uint8_t Parameters::serializeGetVersion() const { return 0; }
17 void Parameters::serializeTo(mrpt::serialization::CArchive& out) const
18 {
22 }
23 void Parameters::serializeFrom(
24  mrpt::serialization::CArchive& in, uint8_t version)
25 {
26  *this = Parameters();
27 
28  switch (version)
29  {
30  case 0:
31  {
35  }
36  break;
37  default:
38  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
39  };
40 }
41 
42 void Parameters::load_from(const mrpt::containers::yaml& p)
43 {
44  MCP_LOAD_REQ(p, maxIterations);
45  MCP_LOAD_OPT(p, minAbsStep_trans);
46  MCP_LOAD_OPT(p, minAbsStep_rot);
47  MCP_LOAD_OPT(p, generateDebugFiles);
48  MCP_LOAD_OPT(p, debugFileNameFormat);
49  MCP_LOAD_OPT(p, debugPrintIterationProgress);
50 }
51 void Parameters::save_to(mrpt::containers::yaml& p) const
52 {
53  MCP_SAVE(p, maxIterations);
54  MCP_SAVE(p, minAbsStep_trans);
55  MCP_SAVE(p, minAbsStep_rot);
56  MCP_SAVE(p, generateDebugFiles);
57  MCP_SAVE(p, debugFileNameFormat);
58  MCP_SAVE(p, debugPrintIterationProgress);
59 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Parameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: Parameters.cpp:51
mp2p_icp::Parameters::minAbsStep_trans
double minAbsStep_trans
Definition: Parameters.h:38
Parameters
PM::Parameters Parameters
Definition: filterProfiler.cpp:20
mp2p_icp::Parameters::generateDebugFiles
bool generateDebugFiles
Definition: Parameters.h:57
mp2p_icp::Parameters::debugFileNameFormat
std::string debugFileNameFormat
Definition: Parameters.h:60
Parameters.h
mp2p_icp::Parameters::maxIterations
uint32_t maxIterations
Definition: Parameters.h:33
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Parameters::minAbsStep_rot
double minAbsStep_rot
Definition: Parameters.h:43
mp2p_icp::Parameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: Parameters.cpp:42
mp2p_icp::Parameters::debugPrintIterationProgress
bool debugPrintIterationProgress
Definition: Parameters.h:64
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
mp2p_icp::Parameters
Definition: Parameters.h:25


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04