WeightParameters.h
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  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/PairWeights.h>
15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/poses/CPose3D.h>
17 #include <mrpt/serialization/CSerializable.h>
18 
19 namespace mp2p_icp
20 {
25 struct WeightParameters : public mrpt::serialization::CSerializable
26 {
27  DEFINE_SERIALIZABLE(WeightParameters, mp2p_icp)
28 
29  public:
35 
43 
46 
49  bool use_robust_kernel = false;
50 
53  std::optional<mrpt::poses::CPose3D> currentEstimateForRobust;
54 
55  double robust_kernel_param{mrpt::DEG2RAD(0.1)}, robust_kernel_scale{400.0};
56 
59  void load_from(const mrpt::containers::yaml& p);
60  void save_to(mrpt::containers::yaml& p) const;
61 };
62 
65 } // namespace mp2p_icp
PairWeights pair_weights
See docs for PairWeights.
void save_to(mrpt::containers::yaml &p) const
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
void load_from(const mrpt::containers::yaml &p)
Common types for all SE(3) optimal transformation methods.


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43