Solver_Horn.cpp
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  * ------------------------------------------------------------------------- */
13 #include <mp2p_icp/Solver_Horn.h>
16 #include <mrpt/core/exceptions.h>
17 #include <mrpt/math/geometry.h>
18 
19 #include <iostream>
20 
22 
23 using namespace mp2p_icp;
24 
25 void Solver_Horn::initialize(const mrpt::containers::yaml& p)
26 {
28 
29  if (p.has("pairingsWeightParameters"))
30  pairingsWeightParameters.load_from(p["pairingsWeightParameters"]);
31 }
32 
34  const Pairings& pairings, OptimalTF_Result& out,
35  [[maybe_unused]] const SolverContext& sc) const
36 {
37  MRPT_START
38 
40 
41  const Pairings* effectivePairings = &pairings;
42  std::optional<Pairings> altPairings;
43 
44  if (!pairings.paired_pt2ln.empty() || !pairings.paired_pt2pl.empty())
45  {
46  altPairings = pt2ln_pl_to_pt2pt(pairings, sc);
47  effectivePairings = &altPairings.value();
48  }
49 
50  // Compute the optimal pose, and return its validity:
51  return optimal_tf_horn(*effectivePairings, pairingsWeightParameters, out);
52 
53  MRPT_END
54 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::pt2ln_pl_to_pt2pt
Pairings pt2ln_pl_to_pt2pt(const Pairings &in, const SolverContext &sc)
Definition: pt2ln_pl_to_pt2pt.cpp:39
mp2p_icp::optimal_tf_horn
bool optimal_tf_horn(const mp2p_icp::Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_horn.cpp:199
mp2p_icp::Solver_Horn::pairingsWeightParameters
WeightParameters pairingsWeightParameters
Definition: Solver_Horn.h:28
mp2p_icp::Pairings
Definition: Pairings.h:78
mp2p_icp::SolverContext
Definition: Solver.h:36
pt2ln_pl_to_pt2pt.h
Converter of pairings.
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::Solver_Horn
Definition: Solver_Horn.h:22
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Solver
Definition: Solver.h:66
mp2p_icp::WeightParameters::load_from
void load_from(const mrpt::containers::yaml &p)
Definition: WeightParameters.cpp:65
Solver_Horn.h
ICP solver for pointclouds split in different "layers".
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
mp2p_icp::Solver_Horn::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Solver_Horn.cpp:25
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:89
mp2p_icp::Solver::initialize
virtual void initialize(const mrpt::containers::yaml &params)
Definition: Solver.cpp:20
mp2p_icp::Solver_Horn::impl_optimal_pose
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
Definition: Solver_Horn.cpp:33
optimal_tf_horn.h
Classic Horn's solution for optimal SE(3) transformation.
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:90


mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:41