mp2p_icp
include
mp2p_icp
QualityEvaluator.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 <
mp2p_icp/Pairings.h
>
15
#include <
mp2p_icp/Parameterizable.h
>
16
#include <
mp2p_icp/metricmap.h
>
17
#include <mrpt/containers/yaml.h>
18
#include <mrpt/rtti/CObject.h>
19
#include <mrpt/system/COutputLogger.h>
20
#include <mrpt/version.h>
21
22
namespace
mp2p_icp
23
{
28
class
QualityEvaluator
:
public
mrpt::system::COutputLogger,
29
public
mrpt::rtti::CObject,
30
public
mp2p_icp::Parameterizable
31
{
32
#if MRPT_VERSION < 0x020e00
33
DEFINE_VIRTUAL_MRPT_OBJECT(
QualityEvaluator
)
34
#else
35
DEFINE_VIRTUAL_MRPT_OBJECT(
QualityEvaluator
,
mp2p_icp
)
36
#endif
37
38
public
:
39
struct
Result
40
{
42
double
quality
= .0;
43
46
bool
hard_discard
=
false
;
47
};
48
50
virtual
void
initialize
(
const
mrpt::containers::yaml& params) = 0;
51
53
virtual
Result
evaluate
(
54
const
metric_map_t
& pcGlobal,
const
metric_map_t
& pcLocal,
55
const
mrpt::poses::CPose3D& localPose,
56
const
Pairings
& pairingsFromICP)
const
= 0;
57
};
58
59
}
// namespace mp2p_icp
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::QualityEvaluator::Result
Definition:
QualityEvaluator.h:39
mp2p_icp::Pairings
Definition:
Pairings.h:78
mp2p_icp::QualityEvaluator::Result::quality
double quality
The resulting quality measure, in the range [0,1].
Definition:
QualityEvaluator.h:42
mp2p_icp::Parameterizable
Definition:
Parameterizable.h:85
Pairings.h
Common types for all SE(3) optimal transformation methods.
Parameterizable.h
mp2p_icp::QualityEvaluator::Result::hard_discard
bool hard_discard
Definition:
QualityEvaluator.h:46
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp::QualityEvaluator::evaluate
virtual Result evaluate(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const =0
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition:
metricmap.h:49
mp2p_icp::QualityEvaluator::initialize
virtual void initialize(const mrpt::containers::yaml ¶ms)=0
mp2p_icp::QualityEvaluator
Definition:
QualityEvaluator.h:28
mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:40