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-2021 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  runFromIteration = params.getOrDefault<uint32_t>("runFromIteration", 0);
23  runUpToIteration = params.getOrDefault<uint32_t>("runUpToIteration", 0);
24 }
25 
27  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
28  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
29  MatchState& ms, Pairings& out) const
30 {
31  if (mc.icpIteration < runFromIteration) return false;
33  return false;
34  return impl_match(pcGlobal, pcLocal, localPose, mc, ms, out);
35 }
36 
38  const matcher_list_t& matchers, const metric_map_t& pcGlobal,
39  const metric_map_t& pcLocal, const mrpt::poses::CPose3D& local_wrt_global,
40  const MatchContext& mc,
41  const mrpt::optional_ref<MatchState>& userProvidedMS)
42 {
43  Pairings pairings;
44 
45  MatchState* ms = nullptr;
46 
47  std::optional<MatchState> localMS;
48 
49  if (userProvidedMS.has_value())
50  {
51  // Use user-provided memory storage:
52  ms = &userProvidedMS.value().get();
53  }
54  else
55  {
56  // Reserve here:
57  localMS.emplace(pcGlobal, pcLocal);
58  ms = &localMS.value();
59  }
60 
61  bool anyRun = false;
62 
63  for (const auto& matcher : matchers)
64  {
65  ASSERT_(matcher);
66  Pairings pc;
67  bool hasRun =
68  matcher->match(pcGlobal, pcLocal, local_wrt_global, mc, *ms, pc);
69  anyRun = anyRun || hasRun;
70  pairings.push_back(pc);
71  }
72 
73  if (!anyRun)
74  {
75  std::cerr << "[mp2p_icp::run_matchers] WARNING: No active matcher "
76  "actually ran on the two maps."
77  << std::endl;
78  }
79 
80  return pairings;
81 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher
Definition: Matcher.h:70
mp2p_icp::Matcher::runUpToIteration
uint32_t runUpToIteration
0: no limit
Definition: Matcher.h:88
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:26
mp2p_icp::MatchState
Definition: Matcher.h:34
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::Matcher::runFromIteration
uint32_t runFromIteration
Definition: Matcher.h:87
mp2p_icp::MatchContext
Definition: Matcher.h:26
mp2p_icp::Pairings::push_back
virtual void push_back(const Pairings &o)
Definition: Pairings.cpp:117
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:37
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
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:98
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:31


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:03