mp2p_icp
include
mp2p_icp
QualityEvaluator_PairedRatio.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/Matcher_Points_DistanceThreshold.h
>
15
#include <
mp2p_icp/QualityEvaluator.h
>
16
17
namespace
mp2p_icp
18
{
26
class
QualityEvaluator_PairedRatio
:
public
QualityEvaluator
27
{
28
DEFINE_MRPT_OBJECT(
QualityEvaluator_PairedRatio
,
mp2p_icp
)
29
30
public
:
39
void
initialize
(
const
mrpt::containers::yaml& params)
override
;
40
41
Result
evaluate
(
42
const
metric_map_t
& pcGlobal,
const
metric_map_t
& pcLocal,
43
const
mrpt::poses::CPose3D& localPose,
44
const
Pairings
& pairingsFromICP)
const override
;
45
46
void
attachToParameterSource
(
ParameterSource
& source)
override
47
{
48
source.
attach
(*
this
);
49
source.
attach
(
matcher_
);
50
}
51
52
private
:
53
Matcher_Points_DistanceThreshold
matcher_
;
54
bool
reuse_icp_pairings
=
true
;
55
56
double
absolute_minimum_pairing_ratio
= 0.20;
57
};
58
59
}
// namespace mp2p_icp
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::ParameterSource
Definition:
Parameterizable.h:42
mp2p_icp::ParameterSource::attach
void attach(Parameterizable &obj)
Definition:
Parameterizable.cpp:15
mp2p_icp::QualityEvaluator::Result
Definition:
QualityEvaluator.h:39
mp2p_icp::Pairings
Definition:
Pairings.h:78
mp2p_icp::QualityEvaluator_PairedRatio::attachToParameterSource
void attachToParameterSource(ParameterSource &source) override
Definition:
QualityEvaluator_PairedRatio.h:46
mp2p_icp::QualityEvaluator_PairedRatio::absolute_minimum_pairing_ratio
double absolute_minimum_pairing_ratio
Definition:
QualityEvaluator_PairedRatio.h:56
mp2p_icp::QualityEvaluator_PairedRatio::matcher_
Matcher_Points_DistanceThreshold matcher_
Definition:
QualityEvaluator_PairedRatio.h:53
mp2p_icp::Matcher_Points_DistanceThreshold
Definition:
Matcher_Points_DistanceThreshold.h:30
mp2p_icp::QualityEvaluator_PairedRatio
Definition:
QualityEvaluator_PairedRatio.h:26
mp2p_icp::QualityEvaluator_PairedRatio::initialize
void initialize(const mrpt::containers::yaml ¶ms) override
Definition:
QualityEvaluator_PairedRatio.cpp:19
mp2p_icp::QualityEvaluator_PairedRatio::reuse_icp_pairings
bool reuse_icp_pairings
Definition:
QualityEvaluator_PairedRatio.h:54
Matcher_Points_DistanceThreshold.h
Pointcloud matcher: fixed distance thresholds.
QualityEvaluator.h
Matching quality evaluator (virtual base class)
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition:
metricmap.h:49
mp2p_icp::QualityEvaluator_PairedRatio::evaluate
Result evaluate(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const override
Definition:
QualityEvaluator_PairedRatio.cpp:38
mp2p_icp::QualityEvaluator
Definition:
QualityEvaluator.h:28
mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12