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>
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>
34 metric_map_t, mrpt::serialization::CSerializable,
mp2p_icp)
39 uint8_t metric_map_t::serializeGetVersion()
const {
return 4; }
40 void metric_map_t::serializeTo(mrpt::serialization::CArchive&
out)
const
45 for (
const auto& p :
planes)
out << p.plane << p.centroid;
48 for (
const auto& l :
lines)
out << l;
51 for (
const auto& l :
layers)
out << l.first << *l.second.get();
61 void metric_map_t::serializeFrom(
62 mrpt::serialization::CArchive& in, uint8_t version)
73 const auto nPls = in.ReadAs<uint32_t>();
75 for (
auto& pl :
planes) in >> pl.plane >> pl.centroid;
77 const auto nLins = in.ReadAs<uint32_t>();
79 for (
auto& l :
lines) in >> l;
81 const auto nPts = in.ReadAs<uint32_t>();
83 for (std::size_t i = 0; i < nPts; i++)
87 layers[name] = mrpt::ptr_cast<mrpt::maps::CMetricMap>::from(
91 if (version >= 1) { in >>
id >>
label; }
100 if ((version >= 2 && version < 4) && in.ReadAs<
bool>())
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; }
117 MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
122 -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
125 auto o = mrpt::opengl::CSetOfObjects::Create();
127 get_visualization_planes(*o, p.planes);
128 get_visualization_lines(*o, p.lines);
129 get_visualization_points(*o, p.points);
143 for (
const auto& plane :
planes)
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);
162 auto glLin = mrpt::opengl::CSetOfLines::Create();
163 glLin->setColor_u8(p.
color);
165 for (
size_t idxLine = 0; idxLine <
lines.size(); idxLine++)
167 const auto& line =
lines[idxLine];
169 const auto halfSeg = line.director * (0.5 * linLen);
170 glLin->appendLine(line.pBase - halfSeg, line.pBase + halfSeg);
189 const auto itPts =
layers.find(kv.first);
190 if (itPts ==
layers.end())
192 "Rendering parameters given for layer '%s' which does not "
193 "exist in this metric_map_t object",
202 for (
const auto& kv :
layers)
213 const mrpt::maps::CMetricMap::Ptr& map)
215 mrpt::maps::CPointsMap::Ptr pts;
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)
224 if (voxelMap) pts = voxelMap->getOccupiedVoxels();
225 if (voxelRGBMap) pts = voxelRGBMap->getOccupiedVoxels();
232 voxelMap->renderingOptions.generateFreeVoxels =
235 else if (voxelRGBMap)
237 voxelRGBMap->renderingOptions.generateFreeVoxels =
242 map->getVisualizationInto(o);
246 else { pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(map); }
253 map->getVisualizationInto(o);
256 if (
auto glPtsCol = o.getByClass<mrpt::opengl::CPointCloudColoured>();
261 else if (
auto glPts = o.getByClass<mrpt::opengl::CPointCloud>(); glPts)
269 if (pts && pts->empty())
return;
274 auto glPts = mrpt::opengl::CPointCloudColoured::Create();
275 glPts->loadFromPointsMap(pts.get());
279 mrpt::math::TBoundingBoxf bb;
281 const bool hasToAutoFindBB =
282 (!p.
colorMode->colorMapMinCoord.has_value() ||
283 !p.
colorMode->colorMapMaxCoord.has_value());
285 if (hasToAutoFindBB) bb = pts->boundingBox();
287 ASSERT_(p.
colorMode->recolorizeByCoordinate.has_value());
289 const unsigned int coordIdx =
static_cast<unsigned int>(
290 p.
colorMode->recolorizeByCoordinate.value());
291 ASSERT_(coordIdx < 3);
293 float min = bb.min[coordIdx], max = bb.max[coordIdx];
295 if (hasToAutoFindBB &&
296 p.
colorMode->autoBoundingBoxOutliersPercentile.has_value())
298 const float confidenceInterval =
299 *p.
colorMode->autoBoundingBoxOutliersPercentile;
302 for (
int i = 0; i < 3; i++)
303 if (bb.max[i] == bb.min[i]) bb.max[i] = bb.min[i] + 0.1f;
306 constexpr
size_t nBins = 100;
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)};
313 const auto lambdaVisitPoints =
314 [&hists](
const mrpt::math::TPoint3Df&
pt)
316 for (
int i = 0; i < 3; i++) hists[i].
add(
pt[i]);
319 for (
size_t i = 0; i < pts->size(); i++)
321 mrpt::math::TPoint3Df
pt;
322 pts->getPoint(i,
pt.x,
pt.y,
pt.z);
323 lambdaVisitPoints(
pt);
327 std::vector<double> coords;
328 std::vector<double> hits;
330 hists[coordIdx].getHistogramNormalized(coords, hits);
331 mrpt::math::confidenceIntervalsFromHistogram(
332 coords, hits,
min, max, confidenceInterval);
336 const float coordMin = p.
colorMode->colorMapMinCoord.has_value()
340 const float coordMax = p.
colorMode->colorMapMaxCoord.has_value()
344 glPts->recolorizeByCoordinate(
345 coordMin, coordMax, coordIdx, p.
colorMode->colorMap);
352 auto glPts = mrpt::opengl::CPointCloud::Create();
353 glPts->loadFromPointsMap(pts.get());
356 glPts->setColor_u8(p.
color);
372 const std::optional<mrpt::math::TPose3D>& otherRelativePose)
374 mrpt::poses::CPose3D pose;
375 if (otherRelativePose.has_value())
376 pose = mrpt::poses::CPose3D(otherRelativePose.value());
379 if (otherRelativePose.has_value())
383 std::back_inserter(
lines),
384 [&](
const mrpt::math::TLine3D& l)
386 return mrpt::math::TLine3D::FromPointAndDirector(
387 pose.composePoint(l.pBase),
388 pose.rotateVector(l.getDirectorVector()));
395 std::back_inserter(
lines));
399 if (otherRelativePose.has_value())
403 std::back_inserter(
planes),
407 g.centroid = pose.composePoint(l.centroid);
411 THROW_EXCEPTION(
"To-do");
419 std::back_inserter(
planes));
423 for (
const auto& layer : otherPc.
layers)
425 const auto& name = layer.first;
426 const auto& otherMap = layer.second;
429 if (
layers.count(name) == 0)
432 layers[name] = std::dynamic_pointer_cast<mrpt::maps::CMetricMap>(
433 otherMap->duplicateGetSmartPtr());
435 if (otherRelativePose.has_value())
438 std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
443 pts->changeCoordinatesReference(pose);
448 "Merging with SE(3) transform only available for "
449 "metric maps of point cloud types.");
456 if (
auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
460 pts->insertAnotherMap(
461 std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(otherMap)
468 "Merging with SE(3) transform only available for "
469 "metric maps of point cloud types.");
488 for (
const auto& layer :
layers)
491 std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
502 using namespace std::string_literals;
506 if (
id) ret +=
"id="s + std::to_string(*
id) +
" "s;
510 ret +=
"georeferenced: lat="s +
516 if (
empty())
return {ret +
"empty"s};
520 if (!ret.empty()) ret +=
", "s;
524 if (!
lines.empty()) retAppend(std::to_string(
lines.size()) +
" lines"s);
525 if (!
planes.empty()) retAppend(std::to_string(
planes.size()) +
" planes"s);
527 size_t nPts = 0, nVoxels = 0;
528 bool otherLayers =
false;
529 for (
const auto& layer :
layers)
531 ASSERT_(layer.second);
533 std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second);
538 else if (
auto vxs = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(
542 nVoxels += vxs->grid().activeCellsCount();
548 if (nPts != 0 || nVoxels != 0 || otherLayers)
551 mrpt::system::unitsFormat(
static_cast<double>(nPts), 2,
false) +
553 mrpt::system::unitsFormat(
static_cast<double>(nVoxels), 2,
false) +
554 " voxels in "s + std::to_string(
layers.size()) +
" layers ("s);
556 for (
const auto& layer :
layers)
559 "\""s + layer.first +
"\":"s + layer.second->asString() +
" "s;
569 auto f = mrpt::io::CFileGZOutputStream(fileName);
570 if (!
f.is_open())
return false;
572 auto arch = mrpt::serialization::archiveFrom(
f);
580 auto f = mrpt::io::CFileGZInputStream(fileName);
581 if (!
f.is_open())
return false;
583 auto arch = mrpt::serialization::archiveFrom(
f);
593 return shared_from_this();
595 catch (
const std::bad_weak_ptr&)
605 if (!ret) ret = std::make_shared<metric_map_t>(*
this);
613 return shared_from_this();
615 catch (
const std::bad_weak_ptr&)
625 if (!ret) ret = std::make_shared<metric_map_t>(*
this);
632 auto it =
layers.find(name);
634 THROW_EXCEPTION_FMT(
"Layer '%s' does not exist.", name.c_str());
636 const auto& ptr = it->second;
639 auto ret = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(ptr);
642 "Layer '%s' is not a point cloud (actual class:'%s').",
643 name.c_str(), ptr->GetRuntimeClass()->className);
649 const mrpt::maps::CMetricMap& map)
651 if (
auto ptsMap =
dynamic_cast<const mrpt::maps::CPointsMap*
>(&map); ptsMap)
655 if (
auto voxelMap =
dynamic_cast<const mrpt::maps::CVoxelMap*
>(&map);
658 return voxelMap->getOccupiedVoxels().get();
660 if (
auto voxelRGBMap =
dynamic_cast<const mrpt::maps::CVoxelMapRGB*
>(&map);
663 return voxelRGBMap->getOccupiedVoxels().get();
670 if (
auto ptsMap =
dynamic_cast<mrpt::maps::CPointsMap*
>(&map); ptsMap)
674 if (
auto voxelMap =
dynamic_cast<mrpt::maps::CVoxelMap*
>(&map); voxelMap)
676 return voxelMap->getOccupiedVoxels().get();
678 if (
auto voxelRGBMap =
dynamic_cast<mrpt::maps::CVoxelMapRGB*
>(&map);
681 return voxelRGBMap->getOccupiedVoxels().get();
687 const mrpt::maps::CMetricMap& map,
bool throwIfNotImplemented)
690 dynamic_cast<const mrpt::maps::NearestNeighborsCapable*
>(&map);
693 if (!throwIfNotImplemented)
return nullptr;
696 "The map of type '%s' does not implement the expected interface "
697 "mrpt::maps::NearestNeighborsCapable",
698 map.GetRuntimeClass()->className);
702 const mrpt::maps::CMetricMap& map,
bool throwIfNotImplemented)
707 if (!throwIfNotImplemented)
return nullptr;
710 "The map of type '%s' does not implement the expected interface "
711 "mp2p_icp::NearestPlaneCapable",
712 map.GetRuntimeClass()->className);
719 mrpt::serialization::CArchive& in,
720 std::optional<metric_map_t::Georeferencing>& g)
723 in >> georef_stream_signature;
725 const uint8_t version = in.ReadAs<uint8_t>();
729 if (in.ReadAs<
bool>())
731 auto& gg = g.emplace();
732 in >> gg.geo_coord.lat.decimal_value >>
733 gg.geo_coord.lon.decimal_value >> gg.geo_coord.height;
734 in >> gg.T_enu_to_map;
738 MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
745 mrpt::serialization::CArchive&
out,
746 const std::optional<metric_map_t::Georeferencing>& g)
749 constexpr uint8_t serial_version = 0;
750 out.WriteAs<uint8_t>(serial_version);
752 out.WriteAs<
bool>(g.has_value());
755 out << g->geo_coord.lat.decimal_value << g->geo_coord.lon.decimal_value
756 << g->geo_coord.height;
757 out << g->T_enu_to_map;