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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/plane_patch.h>
15 #include <mp2p_icp/render_params.h>
16 #include <mrpt/containers/yaml.h>
17 #include <mrpt/math/TLine3D.h>
18 #include <mrpt/serialization/CSerializable.h>
19 #include <mrpt/tfest/TMatchingPair.h>
20 #include <mrpt/typemeta/TTypeName.h>
21 
22 namespace mp2p_icp
23 {
29 {
31 
32  matched_plane_t() = default;
33  matched_plane_t(const plane_patch_t& pl_this, const plane_patch_t& pl_other)
34  : p_global(pl_this), p_local(pl_other)
35  {
36  }
37 
38  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::matched_plane_t)
39 };
40 using MatchedPlaneList = std::vector<matched_plane_t>;
41 
44 {
45  mrpt::math::TLine3D ln_global, ln_local;
46 
47  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::matched_line_t)
48 };
49 using MatchedLineList = std::vector<matched_line_t>;
50 
53 {
55  mrpt::math::TPoint3Df pt_local;
56 
57  point_plane_pair_t() = default;
59  const plane_patch_t& p_global, const mrpt::math::TPoint3Df& p_local)
60  : pl_global(p_global), pt_local(p_local)
61  {
62  }
63 
64  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::point_plane_pair_t)
65 };
66 using MatchedPointPlaneList = std::vector<point_plane_pair_t>;
67 
70 {
71  mrpt::math::TLine3D ln_global;
72  mrpt::math::TPoint3D pt_local;
73 
74  point_line_pair_t() = default;
76  const mrpt::math::TLine3D& l_global,
77  const mrpt::math::TPoint3D& p_local)
78  : ln_global(l_global), pt_local(p_local)
79  {
80  }
81 
82  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::point_line_pair_t)
83 };
84 
85 using MatchedPointLineList = std::vector<point_line_pair_t>;
86 
94 struct Pairings
95 {
99  mrpt::tfest::TMatchingPairList paired_pt2pt;
106 
111  std::vector<std::pair<std::size_t, double>> point_weights;
112 
118  virtual bool empty() const
119  {
120  return paired_pt2pt.empty() && paired_pl2pl.empty() &&
121  paired_ln2ln.empty() && paired_pt2ln.empty() &&
122  paired_pt2pl.empty();
123  }
124 
126  virtual size_t size() const;
127 
129  virtual std::string contents_summary() const;
130 
132  virtual void push_back(const Pairings& o);
133 
135  virtual void push_back(Pairings&& o);
136 
137  virtual void serializeTo(mrpt::serialization::CArchive& out) const;
138  virtual void serializeFrom(mrpt::serialization::CArchive& in);
139 
149  virtual auto get_visualization(
150  const mrpt::poses::CPose3D& localWrtGlobal,
152  -> std::shared_ptr<mrpt::opengl::CSetOfObjects>;
153 
155  virtual void get_visualization_pt2pt(
156  mrpt::opengl::CSetOfObjects& o,
157  const mrpt::poses::CPose3D& localWrtGlobal,
158  const render_params_pairings_pt2pt_t& p) const;
159 
161  virtual void get_visualization_pt2pl(
162  mrpt::opengl::CSetOfObjects& o,
163  const mrpt::poses::CPose3D& localWrtGlobal,
164  const render_params_pairings_pt2pl_t& p) const;
165 
167  virtual void get_visualization_pt2ln(
168  mrpt::opengl::CSetOfObjects& o,
169  const mrpt::poses::CPose3D& localWrtGlobal,
170  const render_params_pairings_pt2ln_t& p) const;
171 
173  DECLARE_TTYPENAME_CLASSNAME(mp2p_icp::Pairings)
174 };
175 
176 mrpt::serialization::CArchive& operator<<(
177  mrpt::serialization::CArchive& out, const Pairings& obj);
178 
179 mrpt::serialization::CArchive& operator>>(
180  mrpt::serialization::CArchive& in, Pairings& obj);
181 
188 {
189  std::vector<std::size_t> point2point;
190  std::vector<std::size_t> line2line;
191  std::vector<std::size_t> plane2plane;
192 
193  inline bool empty() const
194  {
195  return point2point.empty() && line2line.empty() && plane2plane.empty();
196  }
197  inline std::size_t size() const
198  {
199  return point2point.size() + line2line.size() + plane2plane.size();
200  }
201 };
202 
206 std::tuple<mrpt::math::TPoint3D, mrpt::math::TPoint3D> eval_centroids_robust(
207  const Pairings& in, const OutlierIndices& outliers);
208 
211 } // namespace mp2p_icp
212 
213 namespace mrpt::serialization
214 {
215 CArchive& operator<<(CArchive& out, const mp2p_icp::point_line_pair_t& obj);
216 CArchive& operator>>(CArchive& in, mp2p_icp::point_line_pair_t& obj);
217 
218 CArchive& operator<<(CArchive& out, const mp2p_icp::point_plane_pair_t& obj);
219 CArchive& operator>>(CArchive& in, mp2p_icp::point_plane_pair_t& obj);
220 
221 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_line_t& obj);
222 CArchive& operator>>(CArchive& in, mp2p_icp::matched_line_t& obj);
223 
224 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_plane_t& obj);
225 CArchive& operator>>(CArchive& in, mp2p_icp::matched_plane_t& obj);
226 
227 } // namespace mrpt::serialization
mp2p_icp::Pairings::paired_ln2ln
MatchedLineList paired_ln2ln
Definition: Pairings.h:104
mp2p_icp::Pairings::contents_summary
virtual std::string contents_summary() const
Definition: Pairings.cpp:152
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:239
mp2p_icp
Definition: covariance.h:17
mp2p_icp::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, Pairings &obj)
Definition: Pairings.cpp:51
mp2p_icp::matched_plane_t::p_global
plane_patch_t p_global
Definition: Pairings.h:30
mp2p_icp::point_plane_pair_t
Definition: Pairings.h:52
mp2p_icp::point_plane_pair_t::pl_global
plane_patch_t pl_global
Definition: Pairings.h:54
mp2p_icp::MatchedPlaneList
std::vector< matched_plane_t > MatchedPlaneList
Definition: Pairings.h:40
mp2p_icp::MatchedLineList
std::vector< matched_line_t > MatchedLineList
Definition: Pairings.h:49
mp2p_icp::Pairings
Definition: Pairings.h:94
render_params.h
Render parameters for the different geometric entities.
mp2p_icp::Pairings::empty
virtual bool empty() const
Definition: Pairings.h:118
mp2p_icp::matched_plane_t::p_local
plane_patch_t p_local
Definition: Pairings.h:30
mp2p_icp::Pairings::serializeFrom
virtual void serializeFrom(mrpt::serialization::CArchive &in)
Definition: Pairings.cpp:34
mp2p_icp::point_line_pair_t::ln_global
mrpt::math::TLine3D ln_global
Definition: Pairings.h:71
mp2p_icp::MatchedPointPlaneList
std::vector< point_plane_pair_t > MatchedPointPlaneList
Definition: Pairings.h:66
mp2p_icp::render_params_pairings_pt2pl_t
Definition: render_params.h:133
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:184
mrpt
Definition: LogRecord.h:99
plane_patch.h
Defines plane_patch_t.
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::OutlierIndices::empty
bool empty() const
Definition: Pairings.h:193
mp2p_icp::OutlierIndices::point2point
std::vector< std::size_t > point2point
Definition: Pairings.h:189
mp2p_icp::OutlierIndices::line2line
std::vector< std::size_t > line2line
Definition: Pairings.h:190
mp2p_icp::Pairings::point_weights
std::vector< std::pair< std::size_t, double > > point_weights
Definition: Pairings.h:111
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:45
mp2p_icp::matched_line_t
Definition: Pairings.h:43
mp2p_icp::OutlierIndices::size
std::size_t size() const
Definition: Pairings.h:197
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:75
mp2p_icp::Pairings::serializeTo
virtual void serializeTo(mrpt::serialization::CArchive &out) const
Definition: Pairings.cpp:26
mp2p_icp::point_plane_pair_t::point_plane_pair_t
point_plane_pair_t(const plane_patch_t &p_global, const mrpt::math::TPoint3Df &p_local)
Definition: Pairings.h:58
mrpt::serialization
Definition: LogRecord.h:99
mp2p_icp::Pairings::push_back
virtual void push_back(const Pairings &o)
Definition: Pairings.cpp:117
mp2p_icp::point_line_pair_t
Definition: Pairings.h:69
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:59
mp2p_icp::point_plane_pair_t::point_plane_pair_t
point_plane_pair_t()=default
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:105
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:124
mp2p_icp::point_line_pair_t::point_line_pair_t
point_line_pair_t()=default
mp2p_icp::plane_patch_t
Definition: plane_patch.h:22
std
mp2p_icp::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const Pairings &obj)
Definition: Pairings.cpp:44
mp2p_icp::point_line_pair_t::pt_local
mrpt::math::TPoint3D pt_local
Definition: Pairings.h:72
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:203
mp2p_icp::Pairings::paired_pt2ln
MatchedPointLineList paired_pt2ln
Definition: Pairings.h:102
mp2p_icp::MatchedPointLineList
std::vector< point_line_pair_t > MatchedPointLineList
Definition: Pairings.h:85
mp2p_icp::point_plane_pair_t::pt_local
mrpt::math::TPoint3Df pt_local
Definition: Pairings.h:55
mp2p_icp::matched_plane_t::matched_plane_t
matched_plane_t()=default
mp2p_icp::matched_plane_t
Definition: Pairings.h:28
mp2p_icp::matched_line_t::ln_local
mrpt::math::TLine3D ln_local
Definition: Pairings.h:45
mp2p_icp::render_params_pairings_pt2ln_t
Definition: render_params.h:144
mp2p_icp::OutlierIndices
Definition: Pairings.h:187
mp2p_icp::pairings_render_params_t
Definition: render_params.h:156
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:101
mp2p_icp::OutlierIndices::plane2plane
std::vector< std::size_t > plane2plane
Definition: Pairings.h:191
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:103
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:33


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