submodules
mp2p_icp
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-2021 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/metricmap.h
>
16
#include <mrpt/containers/yaml.h>
17
#include <mrpt/rtti/CObject.h>
18
#include <mrpt/system/COutputLogger.h>
19
20
namespace
mp2p_icp
21
{
26
class
QualityEvaluator
:
public
mrpt::system::COutputLogger,
27
public
mrpt::rtti::CObject
28
{
29
DEFINE_VIRTUAL_MRPT_OBJECT(
QualityEvaluator
)
30
31
public
:
33
virtual
void
initialize
(
const
mrpt::containers::yaml& params) = 0;
34
36
virtual
double
evaluate
(
37
const
metric_map_t
& pcGlobal,
const
metric_map_t
& pcLocal,
38
const
mrpt::poses::CPose3D& localPose,
39
const
Pairings
& pairingsFromICP)
const
= 0;
40
};
41
42
}
// namespace mp2p_icp
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::Pairings
Definition:
Pairings.h:94
mp2p_icp::QualityEvaluator::evaluate
virtual double evaluate(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const =0
Pairings.h
Common types for all SE(3) optimal transformation methods.
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition:
metricmap.h:47
mp2p_icp::QualityEvaluator::initialize
virtual void initialize(const mrpt::containers::yaml ¶ms)=0
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