metricmap.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/metricmap.h>
14 #include <mrpt/io/CFileGZInputStream.h>
15 #include <mrpt/io/CFileGZOutputStream.h>
16 #include <mrpt/opengl/CGridPlaneXY.h>
17 #include <mrpt/opengl/CPointCloud.h>
18 #include <mrpt/opengl/CPointCloudColoured.h>
19 #include <mrpt/opengl/CSetOfLines.h>
20 #include <mrpt/opengl/CSetOfObjects.h>
21 #include <mrpt/serialization/CArchive.h>
22 #include <mrpt/serialization/optional_serialization.h>
23 #include <mrpt/serialization/stl_serialization.h>
24 
25 #include <algorithm>
26 #include <iterator>
27 
29  metric_map_t, mrpt::serialization::CSerializable, mp2p_icp)
30 
31 using namespace mp2p_icp;
32 
33 // Implementation of the CSerializable virtual interface:
34 uint8_t metric_map_t::serializeGetVersion() const { return 1; }
35 void metric_map_t::serializeTo(mrpt::serialization::CArchive& out) const
36 {
37  out << lines;
38 
39  out.WriteAs<uint32_t>(planes.size());
40  for (const auto& p : planes) out << p.plane << p.centroid;
41 
42  out.WriteAs<uint32_t>(lines.size());
43  for (const auto& l : lines) out << l;
44 
45  out.WriteAs<uint32_t>(layers.size());
46  for (const auto& l : layers) out << l.first << *l.second.get();
47 
48  out << id << label; // new in v1
49 
50  // Optional user data:
52 }
53 void metric_map_t::serializeFrom(
54  mrpt::serialization::CArchive& in, uint8_t version)
55 {
56  switch (version)
57  {
58  case 0:
59  case 1:
60  {
61  in >> lines;
62  const auto nPls = in.ReadAs<uint32_t>();
63  planes.resize(nPls);
64  for (auto& pl : planes) in >> pl.plane >> pl.centroid;
65 
66  const auto nLins = in.ReadAs<uint32_t>();
67  lines.resize(nLins);
68  for (auto& l : lines) in >> l;
69 
70  const auto nPts = in.ReadAs<uint32_t>();
71  layers.clear();
72  for (std::size_t i = 0; i < nPts; i++)
73  {
74  std::string name;
75  in >> name;
76  layers[name] = mrpt::ptr_cast<mrpt::maps::CMetricMap>::from(
77  in.ReadObject());
78  }
79 
80  if (version >= 1) { in >> id >> label; }
81  else
82  {
83  id.reset();
84  label.reset();
85  }
86 
87  // Optional user data:
89  }
90  break;
91  default:
92  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
93  };
94 }
95 
97  -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
98 {
99  MRPT_START
100  auto o = mrpt::opengl::CSetOfObjects::Create();
101 
102  get_visualization_planes(*o, p.planes);
103  get_visualization_lines(*o, p.lines);
104  get_visualization_points(*o, p.points);
105 
106  return o;
107  MRPT_END
108 }
109 
111  mrpt::opengl::CSetOfObjects& o, const render_params_planes_t& p) const
112 {
113  MRPT_START
114  if (!p.visible) return;
115 
116  const float pw = p.halfWidth, pf = p.gridSpacing;
117 
118  for (const auto& plane : planes)
119  {
120  auto gl_pl =
121  mrpt::opengl::CGridPlaneXY::Create(-pw, pw, -pw, pw, .0, pf);
122  gl_pl->setColor_u8(p.color);
123  mrpt::math::TPose3D planePose;
124  plane.plane.getAsPose3DForcingOrigin(plane.centroid, planePose);
125  gl_pl->setPose(planePose);
126  o.insert(gl_pl);
127  }
128 
129  MRPT_END
130 }
131 
133  mrpt::opengl::CSetOfObjects& o, const render_params_lines_t& p) const
134 {
135  MRPT_START
136 
137  auto glLin = mrpt::opengl::CSetOfLines::Create();
138  glLin->setColor_u8(p.color);
139 
140  for (size_t idxLine = 0; idxLine < lines.size(); idxLine++)
141  {
142  const auto& line = lines[idxLine];
143  double linLen = p.length;
144  const auto halfSeg = line.director * (0.5 * linLen);
145  glLin->appendLine(line.pBase - halfSeg, line.pBase + halfSeg);
146  }
147  o.insert(glLin);
148 
149  MRPT_END
150 }
151 
153  mrpt::opengl::CSetOfObjects& o, const render_params_points_t& p) const
154 {
155  MRPT_START
156  // Planes:
157  if (!p.visible) return;
158 
159  if (!p.perLayer.empty())
160  {
161  // render only these layers:
162  for (const auto& kv : p.perLayer)
163  {
164  const auto itPts = layers.find(kv.first);
165  if (itPts == layers.end())
166  THROW_EXCEPTION_FMT(
167  "Rendering parameters given for layer '%s' which does not "
168  "exist in this metric_map_t object",
169  kv.first.c_str());
170 
172  o, kv.second,
173  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
174  itPts->second));
175  }
176  }
177  else
178  {
179  // render all layers with the same params:
180  for (const auto& kv : layers)
181  {
182  auto pts =
183  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(kv.second);
184  if (!pts) continue; // not a point cloud.
185 
187  }
188  }
189 
190  MRPT_END
191 }
192 
194  mrpt::opengl::CSetOfObjects& o, const render_params_point_layer_t& p,
195  const mrpt::maps::CPointsMap::Ptr& pts)
196 {
197  ASSERT_(pts);
198  if (pts->empty()) return;
199 
200  if (p.colorMode.has_value())
201  {
202  // color point cloud:
203  auto glPts = mrpt::opengl::CPointCloudColoured::Create();
204  glPts->loadFromPointsMap(pts.get());
205 
206  glPts->setPointSize(p.pointSize);
207 
208  mrpt::math::TBoundingBoxf bb;
209 
210  if (!p.colorMode->colorMapMinCoord.has_value() ||
211  !p.colorMode->colorMapMaxCoord.has_value())
212  bb = pts->boundingBox();
213 
214  ASSERT_(p.colorMode->recolorizeByCoordinate.has_value());
215 
216  const unsigned int coordIdx = static_cast<unsigned int>(
217  p.colorMode->recolorizeByCoordinate.value());
218 
219  const float coordMin = p.colorMode->colorMapMinCoord.has_value()
220  ? *p.colorMode->colorMapMinCoord
221  : bb.min[coordIdx];
222 
223  const float coordMax = p.colorMode->colorMapMaxCoord.has_value()
224  ? *p.colorMode->colorMapMaxCoord
225  : bb.max[coordIdx];
226 
227  glPts->recolorizeByCoordinate(
228  coordMin, coordMax, coordIdx, p.colorMode->colorMap);
229 
230  o.insert(glPts);
231  }
232  else
233  {
234  // uniform color point cloud:
235  auto glPts = mrpt::opengl::CPointCloud::Create();
236  glPts->loadFromPointsMap(pts.get());
237 
238  glPts->setPointSize(p.pointSize);
239  glPts->setColor_u8(p.color);
240 
241  o.insert(glPts);
242  }
243 }
244 
246 {
247  return layers.empty() && lines.empty() && planes.empty();
248 }
249 void metric_map_t::clear() { *this = metric_map_t(); }
250 
251 MRPT_TODO("Write unit test for mergeWith()")
252 void metric_map_t::merge_with(
253  const metric_map_t& otherPc,
254  const std::optional<mrpt::math::TPose3D>& otherRelativePose)
255 {
256  mrpt::poses::CPose3D pose;
257  if (otherRelativePose.has_value())
258  pose = mrpt::poses::CPose3D(otherRelativePose.value());
259 
260  // Lines:
261  if (otherRelativePose.has_value())
262  {
263  std::transform(
264  otherPc.lines.begin(), otherPc.lines.end(),
265  std::back_inserter(lines), [&](const mrpt::math::TLine3D& l) {
266  return mrpt::math::TLine3D::FromPointAndDirector(
267  pose.composePoint(l.pBase),
268  pose.rotateVector(l.getDirectorVector()));
269  });
270  }
271  else
272  {
273  std::copy(
274  otherPc.lines.begin(), otherPc.lines.end(),
275  std::back_inserter(lines));
276  }
277 
278  // Planes:
279  if (otherRelativePose.has_value())
280  {
281  std::transform(
282  otherPc.planes.begin(), otherPc.planes.end(),
283  std::back_inserter(planes), [&](const plane_patch_t& l) {
284  plane_patch_t g;
285  g.centroid = pose.composePoint(l.centroid);
286  MRPT_TODO("Finish rotating planes");
287  // ...
288  THROW_EXCEPTION("To-do");
289  return g;
290  });
291  }
292  else
293  {
294  std::copy(
295  otherPc.planes.begin(), otherPc.planes.end(),
296  std::back_inserter(planes));
297  }
298 
299  // Points:
300  for (const auto& layer : otherPc.layers)
301  {
302  const auto& name = layer.first;
303  const auto& otherMap = layer.second;
304 
305  // New layer?
306  if (layers.count(name) == 0)
307  {
308  // Make a copy and transform (if applicable):
309  layers[name] = std::dynamic_pointer_cast<mrpt::maps::CMetricMap>(
310  otherMap->duplicateGetSmartPtr());
311 
312  if (otherRelativePose.has_value())
313  {
314  if (auto pts =
315  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
316  layers[name]);
317  pts)
318  {
319  // Transform:
320  pts->changeCoordinatesReference(pose);
321  }
322  else
323  {
324  THROW_EXCEPTION(
325  "Merging with SE(3) transform only available for "
326  "metric maps of point cloud types.");
327  }
328  }
329  }
330  else
331  {
332  // merge with existing layer:
333  if (auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
334  layers[name]);
335  pts)
336  {
337  pts->insertAnotherMap(
338  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(otherMap)
339  .get(),
340  pose);
341  }
342  else
343  {
344  THROW_EXCEPTION(
345  "Merging with SE(3) transform only available for "
346  "metric maps of point cloud types.");
347  }
348  }
349  }
350 }
351 
352 size_t metric_map_t::size() const
353 {
354  size_t n = 0;
355 
356  n += lines.size();
357  n += planes.size();
358  n += size_points_only();
359 
360  return n;
361 }
363 {
364  size_t n = 0;
365  for (const auto& layer : layers)
366  {
367  if (auto pts =
368  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
369  pts)
370  { n += pts->size(); }
371  }
372  return n;
373 }
374 
376 {
377  using namespace std::string_literals;
378 
379  std::string ret;
380 
381  if (id) ret += "id="s + std::to_string(*id) + " "s;
382  if (label) ret += "label='"s + *label + "' "s;
383 
384  if (empty()) return {ret + "empty"s};
385 
386  const auto retAppend = [&ret](const std::string& s) {
387  if (!ret.empty()) ret += ", "s;
388  ret += s;
389  };
390 
391  if (!lines.empty()) retAppend(std::to_string(lines.size()) + " lines"s);
392  if (!planes.empty()) retAppend(std::to_string(planes.size()) + " planes"s);
393 
394  size_t nPts = 0;
395  for (const auto& layer : layers)
396  {
397  ASSERT_(layer.second);
398  if (auto pts =
399  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
400  pts)
401  { nPts += pts->size(); }
402  }
403 
404  if (nPts != 0)
405  {
406  retAppend(
407  std::to_string(nPts) + " points in "s +
408  std::to_string(layers.size()) + " layers ("s);
409 
410  for (const auto& layer : layers)
411  {
412  ret +=
413  "\""s + layer.first + "\":"s + layer.second->asString() + " "s;
414  }
415  ret += ")";
416  }
417 
418  return ret;
419 }
420 
421 bool metric_map_t::save_to_file(const std::string& fileName) const
422 {
423  auto f = mrpt::io::CFileGZOutputStream(fileName);
424  if (!f.is_open()) return false;
425 
426  auto arch = mrpt::serialization::archiveFrom(f);
427  arch << *this;
428 
429  return true;
430 }
431 
433 {
434  auto f = mrpt::io::CFileGZInputStream(fileName);
435  if (!f.is_open()) return false;
436 
437  auto arch = mrpt::serialization::archiveFrom(f);
438  arch >> *this;
439 
440  return true;
441 }
442 
444 {
445  try
446  {
447  return shared_from_this();
448  }
449  catch (const std::bad_weak_ptr&)
450  {
451  // Not created as a shared_ptr.
452  return {};
453  }
454 }
455 
457 {
458  Ptr ret = get_shared_from_this();
459  if (!ret) ret = std::make_shared<metric_map_t>(*this);
460  return ret;
461 }
462 
463 metric_map_t::ConstPtr metric_map_t::get_shared_from_this() const
464 {
465  try
466  {
467  return shared_from_this();
468  }
469  catch (const std::bad_weak_ptr&)
470  {
471  // Not created as a shared_ptr.
472  return {};
473  }
474 }
475 
476 metric_map_t::ConstPtr metric_map_t::get_shared_from_this_or_clone() const
477 {
478  ConstPtr ret = get_shared_from_this();
479  if (!ret) ret = std::make_shared<metric_map_t>(*this);
480  return ret;
481 }
482 
483 mrpt::maps::CPointsMap::Ptr metric_map_t::point_layer(
484  const layer_name_t& name) const
485 {
486  auto it = layers.find(name);
487  if (it == layers.end())
488  THROW_EXCEPTION_FMT("Layer '%s' does not exist.", name.c_str());
489 
490  const auto& ptr = it->second;
491  if (!ptr) return {}; // empty shared_ptr.
492 
493  auto ret = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(ptr);
494  if (!ret)
495  THROW_EXCEPTION_FMT(
496  "Layer '%s' is not a point cloud (actual class:'%s').",
497  name.c_str(), ptr->GetRuntimeClass()->className);
498 
499  return ret;
500 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::metric_map_t::empty
virtual bool empty() const
Definition: metricmap.cpp:245
s
XmlRpcServer s
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::render_params_point_layer_t
Definition: render_params.h:80
mp2p_icp::render_params_planes_t::visible
bool visible
Definition: render_params.h:36
mp2p_icp::metric_map_t::save_to_file
bool save_to_file(const std::string &fileName) const
Definition: metricmap.cpp:421
mp2p_icp::metric_map_t::get_visualization_points
void get_visualization_points(mrpt::opengl::CSetOfObjects &o, const render_params_points_t &p) const
Definition: metricmap.cpp:152
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::metric_map_t::derivedSerializeTo
virtual void derivedSerializeTo([[maybe_unused]] mrpt::serialization::CArchive &out) const
Definition: metricmap.h:200
mp2p_icp::metric_map_t::clear
virtual void clear()
Definition: metricmap.cpp:249
mrpt
Definition: LogRecord.h:99
mp2p_icp::metric_map_t::get_visualization_point_layer
static void get_visualization_point_layer(mrpt::opengl::CSetOfObjects &o, const render_params_point_layer_t &p, const mrpt::maps::CPointsMap::Ptr &pts)
Definition: metricmap.cpp:193
mp2p_icp::render_params_planes_t
Definition: render_params.h:32
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::render_params_lines_t::length
double length
all lines with same length
Definition: render_params.h:49
mp2p_icp::metric_map_t::label
std::optional< std::string > label
Definition: metricmap.h:95
mp2p_icp::render_params_planes_t::halfWidth
double halfWidth
Definition: render_params.h:37
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::metric_map_t::derivedSerializeFrom
virtual void derivedSerializeFrom([[maybe_unused]] mrpt::serialization::CArchive &in)
Definition: metricmap.h:206
mp2p_icp::render_params_lines_t
Definition: render_params.h:43
mp2p_icp::render_params_points_t::allLayers
render_params_point_layer_t allLayers
Definition: render_params.h:107
mp2p_icp::metric_map_t::planes
std::vector< plane_patch_t > planes
Definition: metricmap.h:80
mp2p_icp::render_params_point_layer_t::color
mrpt::img::TColor color
Definition: render_params.h:89
mp2p_icp::render_params_point_layer_t::pointSize
float pointSize
Definition: render_params.h:86
mp2p_icp::render_params_planes_t::gridSpacing
double gridSpacing
Definition: render_params.h:38
mp2p_icp::metric_map_t::lines
std::vector< mrpt::math::TLine3D > lines
Definition: metricmap.h:77
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:483
mp2p_icp::metric_map_t::contents_summary
virtual std::string contents_summary() const
Definition: metricmap.cpp:375
mp2p_icp::render_params_t
Definition: render_params.h:115
mp2p_icp::metric_map_t::size
virtual size_t size() const
Definition: metricmap.cpp:352
mp2p_icp::metric_map_t::get_visualization
virtual auto get_visualization(const render_params_t &p=render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
Definition: metricmap.cpp:96
mp2p_icp::metric_map_t::get_visualization_lines
void get_visualization_lines(mrpt::opengl::CSetOfObjects &o, const render_params_lines_t &p) const
Definition: metricmap.cpp:132
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:432
mp2p_icp::render_params_points_t::perLayer
std::map< layer_name_t, render_params_point_layer_t > perLayer
Definition: render_params.h:111
mp2p_icp::plane_patch_t
Definition: plane_patch.h:22
std
PointMatcherSupport::get
const M::mapped_type & get(const M &m, const typename M::key_type &k)
Definition: Bibliography.cpp:57
mp2p_icp::render_params_points_t
Definition: render_params.h:97
mp2p_icp::render_params_point_layer_t::colorMode
std::optional< color_mode_t > colorMode
Definition: render_params.h:93
mp2p_icp::render_params_lines_t::color
mrpt::img::TColor color
Definition: render_params.h:48
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:47
mp2p_icp::metric_map_t::get_visualization_planes
void get_visualization_planes(mrpt::opengl::CSetOfObjects &o, const render_params_planes_t &p) const
Definition: metricmap.cpp:110
mp2p_icp::metric_map_t::get_shared_from_this
Ptr get_shared_from_this()
Definition: metricmap.cpp:443
mp2p_icp::metric_map_t::size_points_only
virtual size_t size_points_only() const
Definition: metricmap.cpp:362
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
mp2p_icp::render_params_planes_t::color
mrpt::img::TColor color
Definition: render_params.h:39
mp2p_icp::metric_map_t::get_shared_from_this_or_clone
Ptr get_shared_from_this_or_clone()
Definition: metricmap.cpp:456
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:74
mp2p_icp::render_params_points_t::visible
bool visible
Definition: render_params.h:103


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