mp2p_icp
src
PairWeights.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
* ------------------------------------------------------------------------- */
13
#include <
mp2p_icp/PairWeights.h
>
14
#include <mrpt/serialization/CArchive.h>
15
16
using namespace
mp2p_icp
;
17
18
void
PairWeights::load_from
(
const
mrpt::containers::yaml& p)
19
{
20
MCP_LOAD_REQ(p,
pt2pt
);
21
MCP_LOAD_REQ(p,
pt2pl
);
22
MCP_LOAD_REQ(p,
pt2ln
);
23
24
MCP_LOAD_REQ(p,
ln2ln
);
25
MCP_LOAD_REQ(p,
pl2pl
);
26
}
27
28
void
PairWeights::save_to
(mrpt::containers::yaml& p)
const
29
{
30
MCP_SAVE(p,
pt2pt
);
31
MCP_SAVE(p,
pt2pl
);
32
MCP_SAVE(p,
pt2ln
);
33
34
MCP_SAVE(p,
ln2ln
);
35
MCP_SAVE(p,
pl2pl
);
36
}
37
38
void
PairWeights::serializeTo
(mrpt::serialization::CArchive&
out
)
const
39
{
40
out
<<
pt2pt
<<
pt2pl
<<
pt2ln
<<
ln2ln
<<
pl2pl
;
41
}
42
void
PairWeights::serializeFrom
(mrpt::serialization::CArchive& in)
43
{
44
in >>
pt2pt
>>
pt2pl
>>
pt2ln
>>
ln2ln
>>
pl2pl
;
45
}
PairWeights.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::PairWeights::save_to
void save_to(mrpt::containers::yaml &p) const
Definition:
PairWeights.cpp:28
mp2p_icp
Definition:
covariance.h:17
kitti-batch-convert.out
string out
Definition:
kitti-batch-convert.py:7
mp2p_icp::PairWeights::load_from
void load_from(const mrpt::containers::yaml &p)
Definition:
PairWeights.cpp:18
mp2p_icp::PairWeights::pl2pl
double pl2pl
Weight of plane-to-plane pairs.
Definition:
PairWeights.h:38
mp2p_icp::PairWeights::serializeTo
void serializeTo(mrpt::serialization::CArchive &out) const
Definition:
PairWeights.cpp:38
mp2p_icp::PairWeights::ln2ln
double ln2ln
Weight of line-to-line pairs.
Definition:
PairWeights.h:37
mp2p_icp::PairWeights::pt2pl
double pt2pl
Weight of point-to-plane pairs.
Definition:
PairWeights.h:35
mp2p_icp::PairWeights::serializeFrom
void serializeFrom(mrpt::serialization::CArchive &in)
Definition:
PairWeights.cpp:42
mp2p_icp::PairWeights::pt2ln
double pt2ln
Weight of point-to-line pairs.
Definition:
PairWeights.h:34
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition:
PairWeights.h:32
mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12