FilterEdgesPlanes.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/containers/yaml.h>
15 #include <mrpt/maps/CSimplePointsMap.h>
16 #include <mrpt/math/ops_containers.h> // dotProduct
17 
19 
20 using namespace mp2p_icp_filters;
21 
22 void FilterEdgesPlanes::Parameters::load_from_yaml(const mrpt::containers::yaml& c)
23 {
24  MCP_LOAD_OPT(c, input_pointcloud_layer);
25 
26  MCP_LOAD_REQ(c, voxel_filter_resolution);
27  MCP_LOAD_REQ(c, voxel_filter_decimation);
28  MCP_LOAD_REQ(c, full_pointcloud_decimation);
29  MCP_LOAD_REQ(c, voxel_filter_max_e2_e0);
30  MCP_LOAD_REQ(c, voxel_filter_max_e1_e0);
31  MCP_LOAD_REQ(c, voxel_filter_min_e2_e0);
32  MCP_LOAD_REQ(c, voxel_filter_min_e1_e0);
33  MCP_LOAD_OPT(c, voxel_filter_min_e1);
34 }
35 
37 
38 void FilterEdgesPlanes::initialize(const mrpt::containers::yaml& c)
39 {
40  MRPT_START
41 
42  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
44 
46 
47  MRPT_END
48 }
49 
51 {
52  MRPT_START
53 
54  // In:
55  const auto& pcPtr = inOut.point_layer(params_.input_pointcloud_layer);
56  ASSERTMSG_(
57  pcPtr,
58  mrpt::format(
59  "Input point cloud layer '%s' was not found.", params_.input_pointcloud_layer.c_str()));
60 
61  const auto& pc = *pcPtr;
62 
63  // Out:
64  auto pc_edges = mrpt::maps::CSimplePointsMap::Create();
65  auto pc_planes = mrpt::maps::CSimplePointsMap::Create();
66  auto pc_full_decim = mrpt::maps::CSimplePointsMap::Create();
67  auto pc_plane_centroids = mrpt::maps::CSimplePointsMap::Create();
68 
69  inOut.layers["edge_points"] = pc_edges;
70  inOut.layers["plane_points"] = pc_planes;
71  inOut.layers["full_decim"] = pc_full_decim;
72  inOut.layers["plane_centroids"] = pc_plane_centroids;
73 
74  pc_edges->reserve(pc.size() / 10);
75  pc_planes->reserve(pc.size() / 10);
76  pc_full_decim->reserve(pc.size() / 10);
77  pc_plane_centroids->reserve(pc.size() / 1000);
78 
81 
82  const auto& xs = pc.getPointsBufferRef_x();
83  const auto& ys = pc.getPointsBufferRef_y();
84  const auto& zs = pc.getPointsBufferRef_z();
85 
86  const float max_e20 = params_.voxel_filter_max_e2_e0;
87  const float max_e10 = params_.voxel_filter_max_e1_e0;
88  const float min_e20 = params_.voxel_filter_min_e2_e0;
89  const float min_e10 = params_.voxel_filter_min_e1_e0;
90  const float min_e1 = params_.voxel_filter_min_e1;
91 
92  std::size_t nEdgeVoxels = 0, nPlaneVoxels = 0, nTotalVoxels = 0;
93 
96  {
97  if (!vxl.indices.empty()) nTotalVoxels++;
98  if (vxl.indices.size() < 5) return;
99 
100  // Analyze the voxel contents:
101  mrpt::math::TPoint3Df mean{0, 0, 0};
102  const float inv_n = (1.0f / vxl.indices.size());
103  for (size_t i = 0; i < vxl.indices.size(); i++)
104  {
105  const auto pt_idx = vxl.indices[i];
106  mean.x += xs[pt_idx];
107  mean.y += ys[pt_idx];
108  mean.z += zs[pt_idx];
109  }
110  mean.x *= inv_n;
111  mean.y *= inv_n;
112  mean.z *= inv_n;
113 
114  mrpt::math::CMatrixFixed<double, 3, 3> mat_a;
115  mat_a.setZero();
116  for (size_t i = 0; i < vxl.indices.size(); i++)
117  {
118  const auto pt_idx = vxl.indices[i];
119  const mrpt::math::TPoint3Df a(
120  xs[pt_idx] - mean.x, ys[pt_idx] - mean.y, zs[pt_idx] - mean.z);
121  mat_a(0, 0) += a.x * a.x;
122  mat_a(1, 0) += a.x * a.y;
123  mat_a(2, 0) += a.x * a.z;
124  mat_a(1, 1) += a.y * a.y;
125  mat_a(2, 1) += a.y * a.z;
126  mat_a(2, 2) += a.z * a.z;
127  }
128  mat_a *= inv_n;
129 
130  // Find eigenvalues & eigenvectors:
131  // This only looks at the lower-triangular part of the cov matrix.
132  mrpt::math::CMatrixFixed<double, 3, 3> eig_vectors;
133  std::vector<double> eig_vals;
134  mat_a.eig_symmetric(eig_vectors, eig_vals);
135 
136  const float e0 = eig_vals[0], e1 = eig_vals[1], e2 = eig_vals[2];
137 
138  mrpt::maps::CPointsMap* dest = nullptr;
139  if (e2 < max_e20 * e0 && e1 < max_e10 * e0)
140  {
141  // Classified as EDGE
142  // ------------------------
143  nEdgeVoxels++;
144  dest = pc_edges.get();
145  }
146  else if (e2 > min_e20 * e0 && e1 > min_e10 * e0 && e1 > min_e1)
147  {
148  // Classified as PLANE
149  // ------------------------
150  nPlaneVoxels++;
151 
152  // Define a plane from its centroid + a normal:
153  const auto pl_c = mrpt::math::TPoint3D(mean);
154 
155  // Normal = largest eigenvector:
156  const auto ev0 = eig_vectors.extractColumn<mrpt::math::TVector3D>(0);
157  auto pl_n = mrpt::math::TVector3D(ev0.x, ev0.y, ev0.z);
158 
159  // Normal direction criterion: make it to face towards the
160  // vehicle. We can use the dot product to find it out, since
161  // pointclouds are given in vehicle-frame coordinates.
162  {
163  // Unit vector: vehicle -> plane centroid:
164  ASSERT_GT_(pl_c.norm(), 1e-3);
165  const auto u = pl_c * (1.0 / pl_c.norm());
166  const auto dot_prod = mrpt::math::dotProduct<3, double>(u, pl_n);
167 
168  // It should be <0 if the normal is pointing to the vehicle.
169  // Otherwise, reverse the normal.
170  if (dot_prod > 0) pl_n = -pl_n;
171  }
172 
173  // Add plane & centroid:
174  const auto pl = mrpt::math::TPlane3D(pl_c, pl_n);
175  inOut.planes.emplace_back(pl, pl_c);
176 
177  // Also: add the centroid to this special layer:
178  pc_plane_centroids->insertPointFast(pl_c.x, pl_c.y, pl_c.z);
179 
180  // Filter out horizontal planes, since their uneven density
181  // makes ICP fail to converge.
182  // A plane on the ground has its 0'th eigenvector like [0 0 1]
183  if (std::abs(ev0.z) < 0.9f)
184  {
185  dest = pc_planes.get();
186  }
187  }
188  if (dest != nullptr)
189  {
190  for (size_t i = 0; i < vxl.indices.size(); i += params_.voxel_filter_decimation)
191  {
192  const auto pt_idx = vxl.indices[i];
193  dest->insertPointFast(xs[pt_idx], ys[pt_idx], zs[pt_idx]);
194  }
195  }
196  // full_pointcloud_decimation=0 means dont use this layer
198  {
199  for (size_t i = 0; i < vxl.indices.size(); i += params_.full_pointcloud_decimation)
200  {
201  const auto pt_idx = vxl.indices[i];
202  pc_full_decim->insertPointFast(xs[pt_idx], ys[pt_idx], zs[pt_idx]);
203  }
204  }
205  });
206 
207  MRPT_LOG_DEBUG_STREAM(
208  "[VoxelGridFilter] Voxel counts: total=" << nTotalVoxels << " edges=" << nEdgeVoxels
209  << " planes=" << nPlaneVoxels);
210 
211  MRPT_END
212 }
mp2p_icp_filters::FilterEdgesPlanes::filter_grid_
PointCloudToVoxelGrid filter_grid_
Definition: FilterEdgesPlanes.h:69
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_min_e2_e0
float voxel_filter_min_e2_e0
Definition: FilterEdgesPlanes.h:60
mp2p_icp_filters::FilterEdgesPlanes
Definition: FilterEdgesPlanes.h:34
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_min_e1_e0
float voxel_filter_min_e1_e0
Definition: FilterEdgesPlanes.h:61
mp2p_icp_filters::FilterEdgesPlanes::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c)
Definition: FilterEdgesPlanes.cpp:22
mp2p_icp_filters::FilterEdgesPlanes::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterEdgesPlanes.cpp:50
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_min_e1
float voxel_filter_min_e1
Definition: FilterEdgesPlanes.h:62
mp2p_icp_filters::FilterEdgesPlanes::Parameters::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterEdgesPlanes.h:50
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterEdgesPlanes::FilterEdgesPlanes
FilterEdgesPlanes()
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t::indices
std::vector< std::size_t > indices
Definition: PointCloudToVoxelGrid.h:59
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_decimation
unsigned int voxel_filter_decimation
Definition: FilterEdgesPlanes.h:57
mp2p_icp_filters::FilterEdgesPlanes::Parameters::full_pointcloud_decimation
unsigned int full_pointcloud_decimation
Definition: FilterEdgesPlanes.h:52
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t
Definition: PointCloudToVoxelGrid.h:62
mp2p_icp::metric_map_t::planes
std::vector< plane_patch_t > planes
Definition: metricmap.h:88
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterEdgesPlanes::params_
Parameters params_
Definition: FilterEdgesPlanes.h:66
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:607
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_resolution
double voxel_filter_resolution
Definition: FilterEdgesPlanes.h:55
mp2p_icp_filters::FilterEdgesPlanes::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterEdgesPlanes.cpp:38
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::PointCloudToVoxelGrid::setResolution
void setResolution(const float voxel_size)
Definition: PointCloudToVoxelGrid.cpp:27
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::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
FilterEdgesPlanes.h
Classify pointcloud voxels into planes / "edges".
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_max_e1_e0
float voxel_filter_max_e1_e0
Definition: FilterEdgesPlanes.h:59
mp2p_icp_filters::FilterEdgesPlanes::Parameters::voxel_filter_max_e2_e0
float voxel_filter_max_e2_e0
Definition: FilterEdgesPlanes.h:58


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