Pairings.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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
13 #include <mp2p_icp/Pairings.h>
14 #include <mrpt/opengl/CSetOfLines.h>
15 #include <mrpt/opengl/CSetOfObjects.h>
16 #include <mrpt/opengl/CTexturedPlane.h>
17 #include <mrpt/serialization/CArchive.h>
18 #include <mrpt/serialization/stl_serialization.h>
19 
20 #include <iterator> // std::make_move_iterator
21 
22 using namespace mp2p_icp;
23 
24 static const uint8_t SERIALIZATION_VERSION = 1;
25 
26 Pairings::~Pairings() = default;
27 
28 void Pairings::serializeTo(mrpt::serialization::CArchive& out) const
29 {
30  out.WriteAs<uint8_t>(SERIALIZATION_VERSION);
31  out << paired_pt2pt;
33  out << potential_pairings; // v1
34 }
35 
36 void Pairings::serializeFrom(mrpt::serialization::CArchive& in)
37 {
38  const auto readVersion = in.ReadAs<uint8_t>();
39 
40  ASSERT_LE_(readVersion, SERIALIZATION_VERSION);
41  in >> paired_pt2pt;
43  if (readVersion >= 1) in >> potential_pairings;
44 }
45 
46 mrpt::serialization::CArchive& mp2p_icp::operator<<(
47  mrpt::serialization::CArchive& out, const Pairings& obj)
48 {
49  obj.serializeTo(out);
50  return out;
51 }
52 
53 mrpt::serialization::CArchive& mp2p_icp::operator>>(
54  mrpt::serialization::CArchive& in, Pairings& obj)
55 {
56  obj.serializeFrom(in);
57  return in;
58 }
59 
60 std::tuple<mrpt::math::TPoint3D, mrpt::math::TPoint3D> mp2p_icp::eval_centroids_robust(
61  const Pairings& in, const OutlierIndices& outliers)
62 {
63  using mrpt::math::TPoint3D;
64 
65  const auto nPt2Pt = in.paired_pt2pt.size();
66 
67  // We need more points than outliers (!)
68  ASSERT_GT_(nPt2Pt, outliers.point2point.size());
69 
70  // Normalized weights for centroids.
71  // Discount outliers.
72  const double wcPoints = 1.0 / (nPt2Pt - outliers.point2point.size());
73 
74  // Add global coordinate of points for now, we'll convert them later to
75  // unit vectors relative to the centroids:
76  TPoint3D ct_local(0, 0, 0), ct_global(0, 0, 0);
77  {
78  std::size_t cnt = 0;
79  auto it_next_outlier = outliers.point2point.begin();
80  for (std::size_t i = 0; i < in.paired_pt2pt.size(); i++)
81  {
82  // Skip outlier?
83  if (it_next_outlier != outliers.point2point.end() && i == *it_next_outlier)
84  {
85  ++it_next_outlier;
86  continue;
87  }
88  const auto& pair = in.paired_pt2pt[i];
89 
90  ct_global += pair.global;
91  ct_local += pair.local;
92  cnt++;
93  }
94  // Sanity check:
95  ASSERT_EQUAL_(cnt, nPt2Pt - outliers.point2point.size());
96 
97  ct_local *= wcPoints;
98  ct_global *= wcPoints;
99  }
100 
101  return {ct_local, ct_global};
102 }
103 
104 template <typename T>
105 static void push_back_copy(const T& o, T& me)
106 {
107  me.insert(me.end(), o.begin(), o.end());
108 }
109 template <typename T>
110 static void push_back_move(T&& o, T& me)
111 {
112  me.insert(me.end(), std::make_move_iterator(o.begin()), std::make_move_iterator(o.end()));
113 }
114 
116 {
123 }
124 
126 {
127  push_back_move(std::move(o.paired_pt2pt), paired_pt2pt);
128  push_back_move(std::move(o.paired_pt2ln), paired_pt2ln);
129  push_back_move(std::move(o.paired_pt2pl), paired_pt2pl);
130  push_back_move(std::move(o.paired_ln2ln), paired_ln2ln);
131  push_back_move(std::move(o.paired_pl2pl), paired_pl2pl);
132  potential_pairings = o.potential_pairings;
133 }
134 
135 size_t Pairings::size() const
136 {
137  return paired_pt2pt.size() + paired_pt2ln.size() + paired_pt2pl.size() + paired_ln2ln.size() +
138  paired_pl2pl.size();
139 }
140 
141 template <typename CONTAINER>
142 void append_container_size(const CONTAINER& c, const std::string& name, std::string& ret)
143 {
144  using namespace std::string_literals;
145 
146  if (c.empty()) return;
147  if (!ret.empty()) ret += ", "s;
148  ret += std::to_string(c.size()) + " "s + name;
149 }
150 
152 {
153  using namespace std::string_literals;
154 
155  if (empty()) return {"none"s};
156 
157  std::string ret;
158  append_container_size(paired_pt2pt, "point-point", ret);
159  append_container_size(paired_pt2ln, "point-line", ret);
160  append_container_size(paired_pt2pl, "point-plane", ret);
161  append_container_size(paired_ln2ln, "line-line", ret);
162  append_container_size(paired_pl2pl, "plane-plane", ret);
163  ret += " out of "s + std::to_string(potential_pairings);
164 
165  return ret;
166 }
167 
169  const mrpt::poses::CPose3D& localWrtGlobal, const pairings_render_params_t& p) const
170  -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
171 {
172  MRPT_START
173  auto o = mrpt::opengl::CSetOfObjects::Create();
174 
175  get_visualization_pt2pt(*o, localWrtGlobal, p.pt2pt);
176  get_visualization_pt2pl(*o, localWrtGlobal, p.pt2pl);
177  get_visualization_pt2ln(*o, localWrtGlobal, p.pt2ln);
178 
179  return o;
180  MRPT_END
181 }
182 
184  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
185  const render_params_pairings_pt2pt_t& p) const
186 {
187  if (!p.visible) return;
188 
189  auto lns = mrpt::opengl::CSetOfLines::Create();
190  lns->setColor_u8(p.color);
191 
192  // this: global, other: local
193  for (const auto& pair : paired_pt2pt)
194  {
195  const auto ptLocalTf = localWrtGlobal.composePoint(pair.local);
196  lns->appendLine(ptLocalTf, pair.global);
197  }
198 
199  o.insert(lns);
200 }
201 
203  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
204  const render_params_pairings_pt2pl_t& p) const
205 {
206  if (!p.visible) return;
207 
208  auto lns = mrpt::opengl::CSetOfLines::Create();
209  lns->setColor_u8(p.segmentColor);
210 
211  const double L = 0.5 * p.planePatchSize;
212 
213  for (const auto& pair : paired_pt2pl)
214  {
215  const auto globalPlanePose = mrpt::poses::CPose3D(
216  pair.pl_global.plane.getAsPose3DForcingOrigin(pair.pl_global.centroid));
217 
218  const auto ptLocal = pair.pt_local;
219  const auto ptLocalTf = localWrtGlobal.composePoint(ptLocal);
220 
221  // line segment:
222  lns->appendLine(ptLocalTf, globalPlanePose.translation());
223 
224  // plane patch:
225  auto glPlane = mrpt::opengl::CTexturedPlane::Create();
226  glPlane->setPlaneCorners(-L, L, -L, L);
227  glPlane->setColor_u8(p.planePatchColor);
228 
229  glPlane->setPose(globalPlanePose);
230 
231  o.insert(glPlane);
232  }
233 
234  o.insert(lns);
235 }
236 
238  mrpt::opengl::CSetOfObjects& o, const mrpt::poses::CPose3D& localWrtGlobal,
239  const render_params_pairings_pt2ln_t& p) const
240 {
241  if (!p.visible) return;
242 
243  auto pairingLines = mrpt::opengl::CSetOfLines::Create();
244  pairingLines->setColor_u8(p.segmentColor);
245 
246  auto globalLines = mrpt::opengl::CSetOfLines::Create();
247  globalLines->setColor_u8(p.lineColor);
248 
249  const double L = 0.5 * p.lineLength;
250 
251  for (const auto& pair : paired_pt2ln)
252  {
253  const auto& globalLine = pair.ln_global;
254 
255  const auto ptLocal = pair.pt_local;
256  const auto ptLocalTf = localWrtGlobal.composePoint(ptLocal);
257 
258  // line segment:
259  pairingLines->appendLine(ptLocalTf, globalLine.pBase);
260 
261  // line segment:
262  globalLines->appendLine(
263  globalLine.pBase - globalLine.director * L, globalLine.pBase + globalLine.director * L);
264  }
265 
266  o.insert(pairingLines);
267  o.insert(globalLines);
268 }
269 
270 namespace mrpt::serialization
271 {
272 CArchive& operator<<(CArchive& out, const mp2p_icp::point_line_pair_t& obj)
273 {
274  out.WriteAs<uint8_t>(0);
275 
276  out << obj.ln_global << obj.pt_local;
277  return out;
278 }
279 
280 CArchive& operator>>(CArchive& in, mp2p_icp::point_line_pair_t& obj)
281 {
282  // const auto ver =
283  in.ReadAs<uint8_t>();
284 
285  in >> obj.ln_global >> obj.pt_local;
286  return in;
287 }
288 
289 CArchive& operator<<(CArchive& out, const mp2p_icp::point_plane_pair_t& obj)
290 {
291  out.WriteAs<uint8_t>(0);
292  out << obj.pl_global.centroid << obj.pl_global.plane << obj.pt_local;
293  return out;
294 }
295 
296 CArchive& operator>>(CArchive& in, mp2p_icp::point_plane_pair_t& obj)
297 {
298  in.ReadAs<uint8_t>();
299 
300  in >> obj.pl_global.centroid >> obj.pl_global.plane >> obj.pt_local;
301  return in;
302 }
303 
304 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_line_t& obj)
305 {
306  out.WriteAs<uint8_t>(0);
307  out << obj.ln_local << obj.ln_global;
308  return out;
309 }
310 
311 CArchive& operator>>(CArchive& in, mp2p_icp::matched_line_t& obj)
312 {
313  in.ReadAs<uint8_t>();
314 
315  in >> obj.ln_local >> obj.ln_global;
316  return in;
317 }
318 
319 CArchive& operator<<(CArchive& out, const mp2p_icp::matched_plane_t& obj)
320 {
321  out.WriteAs<uint8_t>(0);
322  out << obj.p_local.centroid << obj.p_local.plane;
323  out << obj.p_global.centroid << obj.p_global.plane;
324  return out;
325 }
326 CArchive& operator>>(CArchive& in, mp2p_icp::matched_plane_t& obj)
327 {
328  in.ReadAs<uint8_t>();
329 
330  in >> obj.p_local.centroid >> obj.p_local.plane;
331  in >> obj.p_global.centroid >> obj.p_global.plane;
332  return in;
333 }
334 
335 } // 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
SERIALIZATION_VERSION
static const uint8_t SERIALIZATION_VERSION
Definition: Pairings.cpp:24
mp2p_icp::render_params_pairings_pt2pl_t::planePatchColor
mrpt::img::TColor planePatchColor
Definition: render_params.h:198
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::render_params_pairings_pt2pt_t::color
mrpt::img::TColor color
Definition: render_params.h:188
mp2p_icp::plane_patch_t::centroid
mrpt::math::TPoint3D centroid
Definition: plane_patch.h:25
mp2p_icp::matched_plane_t::p_global
plane_patch_t p_global
Definition: Pairings.h:31
s
XmlRpcServer s
mp2p_icp::render_params_pairings_pt2pl_t::visible
bool visible
Definition: render_params.h:195
mp2p_icp::point_plane_pair_t
Definition: point_plane_pair_t.h:26
mp2p_icp::point_plane_pair_t::pl_global
plane_patch_t pl_global
Definition: point_plane_pair_t.h:28
mp2p_icp::render_params_pairings_pt2ln_t::segmentColor
mrpt::img::TColor segmentColor
Definition: render_params.h:208
mp2p_icp::Pairings
Definition: Pairings.h:76
mp2p_icp::render_params_pairings_pt2pl_t::segmentColor
mrpt::img::TColor segmentColor
Definition: render_params.h:197
mp2p_icp::render_params_pairings_pt2pt_t::visible
bool visible
Definition: render_params.h:186
mp2p_icp::Pairings::empty
virtual bool empty() const
Definition: Pairings.h:109
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
mp2p_icp::render_params_pairings_pt2pl_t::planePatchSize
double planePatchSize
Definition: render_params.h:199
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::point2point
std::vector< std::size_t > point2point
Definition: Pairings.h:174
mp2p_icp::render_params_pairings_pt2ln_t::visible
bool visible
Definition: render_params.h:206
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
append_container_size
void append_container_size(const CONTAINER &c, const std::string &name, std::string &ret)
Definition: Pairings.cpp:142
mp2p_icp::Pairings::size
virtual size_t size() const
Definition: Pairings.cpp:135
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::Pairings::serializeTo
virtual void serializeTo(mrpt::serialization::CArchive &out) const
Definition: Pairings.cpp:28
mp2p_icp::render_params_pairings_pt2ln_t::lineColor
mrpt::img::TColor lineColor
Definition: render_params.h:209
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::render_params_pairings_pt2ln_t::lineLength
double lineLength
Definition: render_params.h:210
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::Pairings::~Pairings
virtual ~Pairings()
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::point_plane_pair_t::pt_local
mrpt::math::TPoint3Df pt_local
Definition: point_plane_pair_t.h:29
push_back_copy
static void push_back_copy(const T &o, T &me)
Definition: Pairings.cpp:105
push_back_move
static void push_back_move(T &&o, T &me)
Definition: Pairings.cpp:110
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::plane_patch_t::plane
mrpt::math::TPlane plane
Definition: plane_patch.h:24
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:86
mp2p_icp::Pairings::paired_pt2pl
MatchedPointPlaneList paired_pt2pl
Definition: Pairings.h:88


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