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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Pairings.h>
16 #include <mp2p_icp/metricmap.h>
18 #include <mrpt/containers/yaml.h>
19 #include <mrpt/rtti/CObject.h>
20 #include <mrpt/system/COutputLogger.h>
21 
22 namespace mp2p_icp
23 {
29 {
30  MatchContext() = default;
31 
33  uint32_t icpIteration = 0;
34 };
35 
36 struct MatchState
37 {
38  MatchState(const metric_map_t& pcGlobal, const metric_map_t& pcLocal)
39  : pcGlobal_(pcGlobal), pcLocal_(pcLocal)
40  {
41  initialize();
42  }
43 
47 
50 
53  void initialize()
54  {
57  }
58 
59  private:
62 };
63 
72 class Matcher : public mrpt::system::COutputLogger,
73  public mrpt::rtti::CObject,
75 {
76  DEFINE_VIRTUAL_MRPT_OBJECT(Matcher)
77 
78  public:
80  virtual void initialize(const mrpt::containers::yaml& params);
81 
86  virtual bool match(
87  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
88  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
89  MatchState& ms, Pairings& out) const;
90 
91  uint32_t runFromIteration = 0;
92  uint32_t runUpToIteration = 0;
93  bool enabled = true;
94 
95  protected:
97  virtual bool impl_match(
98  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
99  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
100  MatchState& ms, Pairings& out) const = 0;
101 };
102 
103 using matcher_list_t = std::vector<mp2p_icp::Matcher::Ptr>;
104 
113  const matcher_list_t& matchers, const metric_map_t& pcGlobal,
114  const metric_map_t& pcLocal, const mrpt::poses::CPose3D& local_wrt_global,
115  const MatchContext& mc,
116  const mrpt::optional_ref<MatchState>& userProvidedMS = std::nullopt);
117 
118 } // namespace mp2p_icp
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::MatchState::MatchState
MatchState(const metric_map_t &pcGlobal, const metric_map_t &pcLocal)
Definition: Matcher.h:38
mp2p_icp::pointcloud_bitfield_t::initialize_from
void initialize_from(const metric_map_t &pc)
Definition: pointcloud_bitfield.h:87
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:27
mp2p_icp::Matcher::enabled
bool enabled
Definition: Matcher.h:93
mp2p_icp::MatchState::initialize
void initialize()
Definition: Matcher.h:53
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::Parameterizable
Definition: Parameterizable.h:85
mp2p_icp::MatchContext
Definition: Matcher.h:28
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::MatchState::pcLocal_
const metric_map_t & pcLocal_
Definition: Matcher.h:61
Parameterizable.h
mp2p_icp::MatchState::globalPairedBitField
pointcloud_bitfield_t globalPairedBitField
Like localPairedBitField for the global map.
Definition: Matcher.h:49
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
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:48
mp2p_icp::MatchState::pcGlobal_
const metric_map_t & pcGlobal_
Definition: Matcher.h:60
mp2p_icp::MatchState::localPairedBitField
pointcloud_bitfield_t localPairedBitField
Definition: Matcher.h:46
pointcloud_bitfield.h
A bit field with a bool for each metric_map_t entity.
mp2p_icp::pointcloud_bitfield_t
Definition: pointcloud_bitfield.h:34
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 Wed Jun 26 2024 02:47:09