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-2021 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 
18  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 0; }
24 void WeightParameters::serializeTo(mrpt::serialization::CArchive& out) const
25 {
30 }
31 void WeightParameters::serializeFrom(
32  mrpt::serialization::CArchive& in, uint8_t version)
33 {
34  switch (version)
35  {
36  case 0:
37  {
42  }
43  break;
44  default:
45  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
46  };
47 }
48 
49 void WeightParameters::load_from(const mrpt::containers::yaml& p)
50 {
51  MCP_LOAD_REQ(p, use_scale_outlier_detector);
52  MCP_LOAD_OPT(p, scale_outlier_threshold);
53 
54  MCP_LOAD_REQ(p, use_robust_kernel);
55  MCP_LOAD_OPT_DEG(p, robust_kernel_param);
56  MCP_LOAD_OPT(p, robust_kernel_scale);
57 
58  if (p.has("pair_weights")) pair_weights.load_from(p["pair_weights"]);
59 }
60 void WeightParameters::save_to(mrpt::containers::yaml& p) const
61 {
62  MCP_SAVE(p, use_scale_outlier_detector);
63  MCP_SAVE(p, scale_outlier_threshold);
64 
65  MCP_SAVE(p, use_robust_kernel);
66  MCP_SAVE_DEG(p, robust_kernel_param);
67  MCP_SAVE(p, robust_kernel_scale);
68 
69  mrpt::containers::yaml a = mrpt::containers::yaml::Map();
71  p["pair_weights"] = a;
72 }
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:34
mp2p_icp::WeightParameters::robust_kernel_scale
double robust_kernel_scale
Definition: WeightParameters.h:55
mp2p_icp::WeightParameters::pair_weights
PairWeights pair_weights
See docs for PairWeights.
Definition: WeightParameters.h:45
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:55
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:49
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:53
mp2p_icp::WeightParameters::save_to
void save_to(mrpt::containers::yaml &p) const
Definition: WeightParameters.cpp:60
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:42
mp2p_icp::WeightParameters::use_robust_kernel
bool use_robust_kernel
Definition: WeightParameters.h:49


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