Pairings.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/plane_patch.h>
16 #include <mp2p_icp/render_params.h>
17 #include <mrpt/containers/yaml.h>
18 #include <mrpt/math/TLine3D.h>
19 #include <mrpt/serialization/CSerializable.h>
20 #include <mrpt/tfest/TMatchingPair.h>
21 #include <mrpt/typemeta/TTypeName.h>
22 
23 namespace mp2p_icp
24 {
30 {
32 
33  matched_plane_t() = default;
34  matched_plane_t(const plane_patch_t& pl_this, const plane_patch_t& pl_other)
35  : p_global(pl_this), p_local(pl_other)
36  {
37  }
38 
39  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::matched_plane_t)
40 };
41 using MatchedPlaneList = std::vector<matched_plane_t>;
42 
45 {
46  mrpt::math::TLine3D ln_global, ln_local;
47 
48  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::matched_line_t)
49 };
50 using MatchedLineList = std::vector<matched_line_t>;
51 
54 {
55  mrpt::math::TLine3D ln_global;
56  mrpt::math::TPoint3D pt_local;
57 
58  point_line_pair_t() = default;
59  point_line_pair_t(const mrpt::math::TLine3D& l_global, const mrpt::math::TPoint3D& p_local)
60  : ln_global(l_global), pt_local(p_local)
61  {
62  }
63 
64  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::point_line_pair_t)
65 };
66 
67 using MatchedPointLineList = std::vector<point_line_pair_t>;
68 
76 struct Pairings
77 {
78  Pairings() = default;
79  virtual ~Pairings();
80 
84  mrpt::tfest::TMatchingPairList paired_pt2pt;
91 
96  uint64_t potential_pairings = 0;
97 
102  std::vector<std::pair<std::size_t, double>> point_weights;
103 
109  virtual bool empty() const
110  {
111  return paired_pt2pt.empty() && paired_pl2pl.empty() && paired_ln2ln.empty() &&
112  paired_pt2ln.empty() && paired_pt2pl.empty();
113  }
114 
116  virtual size_t size() const;
117 
119  virtual std::string contents_summary() const;
120 
122  virtual void push_back(const Pairings& o);
123 
125  virtual void push_back(Pairings&& o);
126 
127  virtual void serializeTo(mrpt::serialization::CArchive& out) const;
128  virtual void serializeFrom(mrpt::serialization::CArchive& in);
129 
139  virtual auto get_visualization(
140  const mrpt::poses::CPose3D& localWrtGlobal,
142  -> std::shared_ptr<mrpt::opengl::CSetOfObjects>;
143 
145  virtual void get_visualization_pt2pt(
146  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
147  const render_params_pairings_pt2pt_t& p) const;
148 
150  virtual void get_visualization_pt2pl(
151  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
152  const render_params_pairings_pt2pl_t& p) const;
153 
155  virtual void get_visualization_pt2ln(
156  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
157  const render_params_pairings_pt2ln_t& p) const;
158 
160  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::Pairings)
161 };
162 
163 mrpt::serialization::CArchive& operator<<(mrpt::serialization::CArchive& out, const Pairings& obj);
164 
165 mrpt::serialization::CArchive& operator>>(mrpt::serialization::CArchive& in, Pairings& obj);
166 
173 {
174  std::vector<std::size_t> point2point;
175  std::vector<std::size_t> line2line;
176  std::vector<std::size_t> plane2plane;
177 
178  inline bool empty() const
179  {
180  return point2point.empty() && line2line.empty() && plane2plane.empty();
181  }
182  inline std::size_t size() const
183  {
184  return point2point.size() + line2line.size() + plane2plane.size();
185  }
186 };
187 
191 std::tuple<mrpt::math::TPoint3D, mrpt::math::TPoint3D> eval_centroids_robust(
192  const Pairings& in, const OutlierIndices& outliers);
193 
196 } // namespace mp2p_icp
197 
198 namespace mrpt::serialization
199 {
200 CArchive& operator<<(CArchive& out, const mp2p_icp::point_line_pair_t& obj);
201 CArchive& operator>>(CArchive& in, mp2p_icp::point_line_pair_t& obj);
202 
203 CArchive& operator<<(CArchive& out, const mp2p_icp::point_plane_pair_t& obj);
204 CArchive& operator>>(CArchive& in, mp2p_icp::point_plane_pair_t& obj);
205 
206 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_line_t& obj);
207 CArchive& operator>>(CArchive& in, mp2p_icp::matched_line_t& obj);
208 
209 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_plane_t& obj);
210 CArchive& operator>>(CArchive& in, mp2p_icp::matched_plane_t& obj);
211 
212 } // namespace mrpt::serialization
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:89
mp2p_icp::Pairings::contents_summary
virtual std::string contents_summary() const
Definition: Pairings.cpp:151
mp2p_icp::Pairings::get_visualization_pt2ln
virtual void get_visualization_pt2ln(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2ln_t &p) const
Definition: Pairings.cpp:237
mp2p_icp
Definition: covariance.h:17
mp2p_icp::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, Pairings &obj)
Definition: Pairings.cpp:53
mp2p_icp::matched_plane_t::p_global
plane_patch_t p_global
Definition: Pairings.h:31
mp2p_icp::point_plane_pair_t
Definition: point_plane_pair_t.h:26
mp2p_icp::MatchedPlaneList
std::vector< matched_plane_t > MatchedPlaneList
Definition: Pairings.h:41
point_plane_pair_t.h
Defines point_plane_pair_t.
mp2p_icp::MatchedLineList
std::vector< matched_line_t > MatchedLineList
Definition: Pairings.h:50
mp2p_icp::Pairings
Definition: Pairings.h:76
render_params.h
Render parameters for the different geometric entities.
mp2p_icp::Pairings::empty
virtual bool empty() const
Definition: Pairings.h:109
mp2p_icp::MatchedPointPlaneList
std::vector< point_plane_pair_t > MatchedPointPlaneList
Definition: point_plane_pair_t.h:39
mp2p_icp::matched_plane_t::p_local
plane_patch_t p_local
Definition: Pairings.h:31
mp2p_icp::Pairings::serializeFrom
virtual void serializeFrom(mrpt::serialization::CArchive &in)
Definition: Pairings.cpp:36
mp2p_icp::point_line_pair_t::ln_global
mrpt::math::TLine3D ln_global
Definition: Pairings.h:55
mp2p_icp::render_params_pairings_pt2pl_t
Definition: render_params.h:191
mp2p_icp::Pairings::get_visualization_pt2pt
virtual void get_visualization_pt2pt(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pt_t &p) const
Definition: Pairings.cpp:183
mrpt
Definition: LogRecord.h:100
plane_patch.h
Defines plane_patch_t.
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::Pairings::potential_pairings
uint64_t potential_pairings
Definition: Pairings.h:96
mp2p_icp::OutlierIndices::empty
bool empty() const
Definition: Pairings.h:178
mp2p_icp::OutlierIndices::point2point
std::vector< std::size_t > point2point
Definition: Pairings.h:174
mp2p_icp::OutlierIndices::line2line
std::vector< std::size_t > line2line
Definition: Pairings.h:175
mp2p_icp::Pairings::point_weights
std::vector< std::pair< std::size_t, double > > point_weights
Definition: Pairings.h:102
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::matched_line_t::ln_global
mrpt::math::TLine3D ln_global
Definition: Pairings.h:46
mp2p_icp::matched_line_t
Definition: Pairings.h:44
mp2p_icp::OutlierIndices::size
std::size_t size() const
Definition: Pairings.h:182
mp2p_icp::Pairings::size
virtual size_t size() const
Definition: Pairings.cpp:135
mp2p_icp::point_line_pair_t::point_line_pair_t
point_line_pair_t(const mrpt::math::TLine3D &l_global, const mrpt::math::TPoint3D &p_local)
Definition: Pairings.h:59
mp2p_icp::Pairings::serializeTo
virtual void serializeTo(mrpt::serialization::CArchive &out) const
Definition: Pairings.cpp:28
mrpt::serialization
Definition: LogRecord.h:100
mp2p_icp::Pairings::push_back
virtual void push_back(const Pairings &o)
Definition: Pairings.cpp:115
mp2p_icp::point_line_pair_t
Definition: Pairings.h:53
mp2p_icp::eval_centroids_robust
std::tuple< mrpt::math::TPoint3D, mrpt::math::TPoint3D > eval_centroids_robust(const Pairings &in, const OutlierIndices &outliers)
Definition: Pairings.cpp:60
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:90
mp2p_icp::Pairings::get_visualization
virtual auto get_visualization(const mrpt::poses::CPose3D &localWrtGlobal, const pairings_render_params_t &p=pairings_render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
Definition: Pairings.cpp:168
mp2p_icp::render_params_pairings_pt2pt_t
Definition: render_params.h:182
mp2p_icp::point_line_pair_t::point_line_pair_t
point_line_pair_t()=default
mp2p_icp::Pairings::~Pairings
virtual ~Pairings()
mp2p_icp::plane_patch_t
Definition: plane_patch.h:22
std
mp2p_icp::Pairings::Pairings
Pairings()=default
mp2p_icp::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const Pairings &obj)
Definition: Pairings.cpp:46
mp2p_icp::point_line_pair_t::pt_local
mrpt::math::TPoint3D pt_local
Definition: Pairings.h:56
mp2p_icp::Pairings::get_visualization_pt2pl
virtual void get_visualization_pt2pl(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pl_t &p) const
Definition: Pairings.cpp:202
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:87
mp2p_icp::MatchedPointLineList
std::vector< point_line_pair_t > MatchedPointLineList
Definition: Pairings.h:67
mp2p_icp::matched_plane_t::matched_plane_t
matched_plane_t()=default
mp2p_icp::matched_plane_t
Definition: Pairings.h:29
mp2p_icp::matched_line_t::ln_local
mrpt::math::TLine3D ln_local
Definition: Pairings.h:46
mp2p_icp::render_params_pairings_pt2ln_t
Definition: render_params.h:202
mp2p_icp::OutlierIndices
Definition: Pairings.h:172
mp2p_icp::pairings_render_params_t
Definition: render_params.h:214
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:86
mp2p_icp::OutlierIndices::plane2plane
std::vector< std::size_t > plane2plane
Definition: Pairings.h:176
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:88
mp2p_icp::matched_plane_t::matched_plane_t
matched_plane_t(const plane_patch_t &pl_this, const plane_patch_t &pl_other)
Definition: Pairings.h:34


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:50