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 
18 IMPLEMENTS_MRPT_OBJECT(WeightParameters, mrpt::serialization::CSerializable, mp2p_icp)
19 
20 using namespace mp2p_icp;
21 
22 // Implementation of the CSerializable virtual interface:
23 uint8_t WeightParameters::serializeGetVersion() const { return 1; }
24 void WeightParameters::serializeTo(mrpt::serialization::CArchive& out) const
25 {
28 
30 }
31 void WeightParameters::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version)
32 {
33  switch (version)
34  {
35  case 0:
36  case 1:
37  {
39 
40  if (version < 1)
41  {
42  bool dummy_use_robust_kernel;
43  in >> dummy_use_robust_kernel;
44  }
45  else
46  in >> robust_kernel;
47 
49 
50  if (version < 1)
51  {
52  double dummy_robust_kernel_scale;
53  in >> dummy_robust_kernel_scale;
54  }
56  }
57  break;
58  default:
59  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
60  };
61 }
62 
63 void WeightParameters::load_from(const mrpt::containers::yaml& p)
64 {
65  MCP_LOAD_REQ(p, use_scale_outlier_detector);
66  MCP_LOAD_OPT(p, scale_outlier_threshold);
67 
68  MCP_LOAD_REQ(p, robust_kernel);
69  MCP_LOAD_OPT(p, robust_kernel_param);
70 
71  if (p.has("pair_weights")) pair_weights.load_from(p["pair_weights"]);
72 }
73 void WeightParameters::save_to(mrpt::containers::yaml& p) const
74 {
75  MCP_SAVE(p, use_scale_outlier_detector);
76  MCP_SAVE(p, scale_outlier_threshold);
77 
78 #if MRPT_VERSION >= 0x020b03
79  MCP_SAVE(p, robust_kernel);
80 #else
81  MCP_SAVE(p, mrpt::typemeta::enum2str(robust_kernel));
82 #endif
83 
84  MCP_SAVE(p, robust_kernel_param);
85 
86  mrpt::containers::yaml a = mrpt::containers::yaml::Map();
88  p["pair_weights"] = a;
89 }
mp2p_icp::PairWeights::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: PairWeights.cpp:28
mp2p_icp
Definition: covariance.h:17
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
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:63
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:73
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
Definition: WeightParameters.h:26
mp2p_icp::WeightParameters::robust_kernel
RobustKernel robust_kernel
Definition: WeightParameters.h:50


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:50