mp2p_icp/src/Matcher.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/Matcher.h>
14 #include <mrpt/core/exceptions.h>
15 
16 IMPLEMENTS_VIRTUAL_MRPT_OBJECT(Matcher, mrpt::rtti::CObject, mp2p_icp)
17 
18 using namespace mp2p_icp;
19 
20 void Matcher::initialize(const mrpt::containers::yaml& params)
21 {
22  MCP_LOAD_OPT(params, runFromIteration);
23  MCP_LOAD_OPT(params, runUpToIteration);
24  MCP_LOAD_OPT(params, enabled);
25 }
26 
28  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
29  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
30  MatchState& ms, Pairings& out) const
31 {
32  if (!enabled) return false;
33  if (mc.icpIteration < runFromIteration) return false;
35  return false;
36  return impl_match(pcGlobal, pcLocal, localPose, mc, ms, out);
37 }
38 
40  const matcher_list_t& matchers, const metric_map_t& pcGlobal,
41  const metric_map_t& pcLocal, const mrpt::poses::CPose3D& local_wrt_global,
42  const MatchContext& mc,
43  const mrpt::optional_ref<MatchState>& userProvidedMS)
44 {
45  Pairings pairings;
46 
47  MatchState* ms = nullptr;
48 
49  std::optional<MatchState> localMS;
50 
51  if (userProvidedMS.has_value())
52  {
53  // Use user-provided memory storage:
54  ms = &userProvidedMS.value().get();
55  }
56  else
57  {
58  // Reserve here:
59  localMS.emplace(pcGlobal, pcLocal);
60  ms = &localMS.value();
61  }
62 
63  bool anyRun = false;
64 
65  for (const auto& matcher : matchers)
66  {
67  ASSERT_(matcher);
68  Pairings pc;
69  bool hasRun =
70  matcher->match(pcGlobal, pcLocal, local_wrt_global, mc, *ms, pc);
71  anyRun = anyRun || hasRun;
72  pairings.push_back(pc);
73  }
74 
75  if (!anyRun)
76  {
77  std::cerr << "[mp2p_icp::run_matchers] WARNING: No active matcher "
78  "actually ran on the two maps."
79  << std::endl;
80  }
81 
82  return pairings;
83 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher
Definition: Matcher.h:72
mp2p_icp::Matcher::runUpToIteration
uint32_t runUpToIteration
0: no limit
Definition: Matcher.h:92
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::Matcher::match
virtual bool match(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const MatchContext &mc, MatchState &ms, Pairings &out) const
Definition: mp2p_icp/src/Matcher.cpp:27
mp2p_icp::Matcher::enabled
bool enabled
Definition: Matcher.h:93
mp2p_icp::MatchState
Definition: Matcher.h:36
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Matcher::runFromIteration
uint32_t runFromIteration
Definition: Matcher.h:91
mp2p_icp::MatchContext
Definition: Matcher.h:28
mp2p_icp::Pairings::push_back
virtual void push_back(const Pairings &o)
Definition: Pairings.cpp:121
Matcher.h
Pointcloud matching generic base class.
mp2p_icp::Matcher::impl_match
virtual bool impl_match(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const MatchContext &mc, MatchState &ms, Pairings &out) const =0
mp2p_icp::run_matchers
Pairings run_matchers(const matcher_list_t &matchers, const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &local_wrt_global, const MatchContext &mc, const mrpt::optional_ref< MatchState > &userProvidedMS=std::nullopt)
Definition: mp2p_icp/src/Matcher.cpp:39
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:48
IMPLEMENTS_VIRTUAL_MRPT_OBJECT
IMPLEMENTS_VIRTUAL_MRPT_OBJECT(FilterBase, mrpt::rtti::CObject, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::matcher_list_t
std::vector< mp2p_icp::Matcher::Ptr > matcher_list_t
Definition: Matcher.h:103
mp2p_icp::Matcher::initialize
virtual void initialize(const mrpt::containers::yaml &params)
Definition: mp2p_icp/src/Matcher.cpp:20
mp2p_icp::MatchContext::icpIteration
uint32_t icpIteration
The ICP iteration number we are in:
Definition: Matcher.h:33


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