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>   
   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>   
   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(mrpt::serialization::CArchive& in, uint8_t version)
 
   72             const auto nPls = in.ReadAs<uint32_t>();
 
   74             for (
auto& pl : 
planes) in >> pl.plane >> pl.centroid;
 
   76             const auto nLins = in.ReadAs<uint32_t>();
 
   78             for (
auto& l : 
lines) in >> l;
 
   80             const auto nPts = in.ReadAs<uint32_t>();
 
   82             for (std::size_t i = 0; i < nPts; i++)
 
   86                 layers[name] = mrpt::ptr_cast<mrpt::maps::CMetricMap>::from(in.ReadObject());
 
  101             if ((version >= 2 && version < 4) && in.ReadAs<
bool>())
 
  104                 in >> g.geo_coord.lat.decimal_value >> g.geo_coord.lon.decimal_value >>
 
  108                     in >> g.T_enu_to_map;
 
  112                     in >> g.T_enu_to_map.mean;
 
  127             MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
 
  132     -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
 
  135     auto o = mrpt::opengl::CSetOfObjects::Create();
 
  137     get_visualization_planes(*o, p.planes);
 
  138     get_visualization_lines(*o, p.lines);
 
  139     get_visualization_points(*o, p.points);
 
  153     for (
const auto& plane : 
planes)
 
  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);
 
  171     auto glLin = mrpt::opengl::CSetOfLines::Create();
 
  172     glLin->setColor_u8(p.
color);
 
  174     for (
size_t idxLine = 0; idxLine < 
lines.size(); idxLine++)
 
  176         const auto& line    = 
lines[idxLine];
 
  178         const auto  halfSeg = line.director * (0.5 * linLen);
 
  179         glLin->appendLine(line.pBase - halfSeg, line.pBase + halfSeg);
 
  198             const auto itPts = 
layers.find(kv.first);
 
  199             if (itPts == 
layers.end())
 
  201                     "Rendering parameters given for layer '%s' which does not " 
  202                     "exist in this metric_map_t object",
 
  211         for (
const auto& kv : 
layers)
 
  222     const mrpt::maps::CMetricMap::Ptr& map)
 
  224     mrpt::maps::CPointsMap::Ptr pts;
 
  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)
 
  233             if (voxelMap) pts = voxelMap->getOccupiedVoxels();
 
  234             if (voxelRGBMap) pts = voxelRGBMap->getOccupiedVoxels();
 
  243             else if (voxelRGBMap)
 
  249             map->getVisualizationInto(o);
 
  255         pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(map);
 
  262         map->getVisualizationInto(o);
 
  265         if (
auto glPtsCol = o.getByClass<mrpt::opengl::CPointCloudColoured>(); glPtsCol)
 
  269         else if (
auto glPts = o.getByClass<mrpt::opengl::CPointCloud>(); glPts)
 
  277     if (pts && pts->empty()) 
return;  
 
  282         auto glPts = mrpt::opengl::CPointCloudColoured::Create();
 
  283         glPts->loadFromPointsMap(pts.get());
 
  287         mrpt::math::TBoundingBoxf bb;
 
  289         const bool hasToAutoFindBB =
 
  290             (!p.
colorMode->colorMapMinCoord.has_value() ||
 
  291              !p.
colorMode->colorMapMaxCoord.has_value());
 
  293         if (hasToAutoFindBB) bb = pts->boundingBox();
 
  295         ASSERT_(p.
colorMode->recolorizeByCoordinate.has_value());
 
  297         const unsigned int coordIdx =
 
  298             static_cast<unsigned int>(p.
colorMode->recolorizeByCoordinate.value());
 
  299         ASSERT_(coordIdx < 3);
 
  301         float min = bb.min[coordIdx], max = bb.max[coordIdx];
 
  303         if (hasToAutoFindBB && p.
colorMode->autoBoundingBoxOutliersPercentile.has_value())
 
  305             const float confidenceInterval = *p.
colorMode->autoBoundingBoxOutliersPercentile;
 
  308             for (
int i = 0; i < 3; i++)
 
  309                 if (bb.max[i] == bb.min[i]) bb.max[i] = bb.min[i] + 0.1f;
 
  312             constexpr 
size_t nBins = 100;
 
  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)};
 
  319             const auto lambdaVisitPoints = [&hists](
const mrpt::math::TPoint3Df& 
pt)
 
  321                 for (
int i = 0; i < 3; i++) hists[i].
add(
pt[i]);
 
  324             for (
size_t i = 0; i < pts->size(); i++)
 
  326                 mrpt::math::TPoint3Df 
