Solver_OLAE.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/Solver.h>
15 
16 namespace mp2p_icp
17 {
23 class Solver_OLAE : public Solver
24 {
25  DEFINE_MRPT_OBJECT(Solver_OLAE, mp2p_icp)
26  public:
30 
31  void initialize(const mrpt::containers::yaml& params) override;
32 
33  protected:
34  // See base class docs
35  bool impl_optimal_pose(
36  const Pairings& pairings, OptimalTF_Result& out,
37  const SolverContext& sc) const override;
38 };
39 
40 } // namespace mp2p_icp
WeightParameters pairingsWeightParameters
Definition: Solver_OLAE.h:29
void initialize(const mrpt::containers::yaml &params) override
Definition: Solver_OLAE.cpp:23
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
Definition: Solver_OLAE.cpp:37
Virtual base class for optimal alignment solvers (one step in ICP).


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