QualityEvaluator_Voxels.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  * ------------------------------------------------------------------------- */
14 #include <mrpt/maps/CVoxelMap.h>
15 
17 
18 using namespace mp2p_icp;
19 
21 {
22  mrpt::system::COutputLogger::setLoggerName("QualityEvaluator_Voxels");
23 }
24 
26  const mrpt::containers::yaml& params)
27 {
28  MCP_LOAD_REQ(params, voxel_layer_name);
29  MCP_LOAD_OPT(params, dist2quality_scale);
30 }
31 
32 namespace
33 {
34 double loss(double x, double y)
35 {
36  /*
37 
38  D=[0 0 +1;0 0.5 0; 0 1 -10;...
39  0.5 0 0; 0.5 0.5 0; 0.5 1 0;...
40  1 0 -10; 1 0.5 0; 1 1 +1];
41  x=D(:,1); y=D(:,2); z=D(:,3);
42 
43  sf = fit([x, y],z,'poly22')
44  plot(sf,[x,y],z)
45 
46  */
47 
48  // return 1.0 - 2 * x - 2 * y + 4 * x * y;
49  return 1.5 + x + y - 12 * x * x + 22 * x * y - 12 * y * y;
50 }
51 } // namespace
52 
54  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
55  const mrpt::poses::CPose3D& localPose, [[maybe_unused]] const Pairings& pairingsFromICP) const
56 {
57  // Take both voxel maps from each map:
58  // ------------------------------------
59  if (pcGlobal.layers.count(voxel_layer_name) == 0)
60  THROW_EXCEPTION_FMT(
61  "Input global map was expected to contain a layer named '%s'",
62  voxel_layer_name.c_str());
63 
64  if (pcLocal.layers.count(voxel_layer_name) == 0)
65  THROW_EXCEPTION_FMT(
66  "Input local map was expected to contain a layer named '%s'", voxel_layer_name.c_str());
67 
68  const mrpt::maps::CVoxelMap::Ptr globalVoxels =
69  std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(pcGlobal.layers.at(voxel_layer_name));
70  if (!globalVoxels)
71  THROW_EXCEPTION_FMT(
72  "Input global map was expected to contain a layer named '%s' of "
73  "type 'CVoxelMap'",
74  voxel_layer_name.c_str());
75 
76  const mrpt::maps::CVoxelMap::Ptr localVoxels =
77  std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(pcLocal.layers.at(voxel_layer_name));
78 
79  if (!localVoxels)
80  THROW_EXCEPTION_FMT(
81  "Input local map was expected to contain a layer named '%s' of "
82  "type 'CVoxelMap'",
83  voxel_layer_name.c_str());
84 
85  // Compare them:
86  // ----------------------------------
87 
88  // TODO(jlbc): Contribute upstream to Bonxai a "forEachCell() const":
89 
90  // get Bonxai grids:
91  auto& g = const_cast<Bonxai::VoxelGrid<mrpt::maps::VoxelNodeOccupancy>&>(globalVoxels->grid());
92  auto& l = const_cast<Bonxai::VoxelGrid<mrpt::maps::VoxelNodeOccupancy>&>(localVoxels->grid());
93 
94  auto gAccessor = g.createAccessor();
95  auto lAccessor = l.createAccessor();
96 
97  // Kullback-Leibler distance:
98  double dist = 0;
99  size_t dist_cells = 0;
100 
101  auto lmbdPerLocalVoxel =
102  [&](mrpt::maps::CVoxelMap::voxel_node_t& data, const Bonxai::CoordT& coord)
103  {
104  // get the corresponding cell in the global map:
105  const auto ptLocal = Bonxai::CoordToPos(coord, l.resolution);
106  const auto ptGlobal = localPose.composePoint({ptLocal.x, ptLocal.y, ptLocal.z});
107 
108  auto* cell = gAccessor.value(
109  Bonxai::PosToCoord({ptGlobal.x, ptGlobal.y, ptGlobal.z}, g.inv_resolution));
110  if (!cell) return; // cell not observed in global grid
111 
112  const float localOcc = localVoxels->l2p(data.occupancy);
113  const float globalOcc = globalVoxels->l2p(cell->occupancy);
114 
115  // barely observed cells?
116  if (std::abs(globalOcc - 0.5f) < 0.01f || std::abs(localOcc - 0.5f) < 0.01f) return;
117 
118  const double d = loss(localOcc, globalOcc);
119  dist += d;
120  dist_cells++;
121  }; // end lambda for each voxel
122 
123  // run it:
124  l.forEachCell(lmbdPerLocalVoxel);
125 
126  auto lmbdPerGlobalVoxel =
127  [&](mrpt::maps::CVoxelMap::voxel_node_t& data, const Bonxai::CoordT& coord)
128  {
129  // get the corresponding cell in the local map:
130  const auto ptGlobal = Bonxai::CoordToPos(coord, l.resolution);
131  const auto ptLocal = (-localPose).composePoint({ptGlobal.x, ptGlobal.y, ptGlobal.z});
132 
133  auto* cell = lAccessor.value(
134  Bonxai::PosToCoord({ptLocal.x, ptLocal.y, ptLocal.z}, l.inv_resolution));
135  if (!cell) return; // cell not observed in global grid
136 
137  const float localOcc = localVoxels->l2p(cell->occupancy);
138  const float globalOcc = globalVoxels->l2p(data.occupancy);
139 
140  // barely observed cells?
141  if (std::abs(globalOcc - 0.5f) < 0.01f || std::abs(localOcc - 0.5f) < 0.01f) return;
142 
143  const double d = loss(localOcc, globalOcc);
144  dist += d;
145  dist_cells++;
146  }; // end lambda for each voxel
147 
148  g.forEachCell(lmbdPerGlobalVoxel);
149 
150  // const auto nTotalLocalCells = l.activeCellsCount();
151  Result r;
152  r.quality = 0;
153  if (dist_cells)
154  {
155  dist /= dist_cells;
156  r.quality = 1.0 / (1.0 + std::exp(-dist2quality_scale * dist));
157  }
158  MRPT_LOG_DEBUG_STREAM(
159  "dist: " << dist << " dist_cells: " << dist_cells << " quality: " << r.quality);
160 
161  return r;
162 }
mp2p_icp
Definition: covariance.h:17
mp2p_icp::QualityEvaluator::Result
Definition: QualityEvaluator.h:39
mp2p_icp::QualityEvaluator_Voxels
Definition: QualityEvaluator_Voxels.h:22
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::Pairings
Definition: Pairings.h:76
QualityEvaluator_Voxels.h
Matching quality evaluator: comparison via voxel occupancy.
mp2p_icp::QualityEvaluator_Voxels::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: QualityEvaluator_Voxels.cpp:25
test.x
x
Definition: test.py:4
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::QualityEvaluator_Voxels::voxel_layer_name
std::string voxel_layer_name
Definition: QualityEvaluator_Voxels.h:36
mp2p_icp::QualityEvaluator::Result::quality
double quality
The resulting quality measure, in the range [0,1].
Definition: QualityEvaluator.h:42
d
d
mp2p_icp::QualityEvaluator_Voxels::dist2quality_scale
double dist2quality_scale
Definition: QualityEvaluator_Voxels.h:37
mp2p_icp::QualityEvaluator_Voxels::evaluate
Result evaluate(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &pairingsFromICP) const override
Definition: QualityEvaluator_Voxels.cpp:53
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:82
mp2p_icp::QualityEvaluator_Voxels::QualityEvaluator_Voxels
QualityEvaluator_Voxels()
Definition: QualityEvaluator_Voxels.cpp:20
mp2p_icp::QualityEvaluator
Definition: QualityEvaluator.h:28


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