submodules
mp2p_icp
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-2021 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
{
23
class
QualityEvaluator_PairedRatio
:
public
QualityEvaluator
24
{
25
DEFINE_MRPT_OBJECT(
QualityEvaluator_PairedRatio
,
mp2p_icp
)
26
27
public
:
34
void
initialize
(
const
mrpt::containers::yaml& params)
override
;
35
36
double
evaluate
(
37
const
metric_map_t
& pcGlobal,
const
metric_map_t
& pcLocal,
38
const
mrpt::poses::CPose3D& localPose,
39
const
Pairings
& pairingsFromICP)
const override
;
40
41
private
:
42
Matcher_Points_DistanceThreshold
matcher_
;
43
};
44
45
}
// namespace mp2p_icp
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::Pairings
Definition:
Pairings.h:94
mp2p_icp::QualityEvaluator_PairedRatio::matcher_
Matcher_Points_DistanceThreshold matcher_
Definition:
QualityEvaluator_PairedRatio.h:42
mp2p_icp::Matcher_Points_DistanceThreshold
Definition:
Matcher_Points_DistanceThreshold.h:30
mp2p_icp::QualityEvaluator_PairedRatio
Definition:
QualityEvaluator_PairedRatio.h:23
mp2p_icp::QualityEvaluator_PairedRatio::evaluate
double 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:32
mp2p_icp::QualityEvaluator_PairedRatio::initialize
void initialize(const mrpt::containers::yaml ¶ms) override
Definition:
QualityEvaluator_PairedRatio.cpp:19
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:47
mp2p_icp::QualityEvaluator
Definition:
QualityEvaluator.h:26
mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04