PairWeights.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 <mrpt/containers/yaml.h>
15 #include <mrpt/serialization/serialization_frwds.h>
16 
17 namespace mp2p_icp
18 {
27 {
32  double pt2pt = 1.0;
33 
34  double pt2ln = 1.0;
35  double pt2pl = 1.0;
36 
37  double ln2ln = 1.0;
38  double pl2pl = 1.0;
39 
40  void load_from(const mrpt::containers::yaml& p);
41  void save_to(mrpt::containers::yaml& p) const;
42  void serializeTo(mrpt::serialization::CArchive& out) const;
43  void serializeFrom(mrpt::serialization::CArchive& in);
44 };
45 
48 } // namespace mp2p_icp
void load_from(const mrpt::containers::yaml &p)
Definition: PairWeights.cpp:18
double ln2ln
Weight of line-to-line pairs.
Definition: PairWeights.h:37
double pt2ln
Weight of point-to-line pairs.
Definition: PairWeights.h:34
double pt2pl
Weight of point-to-plane pairs.
Definition: PairWeights.h:35
void serializeFrom(mrpt::serialization::CArchive &in)
Definition: PairWeights.cpp:42
void serializeTo(mrpt::serialization::CArchive &out) const
Definition: PairWeights.cpp:38
double pl2pl
Weight of plane-to-plane pairs.
Definition: PairWeights.h:38
void save_to(mrpt::containers::yaml &p) const
Definition: PairWeights.cpp:28


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