WeightParameters.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  * ------------------------------------------------------------------------- */
14 #include <mrpt/serialization/CArchive.h>
15 #include <mrpt/serialization/optional_serialization.h>
16 #include <mrpt/version.h>
17 
19  WeightParameters, mrpt::serialization::CSerializable, mp2p_icp)
20 
21 using namespace mp2p_icp;
22 
23 // Implementation of the CSerializable virtual interface:
24 uint8_t WeightParameters::serializeGetVersion() const { return 1; }
25 void WeightParameters::serializeTo(mrpt::serialization::CArchive& out) const
26 {
29 
31 }
32 void WeightParameters::serializeFrom(
33  mrpt::serialization::CArchive& in, uint8_t version)
34 {
35  switch (version)
36  {
37  case 0:
38  case 1:
39  {
41 
42  if (version < 1)
43  {
44  bool dummy_use_robust_kernel;
45  in >> dummy_use_robust_kernel;
46  }
47  else
48  in >> robust_kernel;
49 
51 
52  if (version < 1)
53  {
54  double dummy_robust_kernel_scale;
55  in >> dummy_robust_kernel_scale;
56  }
58  }
59  break;
60  default:
61  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
62  };
63 }
64 
65 void WeightParameters::load_from(const mrpt::containers::yaml& p)
66 {
67  MCP_LOAD_REQ(p, use_scale_outlier_detector);
68  MCP_LOAD_OPT(p, scale_outlier_threshold);
69 
70  MCP_LOAD_REQ(p, robust_kernel);
71  MCP_LOAD_OPT(p, robust_kernel_param);
72 
73  if (p.has("pair_weights")) pair_weights.load_from(p["pair_weights"]);
74 }
75 void WeightParameters::save_to(mrpt::containers::yaml& p) const
76 {
77  MCP_SAVE(p, use_scale_outlier_detector);
78  MCP_SAVE(p, scale_outlier_threshold);
79 
80 #if MRPT_VERSION >= 0x020b03
81  MCP_SAVE(p, robust_kernel);
82 #else
83  MCP_SAVE(p, mrpt::typemeta::enum2str(robust_kernel));
84 #endif
85 
86  MCP_SAVE(p, robust_kernel_param);
87 
88  mrpt::containers::yaml a = mrpt::containers::yaml::Map();
90  p["pair_weights"] = a;
91 }
mp2p_icp::PairWeights::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: PairWeights.cpp:28
mp2p_icp
Definition: covariance.h:17
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(WeightParameters, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:35
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:46
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::WeightParameters::robust_kernel_param
double robust_kernel_param
Definition: WeightParameters.h:56
mp2p_icp::PairWeights::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: PairWeights.cpp:18
mp2p_icp::WeightParameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: WeightParameters.cpp:65
mp2p_icp::PairWeights::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: PairWeights.cpp:38
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::WeightParameters::currentEstimateForRobust
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
Definition: WeightParameters.h:54
mp2p_icp::WeightParameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: WeightParameters.cpp:75
mp2p_icp::PairWeights::serializeFrom
void serializeFrom(mrpt::serialization::CArchive &in)
Definition: PairWeights.cpp:42
mp2p_icp::WeightParameters::scale_outlier_threshold
double scale_outlier_threshold
Definition: WeightParameters.h:43
mp2p_icp::WeightParameters::robust_kernel
RobustKernel robust_kernel
Definition: WeightParameters.h:50


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:26