Main Page
Related Pages
Modules
Namespaces
Namespace List
Namespace Members
All
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Functions
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
w
Variables
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
x
y
z
Typedefs
a
b
c
d
f
g
i
l
m
n
r
s
t
u
w
Enumerations
Enumerator
a
b
c
d
e
f
g
h
k
l
n
o
r
s
t
u
v
y
Classes
Class List
Class Hierarchy
Class Members
All
:
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
~
Functions
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
~
Variables
_
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
Enumerations
Enumerator
a
b
c
d
f
g
h
i
k
l
m
n
p
r
s
t
u
v
w
Related Functions
:
_
a
g
i
l
n
o
p
r
s
t
u
Files
File List
File Members
All
_
a
b
c
d
e
f
g
i
l
m
n
o
p
q
r
s
t
u
v
w
y
z
Functions
_
a
b
c
d
e
g
i
l
m
n
o
p
r
s
t
u
v
Variables
_
a
c
d
g
i
m
n
r
s
t
v
w
Typedefs
b
c
d
i
m
n
o
p
q
s
t
v
Macros
_
a
b
c
d
e
f
g
i
l
m
n
o
p
r
s
t
y
z
mp2p_icp
include
mp2p_icp
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-2024 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
{
26
struct
PairWeights
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
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
Definition:
PairWeights.h:26
mp2p_icp::PairWeights::pt2pt
double pt2pt
Definition:
PairWeights.h:32
mp2p_icp
Author(s):
autogenerated on Wed Feb 26 2025 03:45:47