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


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