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-2024 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/maps/CVoxelMap.h>
17 #include <mrpt/maps/CVoxelMapRGB.h>
18 #include <mrpt/math/CHistogram.h>
19 #include <mrpt/math/distributions.h> // confidenceIntervals()
20 #include <mrpt/opengl/CGridPlaneXY.h>
21 #include <mrpt/opengl/CPointCloud.h>
22 #include <mrpt/opengl/CPointCloudColoured.h>
23 #include <mrpt/opengl/CSetOfLines.h>
24 #include <mrpt/opengl/CSetOfObjects.h>
25 #include <mrpt/serialization/CArchive.h>
26 #include <mrpt/serialization/optional_serialization.h>
27 #include <mrpt/serialization/stl_serialization.h>
28 #include <mrpt/system/string_utils.h> // unitsFormat()
29 
30 #include <algorithm>
31 #include <iterator>
32 
34  metric_map_t, mrpt::serialization::CSerializable, mp2p_icp)
35 
36 using namespace mp2p_icp;
37 
38 // Implementation of the CSerializable virtual interface:
39 uint8_t metric_map_t::serializeGetVersion() const { return 4; }
40 void metric_map_t::serializeTo(mrpt::serialization::CArchive& out) const
41 {
42  out << lines;
43 
44  out.WriteAs<uint32_t>(planes.size());
45  for (const auto& p : planes) out << p.plane << p.centroid;
46 
47  out.WriteAs<uint32_t>(lines.size());
48  for (const auto& l : lines) out << l;
49 
50  out.WriteAs<uint32_t>(layers.size());
51  for (const auto& l : layers) out << l.first << *l.second.get();
52 
53  out << id << label; // new in v1
54 
55  // new in v4: delegate to external function:
57 
58  // Optional user data:
60 }
61 void metric_map_t::serializeFrom(
62  mrpt::serialization::CArchive& in, uint8_t version)
63 {
64  switch (version)
65  {
66  case 0:
67  case 1:
68  case 2:
69  case 3:
70  case 4:
71  {
72  in >> lines;
73  const auto nPls = in.ReadAs<uint32_t>();
74  planes.resize(nPls);
75  for (auto& pl : planes) in >> pl.plane >> pl.centroid;
76 
77  const auto nLins = in.ReadAs<uint32_t>();
78  lines.resize(nLins);
79  for (auto& l : lines) in >> l;
80 
81  const auto nPts = in.ReadAs<uint32_t>();
82  layers.clear();
83  for (std::size_t i = 0; i < nPts; i++)
84  {
85  std::string name;
86  in >> name;
87  layers[name] = mrpt::ptr_cast<mrpt::maps::CMetricMap>::from(
88  in.ReadObject());
89  }
90 
91  if (version >= 1) { in >> id >> label; }
92  else
93  {
94  id.reset();
95  label.reset();
96  }
97 
98  georeferencing.reset();
99 
100  if ((version >= 2 && version < 4) && in.ReadAs<bool>())
101  {
102  auto& g = georeferencing.emplace();
103  in >> g.geo_coord.lat.decimal_value >>
104  g.geo_coord.lon.decimal_value >> g.geo_coord.height;
105  if (version >= 3) { in >> g.T_enu_to_map; }
106  else { in >> g.T_enu_to_map.mean; }
107  }
108 
109  // delegated function:
110  if (version >= 4) { in >> georeferencing; }
111 
112  // Optional user data:
114  }
115  break;
116  default:
117  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
118  };
119 }
120 
122  -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
123 {
124  MRPT_START
125  auto o = mrpt::opengl::CSetOfObjects::Create();
126 
127  get_visualization_planes(*o, p.planes);
128  get_visualization_lines(*o, p.lines);
129  get_visualization_points(*o, p.points);
130 
131  return o;
132  MRPT_END
133 }
134 
136  mrpt::opengl::CSetOfObjects& o, const render_params_planes_t& p) const
137 {
138  MRPT_START
139  if (!p.visible) return;
140 
141  const float pw = p.halfWidth, pf = p.gridSpacing;
142 
143  for (const auto& plane : planes)
144  {
145  auto gl_pl =
146  mrpt::opengl::CGridPlaneXY::Create(-pw, pw, -pw, pw, .0, pf);
147  gl_pl->setColor_u8(p.color);
148  mrpt::math::TPose3D planePose;
149  plane.plane.getAsPose3DForcingOrigin(plane.centroid, planePose);
150  gl_pl->setPose(planePose);
151  o.insert(gl_pl);
152  }
153 
154  MRPT_END
155 }
156 
158  mrpt::opengl::CSetOfObjects& o, const render_params_lines_t& p) const
159 {
160  MRPT_START
161 
162  auto glLin = mrpt::opengl::CSetOfLines::Create();
163  glLin->setColor_u8(p.color);
164 
165  for (size_t idxLine = 0; idxLine < lines.size(); idxLine++)
166  {
167  const auto& line = lines[idxLine];
168  double linLen = p.length;
169  const auto halfSeg = line.director * (0.5 * linLen);
170  glLin->appendLine(line.pBase - halfSeg, line.pBase + halfSeg);
171  }
172  o.insert(glLin);
173 
174  MRPT_END
175 }
176 
178  mrpt::opengl::CSetOfObjects& o, const render_params_points_t& p) const
179 {
180  MRPT_START
181  // Planes:
182  if (!p.visible) return;
183 
184  if (!p.perLayer.empty())
185  {
186  // render only these layers:
187  for (const auto& kv : p.perLayer)
188  {
189  const auto itPts = layers.find(kv.first);
190  if (itPts == layers.end())
191  THROW_EXCEPTION_FMT(
192  "Rendering parameters given for layer '%s' which does not "
193  "exist in this metric_map_t object",
194  kv.first.c_str());
195 
196  get_visualization_map_layer(o, kv.second, itPts->second);
197  }
198  }
199  else
200  {
201  // render all layers with the same params:
202  for (const auto& kv : layers)
203  {
204  get_visualization_map_layer(o, p.allLayers, kv.second);
205  }
206  }
207 
208  MRPT_END
209 }
210 
212  mrpt::opengl::CSetOfObjects& o, const render_params_point_layer_t& p,
213  const mrpt::maps::CMetricMap::Ptr& map)
214 {
215  mrpt::maps::CPointsMap::Ptr pts;
216 
217  auto voxelMap = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(map);
218  auto voxelRGBMap = std::dynamic_pointer_cast<mrpt::maps::CVoxelMapRGB>(map);
219  if (voxelMap || voxelRGBMap)
220  {
222  {
223  // get occupied voxel XYZ coordinates only:
224  if (voxelMap) pts = voxelMap->getOccupiedVoxels();
225  if (voxelRGBMap) pts = voxelRGBMap->getOccupiedVoxels();
226  }
227  else
228  {
229  // Render as real voxelmaps:
230  if (voxelMap)
231  {
232  voxelMap->renderingOptions.generateFreeVoxels =
234  }
235  else if (voxelRGBMap)
236  {
237  voxelRGBMap->renderingOptions.generateFreeVoxels =
239  }
240 
241  // regular render method:
242  map->getVisualizationInto(o);
243  return;
244  }
245  }
246  else { pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(map); }
247 
248  if (!pts ||
249  (p.colorMode.has_value() && p.colorMode->keep_original_cloud_color))
250  {
251  // Not convertible to point maps or user selected their original colors,
252  // use its own default renderer:
253  map->getVisualizationInto(o);
254 
255  // apply the point size, if possible:
256  if (auto glPtsCol = o.getByClass<mrpt::opengl::CPointCloudColoured>();
257  glPtsCol)
258  {
259  glPtsCol->setPointSize(p.pointSize);
260  }
261  else if (auto glPts = o.getByClass<mrpt::opengl::CPointCloud>(); glPts)
262  {
263  glPts->setPointSize(p.pointSize);
264  }
265 
266  return;
267  }
268 
269  if (pts && pts->empty()) return; // quick return if empty point cloud
270 
271  if (p.colorMode.has_value())
272  {
273  // color point cloud:
274  auto glPts = mrpt::opengl::CPointCloudColoured::Create();
275  glPts->loadFromPointsMap(pts.get());
276 
277  glPts->setPointSize(p.pointSize);
278 
279  mrpt::math::TBoundingBoxf bb;
280 
281  const bool hasToAutoFindBB =
282  (!p.colorMode->colorMapMinCoord.has_value() ||
283  !p.colorMode->colorMapMaxCoord.has_value());
284 
285  if (hasToAutoFindBB) bb = pts->boundingBox();
286 
287  ASSERT_(p.colorMode->recolorizeByCoordinate.has_value());
288 
289  const unsigned int coordIdx = static_cast<unsigned int>(
290  p.colorMode->recolorizeByCoordinate.value());
291  ASSERT_(coordIdx < 3);
292 
293  float min = bb.min[coordIdx], max = bb.max[coordIdx];
294 
295  if (hasToAutoFindBB &&
296  p.colorMode->autoBoundingBoxOutliersPercentile.has_value())
297  {
298  const float confidenceInterval =
299  *p.colorMode->autoBoundingBoxOutliersPercentile;
300 
301  // handle planar maps (avoids error in histogram below):
302  for (int i = 0; i < 3; i++)
303  if (bb.max[i] == bb.min[i]) bb.max[i] = bb.min[i] + 0.1f;
304 
305  // Use a histogram to discard outliers from the colormap extremes:
306  constexpr size_t nBins = 100;
307  // for x,y,z
308  std::array<mrpt::math::CHistogram, 3> hists = {
309  mrpt::math::CHistogram(bb.min.x, bb.max.x, nBins),
310  mrpt::math::CHistogram(bb.min.y, bb.max.y, nBins),
311  mrpt::math::CHistogram(bb.min.z, bb.max.z, nBins)};
312 
313  const auto lambdaVisitPoints =
314  [&hists](const mrpt::math::TPoint3Df& pt)
315  {
316  for (int i = 0; i < 3; i++) hists[i].add(pt[i]);
317  };
318 
319  for (size_t i = 0; i < pts->size(); i++)
320  {
321  mrpt::math::TPoint3Df pt;
322  pts->getPoint(i, pt.x, pt.y, pt.z);
323  lambdaVisitPoints(pt);
324  }
325 
326  // Analyze the histograms and get confidence intervals:
327  std::vector<double> coords;
328  std::vector<double> hits;
329 
330  hists[coordIdx].getHistogramNormalized(coords, hits);
331  mrpt::math::confidenceIntervalsFromHistogram(
332  coords, hits, min, max, confidenceInterval);
333 
334  } // end compute outlier limits
335 
336  const float coordMin = p.colorMode->colorMapMinCoord.has_value()
337  ? *p.colorMode->colorMapMinCoord
338  : min;
339 
340  const float coordMax = p.colorMode->colorMapMaxCoord.has_value()
341  ? *p.colorMode->colorMapMaxCoord
342  : max;
343 
344  glPts->recolorizeByCoordinate(
345  coordMin, coordMax, coordIdx, p.colorMode->colorMap);
346 
347  o.insert(glPts);
348  }
349  else
350  {
351  // uniform color point cloud:
352  auto glPts = mrpt::opengl::CPointCloud::Create();
353  glPts->loadFromPointsMap(pts.get());
354 
355  glPts->setPointSize(p.pointSize);
356  glPts->setColor_u8(p.color);
357 
358  o.insert(glPts);
359  }
360 }
361 
363 {
364  return layers.empty() && lines.empty() && planes.empty();
365 }
366 void metric_map_t::clear() { *this = metric_map_t(); }
367 
368 // TODO(JLBC): Write unit test for mergeWith()
369 
371  const metric_map_t& otherPc,
372  const std::optional<mrpt::math::TPose3D>& otherRelativePose)
373 {
374  mrpt::poses::CPose3D pose;
375  if (otherRelativePose.has_value())
376  pose = mrpt::poses::CPose3D(otherRelativePose.value());
377 
378  // Lines:
379  if (otherRelativePose.has_value())
380  {
381  std::transform(
382  otherPc.lines.begin(), otherPc.lines.end(),
383  std::back_inserter(lines),
384  [&](const mrpt::math::TLine3D& l)
385  {
386  return mrpt::math::TLine3D::FromPointAndDirector(
387  pose.composePoint(l.pBase),
388  pose.rotateVector(l.getDirectorVector()));
389  });
390  }
391  else
392  {
393  std::copy(
394  otherPc.lines.begin(), otherPc.lines.end(),
395  std::back_inserter(lines));
396  }
397 
398  // Planes:
399  if (otherRelativePose.has_value())
400  {
401  std::transform(
402  otherPc.planes.begin(), otherPc.planes.end(),
403  std::back_inserter(planes),
404  [&](const plane_patch_t& l)
405  {
406  plane_patch_t g;
407  g.centroid = pose.composePoint(l.centroid);
408 
409  // TODO(JLBC): Finish rotating planes
410  // ...
411  THROW_EXCEPTION("To-do");
412  return g;
413  });
414  }
415  else
416  {
417  std::copy(
418  otherPc.planes.begin(), otherPc.planes.end(),
419  std::back_inserter(planes));
420  }
421 
422  // Points:
423  for (const auto& layer : otherPc.layers)
424  {
425  const auto& name = layer.first;
426  const auto& otherMap = layer.second;
427 
428  // New layer?
429  if (layers.count(name) == 0)
430  {
431  // Make a copy and transform (if applicable):
432  layers[name] = std::dynamic_pointer_cast<mrpt::maps::CMetricMap>(
433  otherMap->duplicateGetSmartPtr());
434 
435  if (otherRelativePose.has_value())
436  {
437  if (auto pts =
438  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
439  layers[name]);
440  pts)
441  {
442  // Transform:
443  pts->changeCoordinatesReference(pose);
444  }
445  else
446  {
447  THROW_EXCEPTION(
448  "Merging with SE(3) transform only available for "
449  "metric maps of point cloud types.");
450  }
451  }
452  }
453  else
454  {
455  // merge with existing layer:
456  if (auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
457  layers[name]);
458  pts)
459  {
460  pts->insertAnotherMap(
461  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(otherMap)
462  .get(),
463  pose);
464  }
465  else
466  {
467  THROW_EXCEPTION(
468  "Merging with SE(3) transform only available for "
469  "metric maps of point cloud types.");
470  }
471  }
472  }
473 }
474 
475 size_t metric_map_t::size() const
476 {
477  size_t n = 0;
478 
479  n += lines.size();
480  n += planes.size();
481  n += size_points_only();
482 
483  return n;
484 }
486 {
487  size_t n = 0;
488  for (const auto& layer : layers)
489  {
490  if (auto pts =
491  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
492  pts)
493  {
494  n += pts->size();
495  }
496  }
497  return n;
498 }
499 
501 {
502  using namespace std::string_literals;
503 
504  std::string ret;
505 
506  if (id) ret += "id="s + std::to_string(*id) + " "s;
507  if (label) ret += "label='"s + *label + "' "s;
508 
509  if (georeferencing)
510  {
511  const auto& gc = georeferencing->geo_coord;
512  ret += "georeferenced: "s + "lat="s + gc.lat.getAsString() + " lon="s +
513  gc.lon.getAsString() +
514  mrpt::format(
515  " (%.09f %.09f) ", gc.lat.getDecimalValue(),
516  gc.lon.getDecimalValue()) +
517  " h="s + std::to_string(gc.height) + " T_enu_map="s +
518  georeferencing->T_enu_to_map.asString();
519  }
520 
521  if (empty()) return {ret + "empty"s};
522 
523  const auto retAppend = [&ret](const std::string& s)
524  {
525  if (!ret.empty()) ret += ", "s;
526  ret += s;
527  };
528 
529  if (!lines.empty()) retAppend(std::to_string(lines.size()) + " lines"s);
530  if (!planes.empty()) retAppend(std::to_string(planes.size()) + " planes"s);
531 
532  size_t nPts = 0, nVoxels = 0;
533  bool otherLayers = false;
534  for (const auto& layer : layers)
535  {
536  ASSERT_(layer.second);
537  if (auto pts =
538  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
539  pts)
540  {
541  nPts += pts->size();
542  }
543  else if (auto vxs = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(
544  layer.second);
545  vxs)
546  {
547  nVoxels += vxs->grid().activeCellsCount();
548  }
549  else
550  otherLayers = true;
551  }
552 
553  if (nPts != 0 || nVoxels != 0 || otherLayers)
554  {
555  retAppend(
556  mrpt::system::unitsFormat(static_cast<double>(nPts), 2, false) +
557  " points, "s +
558  mrpt::system::unitsFormat(static_cast<double>(nVoxels), 2, false) +
559  " voxels in "s + std::to_string(layers.size()) + " layers ("s);
560 
561  for (const auto& layer : layers)
562  {
563  ret +=
564  "\""s + layer.first + "\":"s + layer.second->asString() + " "s;
565  }
566  ret += ")";
567  }
568 
569  return ret;
570 }
571 
572 bool metric_map_t::save_to_file(const std::string& fileName) const
573 {
574  auto f = mrpt::io::CFileGZOutputStream(fileName);
575  if (!f.is_open()) return false;
576 
577  auto arch = mrpt::serialization::archiveFrom(f);
578  arch << *this;
579 
580  return true;
581 }
582 
584 {
585  auto f = mrpt::io::CFileGZInputStream(fileName);
586  if (!f.is_open()) return false;
587 
588  auto arch = mrpt::serialization::archiveFrom(f);
589  arch >> *this;
590 
591  return true;
592 }
593 
595 {
596  try
597  {
598  return shared_from_this();
599  }
600  catch (const std::bad_weak_ptr&)
601  {
602  // Not created as a shared_ptr.
603  return {};
604  }
605 }
606 
608 {
609  Ptr ret = get_shared_from_this();
610  if (!ret) ret = std::make_shared<metric_map_t>(*this);
611  return ret;
612 }
613 
614 metric_map_t::ConstPtr metric_map_t::get_shared_from_this() const
615 {
616  try
617  {
618  return shared_from_this();
619  }
620  catch (const std::bad_weak_ptr&)
621  {
622  // Not created as a shared_ptr.
623  return {};
624  }
625 }
626 
627 metric_map_t::ConstPtr metric_map_t::get_shared_from_this_or_clone() const
628 {
629  ConstPtr ret = get_shared_from_this();
630  if (!ret) ret = std::make_shared<metric_map_t>(*this);
631  return ret;
632 }
633 
634 mrpt::maps::CPointsMap::Ptr metric_map_t::point_layer(
635  const layer_name_t& name) const
636 {
637  auto it = layers.find(name);
638  if (it == layers.end())
639  THROW_EXCEPTION_FMT("Layer '%s' does not exist.", name.c_str());
640 
641  const auto& ptr = it->second;
642  if (!ptr) return {}; // empty shared_ptr.
643 
644  auto ret = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(ptr);
645  if (!ret)
646  THROW_EXCEPTION_FMT(
647  "Layer '%s' is not a point cloud (actual class:'%s').",
648  name.c_str(), ptr->GetRuntimeClass()->className);
649 
650  return ret;
651 }
652 
653 const mrpt::maps::CPointsMap* mp2p_icp::MapToPointsMap(
654  const mrpt::maps::CMetricMap& map)
655 {
656  if (auto ptsMap = dynamic_cast<const mrpt::maps::CPointsMap*>(&map); ptsMap)
657  {
658  return ptsMap;
659  }
660  if (auto voxelMap = dynamic_cast<const mrpt::maps::CVoxelMap*>(&map);
661  voxelMap)
662  {
663  return voxelMap->getOccupiedVoxels().get();
664  }
665  if (auto voxelRGBMap = dynamic_cast<const mrpt::maps::CVoxelMapRGB*>(&map);
666  voxelRGBMap)
667  {
668  return voxelRGBMap->getOccupiedVoxels().get();
669  }
670  return {};
671 }
672 
673 mrpt::maps::CPointsMap* mp2p_icp::MapToPointsMap(mrpt::maps::CMetricMap& map)
674 {
675  if (auto ptsMap = dynamic_cast<mrpt::maps::CPointsMap*>(&map); ptsMap)
676  {
677  return ptsMap;
678  }
679  if (auto voxelMap = dynamic_cast<mrpt::maps::CVoxelMap*>(&map); voxelMap)
680  {
681  return voxelMap->getOccupiedVoxels().get();
682  }
683  if (auto voxelRGBMap = dynamic_cast<mrpt::maps::CVoxelMapRGB*>(&map);
684  voxelRGBMap)
685  {
686  return voxelRGBMap->getOccupiedVoxels().get();
687  }
688  return {};
689 }
690 
691 const mrpt::maps::NearestNeighborsCapable* mp2p_icp::MapToNN(
692  const mrpt::maps::CMetricMap& map, bool throwIfNotImplemented)
693 {
694  const auto* ptr =
695  dynamic_cast<const mrpt::maps::NearestNeighborsCapable*>(&map);
696 
697  if (ptr) return ptr;
698  if (!throwIfNotImplemented) return nullptr;
699 
700  THROW_EXCEPTION_FMT(
701  "The map of type '%s' does not implement the expected interface "
702  "mrpt::maps::NearestNeighborsCapable",
703  map.GetRuntimeClass()->className);
704 }
705 
707  const mrpt::maps::CMetricMap& map, bool throwIfNotImplemented)
708 {
709  const auto* ptr = dynamic_cast<const mp2p_icp::NearestPlaneCapable*>(&map);
710 
711  if (ptr) return ptr;
712  if (!throwIfNotImplemented) return nullptr;
713 
714  THROW_EXCEPTION_FMT(
715  "The map of type '%s' does not implement the expected interface "
716  "mp2p_icp::NearestPlaneCapable",
717  map.GetRuntimeClass()->className);
718 }
719 
720 // Serialization of geo-reference information:
721 constexpr const char* GEOREF_MAGIC_STR = "mp2p_icp::Georeferencing";
722 
723 mrpt::serialization::CArchive& mp2p_icp::operator>>(
724  mrpt::serialization::CArchive& in,
725  std::optional<metric_map_t::Georeferencing>& g)
726 {
727  std::string georef_stream_signature;
728  in >> georef_stream_signature;
729  ASSERT_EQUAL_(georef_stream_signature, std::string(GEOREF_MAGIC_STR));
730  const uint8_t version = in.ReadAs<uint8_t>();
731  switch (version)
732  {
733  case 0:
734  if (in.ReadAs<bool>())
735  {
736  auto& gg = g.emplace();
737  in >> gg.geo_coord.lat.decimal_value >>
738  gg.geo_coord.lon.decimal_value >> gg.geo_coord.height;
739  in >> gg.T_enu_to_map;
740  }
741  break;
742  default:
743  MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
744  };
745 
746  return in;
747 }
748 
749 mrpt::serialization::CArchive& mp2p_icp::operator<<(
750  mrpt::serialization::CArchive& out,
751  const std::optional<metric_map_t::Georeferencing>& g)
752 {
754  constexpr uint8_t serial_version = 0;
755  out.WriteAs<uint8_t>(serial_version);
756 
757  out.WriteAs<bool>(g.has_value());
758  if (g)
759  {
760  out << g->geo_coord.lat.decimal_value << g->geo_coord.lon.decimal_value
761  << g->geo_coord.height;
762  out << g->T_enu_to_map;
763  }
764  return out;
765 }
min
int min(int a, int b)
mp2p_icp
Definition: covariance.h:17
mp2p_icp::metric_map_t::empty
virtual bool empty() const
Definition: metricmap.cpp:362
mp2p_icp::operator>>
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, Pairings &obj)
Definition: Pairings.cpp:55
mp2p_icp::metric_map_t::get_visualization_map_layer
static void get_visualization_map_layer(mrpt::opengl::CSetOfObjects &o, const render_params_point_layer_t &p, const mrpt::maps::CMetricMap::Ptr &map)
Definition: metricmap.cpp:211
s
XmlRpcServer s
mp2p_icp::render_params_point_layer_t::render_voxelmaps_as_points
bool render_voxelmaps_as_points
Definition: render_params.h:139
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::render_params_point_layer_t
Definition: render_params.h:124
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
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:572
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:177
mp2p_icp::metric_map_t::derivedSerializeTo
virtual void derivedSerializeTo([[maybe_unused]] mrpt::serialization::CArchive &out) const
Definition: metricmap.h:222
mp2p_icp::metric_map_t::clear
virtual void clear()
Definition: metricmap.cpp:366
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:59
mp2p_icp::metric_map_t::label
std::optional< std::string > label
Definition: metricmap.h:97
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:228
mp2p_icp::render_params_point_layer_t::render_voxelmaps_free_space
bool render_voxelmaps_free_space
Definition: render_params.h:140
mp2p_icp::render_params_lines_t
Definition: render_params.h:53
mp2p_icp::render_params_points_t::allLayers
render_params_point_layer_t allLayers
Definition: render_params.h:166
mp2p_icp::metric_map_t::planes
std::vector< plane_patch_t > planes
Definition: metricmap.h:82
mp2p_icp::render_params_point_layer_t::color
mrpt::img::TColor color
Definition: render_params.h:133
mp2p_icp::render_params_point_layer_t::pointSize
float pointSize
Definition: render_params.h:130
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:653
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:79
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:634
mp2p_icp::NearestPlaneCapable
Definition: NearestPlaneCapable.h:25
mp2p_icp::metric_map_t::merge_with
virtual void merge_with(const metric_map_t &otherPc, const std::optional< mrpt::math::TPose3D > &otherRelativePose=std::nullopt)
Definition: metricmap.cpp:370
mp2p_icp::metric_map_t::contents_summary
virtual std::string contents_summary() const
Definition: metricmap.cpp:500
mp2p_icp::render_params_t
Definition: render_params.h:184
mp2p_icp::metric_map_t::size
virtual size_t size() const
Definition: metricmap.cpp:475
GEOREF_MAGIC_STR
constexpr const char * GEOREF_MAGIC_STR
Definition: metricmap.cpp:721
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:121
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:157
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:583
mp2p_icp::render_params_points_t::perLayer
std::map< layer_name_t, render_params_point_layer_t > perLayer
Definition: render_params.h:170
add
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
mp2p_icp::plane_patch_t
Definition: plane_patch.h:22
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:156
mp2p_icp::operator<<
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const Pairings &obj)
Definition: Pairings.cpp:48
mp2p_icp::render_params_point_layer_t::colorMode
std::optional< color_mode_t > colorMode
Definition: render_params.h:137
mp2p_icp::render_params_lines_t::color
mrpt::img::TColor color
Definition: render_params.h:58
boost::posix_time
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:49
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:135
mp2p_icp::metric_map_t::georeferencing
std::optional< Georeferencing > georeferencing
Definition: metricmap.h:117
mp2p_icp::metric_map_t::get_shared_from_this
Ptr get_shared_from_this()
Definition: metricmap.cpp:594
mp2p_icp::metric_map_t::size_points_only
virtual size_t size_points_only() const
Definition: metricmap.cpp:485
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:607
mp2p_icp::MapToNN
const mrpt::maps::NearestNeighborsCapable * MapToNN(const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
Definition: metricmap.cpp:691
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
mp2p_icp::render_params_points_t::visible
bool visible
Definition: render_params.h:162
mp2p_icp::MapToNP
const mp2p_icp::NearestPlaneCapable * MapToNP(const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
Definition: metricmap.cpp:706


mp2p_icp
Author(s):
autogenerated on Wed Feb 26 2025 03:45:47