FilterDecimateVoxels.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  * ------------------------------------------------------------------------- */
16 #include <mrpt/containers/yaml.h>
17 #include <mrpt/math/ops_containers.h> // dotProduct
18 #include <mrpt/random/RandomGenerators.h>
19 
20 //
21 #include <mrpt/maps/CPointsMapXYZI.h>
22 #include <mrpt/maps/CPointsMapXYZIRT.h>
23 
25  FilterDecimateVoxels, mp2p_icp_filters::FilterBase, mp2p_icp_filters)
26 
27 using namespace mp2p_icp_filters;
28 
30  const mrpt::containers::yaml& c, FilterDecimateVoxels& parent)
31 {
32  ASSERTMSG_(
33  c.has("input_pointcloud_layer"),
34  "YAML configuration must have an entry `input_pointcloud_layer` with a "
35  "scalar or sequence.");
36 
37  input_pointcloud_layer.clear();
38 
39  auto cfgIn = c["input_pointcloud_layer"];
40  if (cfgIn.isScalar())
41  {
42  input_pointcloud_layer.push_back(cfgIn.as<std::string>());
43  }
44  else
45  {
46  ASSERTMSG_(
47  cfgIn.isSequence(),
48  "YAML configuration must have an entry `input_pointcloud_layer` "
49  "with a scalar or sequence.");
50 
51  for (const auto& s : cfgIn.asSequence())
52  input_pointcloud_layer.push_back(s.as<std::string>());
53  }
54  ASSERT_(!input_pointcloud_layer.empty());
55 
56  MCP_LOAD_OPT(c, error_on_missing_input_layer);
57  MCP_LOAD_REQ(c, decimate_method);
58 
59  MCP_LOAD_REQ(c, output_pointcloud_layer);
60  MCP_LOAD_OPT(c, minimum_input_points_to_filter);
61 
63 
64  if (c.has("flatten_to")) flatten_to = c["flatten_to"].as<double>();
65 }
66 
68 {
69  mrpt::system::COutputLogger::setLoggerName("FilterDecimateVoxels");
70 }
71 
72 void FilterDecimateVoxels::initialize(const mrpt::containers::yaml& c)
73 {
74  MRPT_START
75 
76  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
77  params_.load_from_yaml(c, *this);
78 
79  filter_grid_single_.reset();
80  filter_grid_.reset();
81 
82  if (useSingleGrid())
83  { // Create:
84  filter_grid_single_.emplace();
85  }
86  else
87  { // Create:
88  filter_grid_.emplace();
89  }
90 
91  MRPT_END
92 }
93 
95 {
96  MRPT_START
97 
99 
100  // In:
101  std::vector<mrpt::maps::CPointsMap*> pcPtrs;
102  size_t reserveSize = 0;
103  for (const auto& inputLayer : params_.input_pointcloud_layer)
104  {
105  if (auto itLy = inOut.layers.find(inputLayer);
106  itLy != inOut.layers.end())
107  {
108  auto pcPtr = mp2p_icp::MapToPointsMap(*itLy->second);
109  if (!pcPtr)
110  THROW_EXCEPTION_FMT(
111  "Layer '%s' must be of point cloud type.",
112  inputLayer.c_str());
113 
114  pcPtrs.push_back(pcPtr);
115  reserveSize += pcPtr->size() / 10; // heuristic
116  }
117  else
118  {
119  // Input layer doesn't exist:
121  {
122  THROW_EXCEPTION_FMT(
123  "Input layer '%s' not found on input map.",
124  inputLayer.c_str());
125  }
126  else
127  {
128  // Silently return with an unmodified output layer "outPc"
129  continue;
130  }
131  }
132  }
133 
134  ASSERT_(!pcPtrs.empty());
135 
136  // Out:
137  ASSERT_(!params_.output_pointcloud_layer.empty());
138 
139  // Create if new: Append to existing layer, if already existed.
140  mrpt::maps::CPointsMap::Ptr outPc = GetOrCreatePointLayer(
142  /*do not allow empty*/
143  false,
144  /* create cloud of the same type */
145  pcPtrs.at(0)->GetRuntimeClass()->className);
146 
147  outPc->reserve(outPc->size() + reserveSize);
148 
149  // Skip filtering for layers with less than
150  // "minimum_input_points_to_filter":
152  {
153  std::vector<size_t> idxsToRemove;
154  for (size_t mapIdx = 0; mapIdx < pcPtrs.size(); mapIdx++)
155  {
156  if (pcPtrs[mapIdx]->size() > params_.minimum_input_points_to_filter)
157  { // just proceed as standard with this large map:
158  continue;
159  }
160  // Remove this one from the list of maps to filter,
161  // and just add all points:
162  idxsToRemove.push_back(mapIdx);
163 
164  const auto& xs = pcPtrs[mapIdx]->getPointsBufferRef_x();
165  const auto& ys = pcPtrs[mapIdx]->getPointsBufferRef_y();
166 
167  for (size_t i = 0; i < xs.size(); i++)
168  {
169  if (params_.flatten_to.has_value())
170  {
171  outPc->insertPointFast(xs[i], ys[i], *params_.flatten_to);
172  }
173  else
174  outPc->insertPointFrom(*pcPtrs[mapIdx], i);
175  }
176  }
177  for (auto it = idxsToRemove.rbegin(); it != idxsToRemove.rend(); ++it)
178  pcPtrs.erase(pcPtrs.begin() + *it);
179 
180  } // end handle special case minimum_input_points_to_filter
181 
182  // Do filter:
183  size_t nonEmptyVoxels = 0;
184 
185  if (useSingleGrid())
186  {
187  ASSERTMSG_(
188  filter_grid_single_.has_value(),
189  "Has you called initialize() after updating/loading parameters?");
190 
191  auto& grid = filter_grid_single_.value();
192  grid.setResolution(params_.voxel_filter_resolution);
193  grid.clear();
194 
195  // 1st) go thru all the input layers:
196  for (const auto& pcPtr : pcPtrs)
197  {
198  const auto& pc = *pcPtr;
199  grid.processPointCloud(pc);
200 
201  const bool sanityPassed = mp2p_icp::pointcloud_sanity_check(pc);
202  ASSERT_(sanityPassed);
203  }
204 
205  // 2nd) collect grid results:
206  std::set<
209  flattenUsedBins;
210 
211  grid.visit_voxels(
214  {
215  if (!vxl.pointIdx.has_value()) return;
216 
217  nonEmptyVoxels++;
218 
219  if (params_.flatten_to.has_value())
220  {
221  const PointCloudToVoxelGridSingle::indices_t flattenIdx = {
222  idx.cx_, idx.cy_, 0};
223 
224  // first time?
225  if (flattenUsedBins.count(flattenIdx) != 0)
226  return; // nope. Skip this point.
227 
228  // First time we see this (x,y) cell:
229  flattenUsedBins.insert(flattenIdx);
230 
231  outPc->insertPointFast(
232  vxl.point->x, vxl.point->y, *params_.flatten_to);
233  }
234  else
235  {
236  outPc->insertPointFrom(*vxl.source.value(), *vxl.pointIdx);
237  }
238  });
239  }
240  else
241  {
242  ASSERTMSG_(
243  pcPtrs.size() == 1,
244  "Only one input layer allowed when requiring the non-single "
245  "decimating grid");
246 
247  const auto& pc = *pcPtrs.at(0);
248 
249  ASSERTMSG_(
250  filter_grid_.has_value(),
251  "Has you called initialize() after updating/loading parameters?");
252 
253  auto& grid = filter_grid_.value();
254  grid.setResolution(params_.voxel_filter_resolution);
255  grid.clear();
256 
257  grid.processPointCloud(pc);
258 
259  const auto& xs = pc.getPointsBufferRef_x();
260  const auto& ys = pc.getPointsBufferRef_y();
261  const auto& zs = pc.getPointsBufferRef_z();
262 
263  auto rng = mrpt::random::CRandomGenerator();
264  // TODO?: rng.randomize(seed);
265 
266  std::set<
269  flattenUsedBins;
270 
271  grid.visit_voxels(
272  [&](const PointCloudToVoxelGrid::indices_t& idx,
274  {
275  if (vxl.indices.empty()) return;
276 
277  nonEmptyVoxels++;
278  std::optional<mrpt::math::TPoint3Df> insertPt;
279  size_t insertPtIdx; // valid only if insertPt is empty
280 
283  {
284  // Analyze the voxel contents:
285  auto mean = mrpt::math::TPoint3Df(0, 0, 0);
286  const float inv_n = (1.0f / vxl.indices.size());
287  for (size_t i = 0; i < vxl.indices.size(); i++)
288  {
289  const auto pt_idx = vxl.indices[i];
290  mean.x += xs[pt_idx];
291  mean.y += ys[pt_idx];
292  mean.z += zs[pt_idx];
293  }
294  mean *= inv_n;
295 
296  if (params_.decimate_method ==
298  {
299  std::optional<float> minSqrErr;
300  std::optional<size_t> bestIdx;
301 
302  for (size_t i = 0; i < vxl.indices.size(); i++)
303  {
304  const auto pt_idx = vxl.indices[i];
305  const float sqrErr =
306  mrpt::square(xs[pt_idx] - mean.x) +
307  mrpt::square(ys[pt_idx] - mean.y) +
308  mrpt::square(zs[pt_idx] - mean.z);
309 
310  if (!minSqrErr.has_value() || sqrErr < *minSqrErr)
311  {
312  minSqrErr = sqrErr;
313  bestIdx = pt_idx;
314  }
315  }
316  // Insert the closest to the mean:
317  insertPtIdx = *bestIdx;
318  }
319  else
320  {
321  // Insert the mean:
322  insertPt = {mean.x, mean.y, mean.z};
323  }
324  }
325  else
326  {
327  // Insert a randomly-picked point:
328  const auto idxInVoxel =
330  ? (rng.drawUniform64bit() % vxl.indices.size())
331  : 0UL;
332 
333  const auto pt_idx = vxl.indices.at(idxInVoxel);
334  insertPtIdx = pt_idx;
335  }
336 
337  // insert it, if passed the flatten filter:
338  if (params_.flatten_to.has_value())
339  {
340  const PointCloudToVoxelGrid::indices_t flattenIdx = {
341  idx.cx_, idx.cy_, 0};
342 
343  // first time?
344  if (flattenUsedBins.count(flattenIdx) != 0)
345  return; // nope. Skip this point.
346 
347  // First time we see this (x,y) cell:
348  flattenUsedBins.insert(flattenIdx);
349 
350  if (!insertPt)
351  insertPt.emplace(
352  xs[insertPtIdx], ys[insertPtIdx], zs[insertPtIdx]);
353  outPc->insertPointFast(
354  insertPt->x, insertPt->y, *params_.flatten_to);
355  }
356  else
357  {
358  if (insertPt)
359  outPc->insertPointFast(
360  insertPt->x, insertPt->y, insertPt->z);
361  else { outPc->insertPointFrom(pc, insertPtIdx); }
362  }
363  });
364 
365  } // end: non-single grid
366 
367  outPc->mark_as_modified();
368 
369  MRPT_LOG_DEBUG_STREAM(
370  "Voxel count=" << nonEmptyVoxels
371  << ", output_layer=" << params_.output_pointcloud_layer
372  << " type=" << outPc->GetRuntimeClass()->className
373  << " useSingleGrid="
374  << (useSingleGrid() ? "Yes" : "No"));
375 
376  MRPT_END
377 }
mp2p_icp_filters::FilterDecimateVoxels::Parameters::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDecimateVoxels.h:94
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:138
mp2p_icp_filters::FilterDecimateVoxels::Parameters::decimate_method
DecimateMethod decimate_method
Definition: FilterDecimateVoxels.h:109
mp2p_icp_filters::FilterDecimateVoxels::Parameters::flatten_to
std::optional< double > flatten_to
See description on top of this page.
Definition: FilterDecimateVoxels.h:105
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t::point
std::optional< mrpt::math::TPoint3Df > point
Definition: PointCloudToVoxelGridSingle.h:46
s
XmlRpcServer s
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::cx_
int32_t cx_
Definition: PointCloudToVoxelGrid.h:69
mp2p_icp_filters::FilterDecimateVoxels::useSingleGrid
bool useSingleGrid() const
Definition: FilterDecimateVoxels.h:119
mp2p_icp_filters::DecimateMethod::RandomPoint
@ RandomPoint
mp2p_icp_filters::FilterDecimateVoxels::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDecimateVoxels.cpp:94
mp2p_icp_filters::DecimateMethod::VoxelAverage
@ VoxelAverage
mp2p_icp::pointcloud_sanity_check
bool pointcloud_sanity_check(const mrpt::maps::CPointsMap &pc, bool printWarnings=true)
Definition: pointcloud_sanity_check.cpp:19
pointcloud_sanity_check.h
Checks for consistent length of field vectors.
mp2p_icp_filters::PointCloudToVoxelGrid::IndicesHash
Definition: PointCloudToVoxelGrid.h:84
testing::internal::string
::std::string string
Definition: gtest.h:1979
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxels, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t
Definition: PointCloudToVoxelGridSingle.h:44
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t::indices
std::vector< std::size_t > indices
Definition: PointCloudToVoxelGrid.h:59
mp2p_icp_filters::DecimateMethod::ClosestToAverage
@ ClosestToAverage
mp2p_icp_filters::FilterDecimateVoxels::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterDecimateVoxels.cpp:72
mp2p_icp_filters::PointCloudToVoxelGridSingle::IndicesHash
Definition: PointCloudToVoxelGridSingle.h:76
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t
Definition: PointCloudToVoxelGrid.h:62
DECLARE_PARAMETER_IN_REQ
#define DECLARE_PARAMETER_IN_REQ(__yaml, __variable, __object)
Definition: Parameterizable.h:167
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:648
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterDecimateVoxels
Definition: FilterDecimateVoxels.h:66
mp2p_icp_filters::GetOrCreatePointLayer
mrpt::maps::CPointsMap::Ptr GetOrCreatePointLayer(mp2p_icp::metric_map_t &m, const std::string &layerName, bool allowEmptyName=true, const std::string &classForLayerCreation="mrpt::maps::CSimplePointsMap")
Definition: GetOrCreatePointLayer.cpp:15
mp2p_icp_filters::FilterDecimateVoxels::filter_grid_
std::optional< PointCloudToVoxelGrid > filter_grid_
Definition: FilterDecimateVoxels.h:116
mp2p_icp_filters::FilterDecimateVoxels::Parameters::voxel_filter_resolution
double voxel_filter_resolution
Definition: FilterDecimateVoxels.h:97
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t::pointIdx
std::optional< size_t > pointIdx
Definition: PointCloudToVoxelGridSingle.h:47
mp2p_icp_filters::FilterDecimateVoxels::FilterDecimateVoxels
FilterDecimateVoxels()
Definition: FilterDecimateVoxels.cpp:67
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t
Definition: PointCloudToVoxelGrid.h:57
mp2p_icp_filters::FilterDecimateVoxels::Parameters::error_on_missing_input_layer
bool error_on_missing_input_layer
Definition: FilterDecimateVoxels.h:91
mp2p_icp_filters::FilterDecimateVoxels::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterDecimateVoxels &parent)
Definition: FilterDecimateVoxels.cpp:29
mp2p_icp_filters::FilterDecimateVoxels::params_
Parameters params_
Definition: FilterDecimateVoxels.h:113
mp2p_icp_filters::FilterDecimateVoxels::filter_grid_single_
std::optional< PointCloudToVoxelGridSingle > filter_grid_single_
Definition: FilterDecimateVoxels.h:117
GetOrCreatePointLayer.h
Auxiliary function GetOrCreatePointLayer.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
mp2p_icp_filters::FilterDecimateVoxels::Parameters::minimum_input_points_to_filter
uint32_t minimum_input_points_to_filter
Definition: FilterDecimateVoxels.h:102
mp2p_icp_filters::PointCloudToVoxelGridSingle::indices_t
Definition: PointCloudToVoxelGridSingle.h:54
mp2p_icp_filters::FilterDecimateVoxels::Parameters::input_pointcloud_layer
std::vector< std::string > input_pointcloud_layer
Definition: FilterDecimateVoxels.h:85
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::cy_
int32_t cy_
Definition: PointCloudToVoxelGrid.h:69
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t::source
std::optional< const mrpt::maps::CPointsMap * > source
Definition: PointCloudToVoxelGridSingle.h:48
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
FilterDecimateVoxels.h
Builds a new layer with a decimated version of an input layer.


mp2p_icp
Author(s):
autogenerated on Thu Oct 17 2024 02:45:33