Matcher.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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Pairings.h>
15 #include <mp2p_icp/metricmap.h>
16 #include <mrpt/containers/yaml.h>
17 #include <mrpt/rtti/CObject.h>
18 #include <mrpt/system/COutputLogger.h>
19 
20 namespace mp2p_icp
21 {
27 {
28  MatchContext() = default;
29 
31  uint32_t icpIteration = 0;
32 };
33 
34 struct MatchState
35 {
36  MatchState(const metric_map_t& pcGlobal, const metric_map_t& pcLocal)
37  : pcGlobal_(pcGlobal), pcLocal_(pcLocal)
38  {
39  initialize();
40  }
41 
45 
48 
51  void initialize()
52  {
55  }
56 
57  private:
60 };
61 
70 class Matcher : public mrpt::system::COutputLogger, public mrpt::rtti::CObject
71 {
72  DEFINE_VIRTUAL_MRPT_OBJECT(Matcher)
73 
74  public:
76  virtual void initialize(const mrpt::containers::yaml& params);
77 
82  virtual bool match(
83  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
84  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
85  MatchState& ms, Pairings& out) const;
86 
87  uint32_t runFromIteration = 0;
88  uint32_t runUpToIteration = 0;
89 
90  protected:
92  virtual bool impl_match(
93  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
94  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
95  MatchState& ms, Pairings& out) const = 0;
96 };
97 
98 using matcher_list_t = std::vector<mp2p_icp::Matcher::Ptr>;
99 
108  const matcher_list_t& matchers, const metric_map_t& pcGlobal,
109  const metric_map_t& pcLocal, const mrpt::poses::CPose3D& local_wrt_global,
110  const MatchContext& mc,
111  const mrpt::optional_ref<MatchState>& userProvidedMS = std::nullopt);
112 
113 } // namespace mp2p_icp
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::MatchState::MatchState
MatchState(const metric_map_t &pcGlobal, const metric_map_t &pcLocal)
Definition: Matcher.h:36
mp2p_icp::MatchContext::MatchContext
MatchContext()=default
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::pointcloud_bitfield_t::initialize_from
void initialize_from(const metric_map_t &pc, bool initBoolValue=false)
Definition: metricmap.h:228
mp2p_icp::MatchState::initialize
void initialize()
Definition: Matcher.h:51
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
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::MatchState::pcLocal_
const metric_map_t & pcLocal_
Definition: Matcher.h:59
mp2p_icp::MatchState::globalPairedBitField
pointcloud_bitfield_t globalPairedBitField
Like localPairedBitField for the global map.
Definition: Matcher.h:47
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
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
mp2p_icp::MatchState::pcGlobal_
const metric_map_t & pcGlobal_
Definition: Matcher.h:58
mp2p_icp::MatchState::localPairedBitField
pointcloud_bitfield_t localPairedBitField
Definition: Matcher.h:44
mp2p_icp::pointcloud_bitfield_t
Definition: metricmap.h:216
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