pt;
 
  327                 pts->getPoint(i, 
pt.x, 
pt.y, 
pt.z);
 
  328                 lambdaVisitPoints(
pt);
 
  332             std::vector<double> coords;
 
  333             std::vector<double> hits;
 
  335             hists[coordIdx].getHistogramNormalized(coords, hits);
 
  336             mrpt::math::confidenceIntervalsFromHistogram(
 
  337                 coords, hits, 
min, max, confidenceInterval);
 
  341         const float coordMin =
 
  344         const float coordMax =
 
  347         glPts->recolorizeByCoordinate(coordMin, coordMax, coordIdx, p.
colorMode->colorMap);
 
  354         auto glPts = mrpt::opengl::CPointCloud::Create();
 
  355         glPts->loadFromPointsMap(pts.get());
 
  358         glPts->setColor_u8(p.
color);
 
  370     const metric_map_t& otherPc, 
const std::optional<mrpt::math::TPose3D>& otherRelativePose)
 
  372     mrpt::poses::CPose3D pose;
 
  373     if (otherRelativePose.has_value()) pose = mrpt::poses::CPose3D(otherRelativePose.value());
 
  376     if (otherRelativePose.has_value())
 
  380             [&](
const mrpt::math::TLine3D& l)
 
  382                 return mrpt::math::TLine3D::FromPointAndDirector(
 
  383                     pose.composePoint(l.pBase), pose.rotateVector(l.getDirectorVector()));
 
  388         std::copy(otherPc.
lines.begin(), otherPc.
lines.end(), std::back_inserter(
lines));
 
  392     if (otherRelativePose.has_value())
 
  399                 g.centroid = pose.composePoint(l.centroid);
 
  403                 THROW_EXCEPTION(
"To-do");
 
  413     for (
const auto& layer : otherPc.
layers)
 
  415         const auto& name     = layer.first;
 
  416         const auto& otherMap = layer.second;
 
  419         if (
layers.count(name) == 0)
 
  423                 std::dynamic_pointer_cast<mrpt::maps::CMetricMap>(otherMap->duplicateGetSmartPtr());
 
  425             if (otherRelativePose.has_value())
 
  427                 if (
auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
layers[name]); pts)
 
  430                     pts->changeCoordinatesReference(pose);
 
  435                         "Merging with SE(3) transform only available for " 
  436                         "metric maps of point cloud types.");
 
  443             if (
auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
layers[name]); pts)
 
  445                 pts->insertAnotherMap(
 
  446                     std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(otherMap).
get(), pose);
 
  451                     "Merging with SE(3) transform only available for " 
  452                     "metric maps of point cloud types.");
 
  471     for (
const auto& layer : 
layers)
 
  473         if (
auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second); pts)
 
  483     using namespace std::string_literals;
 
  487     if (
id) ret += 
"id="s + std::to_string(*
id) + 
" "s;
 
  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 +
 
  500     if (
empty()) 
return {ret + 
"empty"s};
 
  504         if (!ret.empty()) ret += 
", "s;
 
  508     if (!
lines.empty()) retAppend(std::to_string(
lines.size()) + 
" lines"s);
 
  509     if (!
planes.empty()) retAppend(std::to_string(
planes.size()) + 
" planes"s);
 
  511     size_t nPts = 0, nVoxels = 0;
 
  512     bool   otherLayers = 
false;
 
  513     for (
const auto& layer : 
layers)
 
  515         ASSERT_(layer.second);
 
  516         if (
auto pts = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(layer.second); pts)
 
  520         else if (
auto vxs = std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(layer.second); vxs)
 
  522             nVoxels += vxs->grid().activeCellsCount();
 
  528     if (nPts != 0 || nVoxels != 0 || otherLayers)
 
  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);
 
  535         for (
const auto& layer : 
layers)
 
  537             ret += 
"\""s + layer.first + 
"\":"s + layer.second->asString() + 
" "s;
 
  547     auto f = mrpt::io::CFileGZOutputStream(fileName);
 
  548     if (!
f.is_open()) 
return false;
 
  550     auto arch = mrpt::serialization::archiveFrom(
f);
 
  558     auto f = mrpt::io::CFileGZInputStream(fileName);
 
  559     if (!
f.is_open()) 
return false;
 
  561     auto arch = mrpt::serialization::archiveFrom(
f);
 
  571         return shared_from_this();
 
  573     catch (
const std::bad_weak_ptr&)
 
  583     if (!ret) ret = std::make_shared<metric_map_t>(*
this);
 
  591         return shared_from_this();
 
  593     catch (
const std::bad_weak_ptr&)
 
  603     if (!ret) ret = std::make_shared<metric_map_t>(*
this);
 
  609     auto it = 
