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 
16 
17 namespace mp2p_icp
18 {
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:
43 };
44 
45 } // namespace mp2p_icp
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
double evaluate(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const override
Matching quality evaluator (virtual base class)
void initialize(const mrpt::containers::yaml &params) override
Pointcloud matcher: fixed distance thresholds.


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43