submodules
mp2p_icp
mp2p_icp
include
mp2p_icp
QualityEvaluator_Voxels.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/QualityEvaluator.h
>
15
16
namespace
mp2p_icp
17
{
22
class
QualityEvaluator_Voxels
:
public
QualityEvaluator
23
{
24
DEFINE_MRPT_OBJECT(
QualityEvaluator_Voxels
,
mp2p_icp
)
25
26
public
:
27
QualityEvaluator_Voxels
();
28
29
// See base class
30
void
initialize
(
const
mrpt::containers::yaml& params)
override
;
31
double
evaluate
(
32
const
metric_map_t
& pcGlobal,
const
metric_map_t
& pcLocal,
33
const
mrpt::poses::CPose3D& localPose,
34
const
Pairings
& pairingsFromICP)
const override
;
35
36
double
resolution
= 0.25;
37
double
maxOccupancyUpdateCertainty
= 0.65;
38
double
maxFreenessUpdateCertainty
= 0.55;
39
double
dist2quality_scale
= 0.1;
40
42
std::set<std::string>
pointLayers
= {
mp2p_icp::metric_map_t::PT_LAYER_RAW
};
43
};
44
45
}
// namespace mp2p_icp
mp2p_icp
Definition:
covariance.h:17
mp2p_icp::QualityEvaluator_Voxels::maxFreenessUpdateCertainty
double maxFreenessUpdateCertainty
<[0.5,1.0]
Definition:
QualityEvaluator_Voxels.h:38
mp2p_icp::QualityEvaluator_Voxels
Definition:
QualityEvaluator_Voxels.h:22
mp2p_icp::Pairings
Definition:
Pairings.h:94
mp2p_icp::QualityEvaluator_Voxels::initialize
void initialize(const mrpt::containers::yaml ¶ms) override
Definition:
QualityEvaluator_Voxels.cpp:27
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition:
metricmap.h:56
mp2p_icp::QualityEvaluator_Voxels::dist2quality_scale
double dist2quality_scale
Definition:
QualityEvaluator_Voxels.h:39
mp2p_icp::QualityEvaluator_Voxels::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_Voxels.cpp:53
mp2p_icp::QualityEvaluator_Voxels::maxOccupancyUpdateCertainty
double maxOccupancyUpdateCertainty
Definition:
QualityEvaluator_Voxels.h:37
mp2p_icp::QualityEvaluator_Voxels::resolution
double resolution
voxel size [meters]
Definition:
QualityEvaluator_Voxels.h:36
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_Voxels::pointLayers
std::set< std::string > pointLayers
Definition:
QualityEvaluator_Voxels.h:42
mp2p_icp::QualityEvaluator_Voxels::QualityEvaluator_Voxels
QualityEvaluator_Voxels()
Definition:
QualityEvaluator_Voxels.cpp:22
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