layers.find(name);
 
  610     if (it == 
layers.end()) THROW_EXCEPTION_FMT(
"Layer '%s' does not exist.", name.c_str());
 
  612     const auto& ptr = it->second;
 
  615     auto ret = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(ptr);
 
  618             "Layer '%s' is not a point cloud (actual class:'%s').", name.c_str(),
 
  619             ptr->GetRuntimeClass()->className);
 
  626     if (
auto ptsMap = 
dynamic_cast<const mrpt::maps::CPointsMap*
>(&map); ptsMap)
 
  630     if (
auto voxelMap = 
dynamic_cast<const mrpt::maps::CVoxelMap*
>(&map); voxelMap)
 
  632         return voxelMap->getOccupiedVoxels().get();
 
  634     if (
auto voxelRGBMap = 
dynamic_cast<const mrpt::maps::CVoxelMapRGB*
>(&map); voxelRGBMap)
 
  636         return voxelRGBMap->getOccupiedVoxels().get();
 
  643     if (
auto ptsMap = 
dynamic_cast<mrpt::maps::CPointsMap*
>(&map); ptsMap)
 
  647     if (
auto voxelMap = 
dynamic_cast<mrpt::maps::CVoxelMap*
>(&map); voxelMap)
 
  649         return voxelMap->getOccupiedVoxels().get();
 
  651     if (
auto voxelRGBMap = 
dynamic_cast<mrpt::maps::CVoxelMapRGB*
>(&map); voxelRGBMap)
 
  653         return voxelRGBMap->getOccupiedVoxels().get();
 
  659     const mrpt::maps::CMetricMap& map, 
bool throwIfNotImplemented)
 
  661     const auto* ptr = 
dynamic_cast<const mrpt::maps::NearestNeighborsCapable*
>(&map);
 
  664     if (!throwIfNotImplemented) 
return nullptr;
 
  667         "The map of type '%s' does not implement the expected interface " 
  668         "mrpt::maps::NearestNeighborsCapable",
 
  669         map.GetRuntimeClass()->className);
 
  673     const mrpt::maps::CMetricMap& map, 
bool throwIfNotImplemented)
 
  678     if (!throwIfNotImplemented) 
return nullptr;
 
  681         "The map of type '%s' does not implement the expected interface " 
  682         "mp2p_icp::NearestPlaneCapable",
 
  683         map.GetRuntimeClass()->className);
 
  690     mrpt::serialization::CArchive& in, std::optional<metric_map_t::Georeferencing>& g)
 
  693     in >> georef_stream_signature;
 
  695     const uint8_t version = in.ReadAs<uint8_t>();
 
  699             if (in.ReadAs<
bool>())
 
  701                 auto& gg = g.emplace();
 
  702                 in >> gg.geo_coord.lat.decimal_value >> gg.geo_coord.lon.decimal_value >>
 
  704                 in >> gg.T_enu_to_map;
 
  708             MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
 
  715     mrpt::serialization::CArchive& 
out, 
const std::optional<metric_map_t::Georeferencing>& g)
 
  718     constexpr uint8_t serial_version = 0;
 
  719     out.WriteAs<uint8_t>(serial_version);
 
  721     out.WriteAs<
bool>(g.has_value());
 
  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;
 
  732     const mrpt::containers::yaml& yaml_data)
 
  734     ASSERT_(yaml_data.isMap());
 
  735     ASSERT_(yaml_data.has(
"type"));
 
  736     ASSERT_(yaml_data.has(
"defined"));
 
  739     const bool defined = yaml_data[
"defined"].as<
bool>();
 
  745     std::optional<metric_map_t::Georeferencing> georef;
 
  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>();
 
  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>());
 
  757     yaml_data[
"T_enu_to_map"][
"cov"].toMatrix(g.T_enu_to_map.cov);
 
  762 mrpt::containers::yaml 
mp2p_icp::ToYAML(
const std::optional<metric_map_t::Georeferencing>& gref)
 
  764     mrpt::containers::yaml data = mrpt::containers::yaml::Map();
 
  767     data[
"defined"] = gref.has_value();
 
  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;
 
  776             data[
"geo_coord"] = gcoord;
 
  779         mrpt::containers::yaml pose_mean = mrpt::containers::yaml::Map();
 
  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();
 
  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;