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


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