Solver.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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
15 #include <mp2p_icp/Pairings.h>
18 #include <mrpt/containers/yaml.h>
19 #include <mrpt/poses/CPose3D.h>
20 #include <mrpt/poses/CPose3DPDFGaussianInf.h>
21 #include <mrpt/rtti/CObject.h>
22 #include <mrpt/system/COutputLogger.h>
23 
24 #include <any>
25 #include <optional>
26 
27 namespace mp2p_icp
28 {
29 class Solver;
30 
36 {
37  SolverContext() = default;
38 
39  std::optional<mrpt::poses::CPose3D> guessRelativePose;
40  std::optional<mrpt::poses::CPose3D> currentCorrectionFromInitialGuess;
41  std::optional<mrpt::poses::CPose3D> lastIcpStepIncrement;
42 
48  std::optional<mrpt::poses::CPose3DPDFGaussianInf> prior;
49 
50  // room for optional solver-specific context:
51  mutable std::map<const Solver*, std::map<std::string, std::any>>
53 
54  std::optional<uint32_t> icpIteration;
55 };
56 
65 class Solver : public mrpt::system::COutputLogger,
66  public mrpt::rtti::CObject,
68 {
69  DEFINE_VIRTUAL_MRPT_OBJECT(Solver)
70 
71  public:
73  virtual void initialize(const mrpt::containers::yaml& params);
74 
81  virtual bool optimal_pose(
82  const Pairings& pairings, OptimalTF_Result& out,
83  const SolverContext& sc) const;
84 
85  uint32_t runFromIteration = 0;
86  uint32_t runUpToIteration = 0;
87 
89 
91  bool enabled = true;
92 
93  protected:
94  virtual bool impl_optimal_pose(
95  const Pairings& pairings, OptimalTF_Result& out,
96  const SolverContext& sc) const = 0;
97 };
98 
99 } // namespace mp2p_icp
mp2p_icp::Solver::runFromIteration
uint32_t runFromIteration
Definition: Solver.h:85
mp2p_icp::Solver::optimal_pose
virtual bool optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const
Definition: Solver.cpp:28
mp2p_icp
Definition: covariance.h:17
mp2p_icp::SolverContext::perSolverPersistentData
std::map< const Solver *, std::map< std::string, std::any > > perSolverPersistentData
Definition: Solver.h:52
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::SolverContext
Definition: Solver.h:35
OptimalTF_Result.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::SolverContext::guessRelativePose
std::optional< mrpt::poses::CPose3D > guessRelativePose
Definition: Solver.h:39
mp2p_icp::SolverContext::icpIteration
std::optional< uint32_t > icpIteration
Definition: Solver.h:54
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::SolverContext::lastIcpStepIncrement
std::optional< mrpt::poses::CPose3D > lastIcpStepIncrement
Definition: Solver.h:41
mp2p_icp::Solver
Definition: Solver.h:65
mp2p_icp::Solver::runUntilTranslationCorrectionSmallerThan
double runUntilTranslationCorrectionSmallerThan
Definition: Solver.h:88
mp2p_icp::Parameterizable
Definition: Parameterizable.h:85
mp2p_icp::Solver::impl_optimal_pose
virtual bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const =0
mp2p_icp::SolverContext::prior
std::optional< mrpt::poses::CPose3DPDFGaussianInf > prior
Definition: Solver.h:48
mp2p_icp::SolverContext::SolverContext
SolverContext()=default
Pairings.h
Common types for all SE(3) optimal transformation methods.
WeightParameters.h
Common types for all SE(3) optimal transformation methods.
Parameterizable.h
mp2p_icp::Solver::initialize
virtual void initialize(const mrpt::containers::yaml &params)
Definition: Solver.cpp:20
mp2p_icp::Solver::runUpToIteration
uint32_t runUpToIteration
0: no limit
Definition: Solver.h:86
mp2p_icp::SolverContext::currentCorrectionFromInitialGuess
std::optional< mrpt::poses::CPose3D > currentCorrectionFromInitialGuess
Definition: Solver.h:40
mp2p_icp::Solver::enabled
bool enabled
Definition: Solver.h:91


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:26