FilterDecimateVoxelsQuadratic.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  * ------------------------------------------------------------------------- */
15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/maps/CSimplePointsMap.h>
17 #include <mrpt/math/ops_containers.h> // dotProduct
18 #include <mrpt/random/RandomGenerators.h>
19 
21  FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters)
22 
23 using namespace mp2p_icp_filters;
24 
25 void FilterDecimateVoxelsQuadratic::Parameters::load_from_yaml(const mrpt::containers::yaml& c)
26 {
27  MCP_LOAD_OPT(c, input_pointcloud_layer);
28  MCP_LOAD_OPT(c, error_on_missing_input_layer);
29  MCP_LOAD_OPT(c, use_random_point_within_voxel);
30 
31  MCP_LOAD_REQ(c, output_pointcloud_layer);
32 
33  MCP_LOAD_REQ(c, voxel_filter_resolution);
34  MCP_LOAD_REQ(c, quadratic_reference_radius);
35  MCP_LOAD_REQ(c, use_voxel_average);
36  MCP_LOAD_REQ(c, use_closest_to_voxel_average);
37 }
38 
40 
41 void FilterDecimateVoxelsQuadratic::initialize(const mrpt::containers::yaml& c)
42 {
43  MRPT_START
44 
45  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
47 
50 
51  MRPT_END
52 }
53 
55 {
56  MRPT_START
57 
58  // Out:
59  ASSERT_(!params_.output_pointcloud_layer.empty());
60 
61  // Create if new: Append to existing layer, if already existed.
62  mrpt::maps::CPointsMap::Ptr outPc =
64 
65  // In:
66  mrpt::maps::CPointsMap* pcPtr = nullptr;
67  if (auto itLy = inOut.layers.find(params_.input_pointcloud_layer); itLy != inOut.layers.end())
68  {
69  pcPtr = mp2p_icp::MapToPointsMap(*itLy->second);
70  if (!pcPtr)
71  THROW_EXCEPTION_FMT(
72  "Layer '%s' must be of point cloud type.", params_.input_pointcloud_layer.c_str());
73  }
74  else
75  {
76  // Input layer doesn't exist:
78  {
79  THROW_EXCEPTION_FMT(
80  "Input layer '%s' not found on input map.", params_.input_pointcloud_layer.c_str());
81  }
82  else
83  {
84  // Silently return with an unmodified output layer "outPc"
85  return;
86  }
87  }
88 
89  // Non-linear transform input cloud:
90  const auto& rawPc = *pcPtr;
91 
92  mrpt::maps::CSimplePointsMap pc;
93  pc.reserve(rawPc.size());
94 
95  const auto& xs = rawPc.getPointsBufferRef_x();
96  const auto& ys = rawPc.getPointsBufferRef_y();
97  const auto& zs = rawPc.getPointsBufferRef_z();
98  for (size_t i = 0; i < xs.size(); i++)
99  {
100  pc.insertPointFast(real2grid(xs[i]), real2grid(ys[i]), real2grid(zs[i]));
101  }
102  pc.mark_as_modified();
103 
104  // Do filter:
105  outPc->reserve(outPc->size() + pc.size() / 10);
106 
109 
110  // const auto& xs = pc.getPointsBufferRef_x();
111  // const auto& ys = pc.getPointsBufferRef_y();
112  // const auto& zs = pc.getPointsBufferRef_z();
113 
114  auto rng = mrpt::random::CRandomGenerator();
115  // TODO?: rng.randomize(seed);
116 
117  // Inverse nonlinear transformation:
118  auto lambdaInsertPt = [&outPc](float x, float y, float z) { outPc->insertPointFast(x, y, z); };
119 
120  size_t nonEmptyVoxels = 0;
121 
124  {
125  if (vxl.indices.empty()) return;
126 
127  nonEmptyVoxels++;
128 
130  {
131  // Analyze the voxel contents:
132  auto mean = mrpt::math::TPoint3Df(0, 0, 0);
133  const float inv_n = (1.0f / vxl.indices.size());
134  for (size_t i = 0; i < vxl.indices.size(); i++)
135  {
136  const auto pt_idx = vxl.indices[i];
137  mean.x += xs[pt_idx];
138  mean.y += ys[pt_idx];
139  mean.z += zs[pt_idx];
140  }
141  mean *= inv_n;
142 
144  {
145  std::optional<float> minSqrErr;
146  std::optional<size_t> bestIdx;
147 
148  for (size_t i = 0; i < vxl.indices.size(); i++)
149  {
150  const auto pt_idx = vxl.indices[i];
151  const float sqrErr = mrpt::square(xs[pt_idx] - mean.x) +
152  mrpt::square(ys[pt_idx] - mean.y) +
153  mrpt::square(zs[pt_idx] - mean.z);
154 
155  if (!minSqrErr.has_value() || sqrErr < *minSqrErr)
156  {
157  minSqrErr = sqrErr;
158  bestIdx = pt_idx;
159  }
160  }
161  // Insert the closest to the mean:
162  lambdaInsertPt(xs[*bestIdx], ys[*bestIdx], zs[*bestIdx]);
163  }
164  else
165  {
166  // Insert the mean:
167  lambdaInsertPt(mean.x, mean.y, mean.z);
168  }
169  }
170  else
171  {
172  // Insert a randomly-picked point:
173  const auto idxInVoxel = params_.use_random_point_within_voxel
174  ? (rng.drawUniform64bit() % vxl.indices.size())
175  : 0UL;
176 
177  const auto pt_idx = vxl.indices.at(idxInVoxel);
178  lambdaInsertPt(xs[pt_idx], ys[pt_idx], zs[pt_idx]);
179  }
180  });
181 
182  outPc->mark_as_modified();
183 
184  MRPT_LOG_DEBUG_STREAM("Voxel counts: total=" << nonEmptyVoxels);
185 
186  MRPT_END
187 }
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::error_on_missing_input_layer
bool error_on_missing_input_layer
Definition: FilterDecimateVoxelsQuadratic.h:59
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::voxel_filter_resolution
double voxel_filter_resolution
Definition: FilterDecimateVoxelsQuadratic.h:65
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::filter_grid_
PointCloudToVoxelGrid filter_grid_
Definition: FilterDecimateVoxelsQuadratic.h:102
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterDecimateVoxelsQuadratic.h:54
FilterDecimateVoxelsQuadratic.h
Builds a new layer with a decimated version of an input layer.
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::quadratic_reference_radius
double quadratic_reference_radius
Definition: FilterDecimateVoxelsQuadratic.h:68
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::real2grid
float real2grid(float x) const
Definition: FilterDecimateVoxelsQuadratic.h:86
test.x
x
Definition: test.py:4
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::quadratic_reference_radius_inv_
float quadratic_reference_radius_inv_
Definition: FilterDecimateVoxelsQuadratic.h:104
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::use_closest_to_voxel_average
bool use_closest_to_voxel_average
Definition: FilterDecimateVoxelsQuadratic.h:76
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDecimateVoxelsQuadratic.cpp:54
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t::indices
std::vector< std::size_t > indices
Definition: PointCloudToVoxelGrid.h:59
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t
Definition: PointCloudToVoxelGrid.h:62
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:624
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
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::FilterDecimateVoxelsQuadratic::Parameters::use_random_point_within_voxel
bool use_random_point_within_voxel
Definition: FilterDecimateVoxelsQuadratic.h:80
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t
Definition: PointCloudToVoxelGrid.h:57
mp2p_icp_filters::PointCloudToVoxelGrid::clear
void clear()
Definition: PointCloudToVoxelGrid.cpp:75
mp2p_icp_filters::PointCloudToVoxelGrid::processPointCloud
void processPointCloud(const mrpt::maps::CPointsMap &p)
Definition: PointCloudToVoxelGrid.cpp:37
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c)
Definition: FilterDecimateVoxelsQuadratic.cpp:25
mp2p_icp_filters::PointCloudToVoxelGrid::setResolution
void setResolution(const float voxel_size)
Definition: PointCloudToVoxelGrid.cpp:27
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDecimateVoxelsQuadratic.h:62
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterDecimateVoxelsQuadratic.cpp:41
GetOrCreatePointLayer.h
Auxiliary function GetOrCreatePointLayer.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
mp2p_icp_filters::PointCloudToVoxelGrid::visit_voxels
void visit_voxels(const std::function< void(const indices_t idx, const voxel_t &vxl)> &userCode) const
Definition: PointCloudToVoxelGrid.cpp:81
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::params_
Parameters params_
Definition: FilterDecimateVoxelsQuadratic.h:84
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::Parameters::use_voxel_average
bool use_voxel_average
Definition: FilterDecimateVoxelsQuadratic.h:72
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:82
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterDecimateVoxelsQuadratic::FilterDecimateVoxelsQuadratic
FilterDecimateVoxelsQuadratic()


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