Solver_OLAE.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_OLAE.h>
16 
17 #include <iostream>
18 
20 
21 using namespace mp2p_icp;
22 
23 void Solver_OLAE::initialize(const mrpt::containers::yaml& p)
24 {
26 
27  if (p.has("pairingsWeightParameters"))
28  pairingsWeightParameters.load_from(p["pairingsWeightParameters"]);
29 }
30 
31 /* Save params:
32  mrpt::containers::yaml pp = mrpt::containers::yaml::Map();
33  pairingsWeightParameters.save_to(pp);
34  p["pairingsWeightParameters"] = std::move(pp);
35 */
36 
38  const Pairings& pairings, OptimalTF_Result& out,
39  [[maybe_unused]] const SolverContext& sc) const
40 {
41  MRPT_START
42 
44 
45  const Pairings* effectivePairings = &pairings;
46  std::optional<Pairings> altPairings;
47 
48  if (!pairings.paired_pt2ln.empty() || !pairings.paired_pt2pl.empty())
49  {
50  altPairings = pt2ln_pl_to_pt2pt(pairings, sc);
51  effectivePairings = &altPairings.value();
52  }
53 
54  // Compute the optimal pose, and return its validity:
55  return optimal_tf_olae(*effectivePairings, pairingsWeightParameters, out);
56 
57  MRPT_END
58 }
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::Pairings
Definition: Pairings.h:78
mp2p_icp::SolverContext
Definition: Solver.h:36
optimal_tf_olae.h
OLAE algorithm to find the SE(3) optimal transformation.
pt2ln_pl_to_pt2pt.h
Converter of pairings.
mp2p_icp::Solver_OLAE::impl_optimal_pose
bool impl_optimal_pose(const Pairings &pairings, OptimalTF_Result &out, const SolverContext &sc) const override
Definition: Solver_OLAE.cpp:37
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
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
mp2p_icp::Solver_OLAE::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Solver_OLAE.cpp:23
mp2p_icp::optimal_tf_olae
bool optimal_tf_olae(const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_olae.cpp:233
Solver_OLAE.h
ICP registration for points and planes.
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
mp2p_icp::Solver_OLAE
Definition: Solver_OLAE.h:23
mp2p_icp::Solver_OLAE::pairingsWeightParameters
WeightParameters pairingsWeightParameters
Definition: Solver_OLAE.h:29
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::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:90


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