14 #include <mrpt/containers/yaml.h>
15 #include <mrpt/maps/CSimplePointsMap.h>
16 #include <mrpt/math/ops_containers.h>
42 MRPT_LOG_DEBUG_STREAM(
"Loading these params:\n" << c);
61 const auto& pc = *pcPtr;
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();
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;
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);
82 const auto& xs = pc.getPointsBufferRef_x();
83 const auto& ys = pc.getPointsBufferRef_y();
84 const auto& zs = pc.getPointsBufferRef_z();
92 std::size_t nEdgeVoxels = 0, nPlaneVoxels = 0, nTotalVoxels = 0;
97 if (!vxl.
indices.empty()) nTotalVoxels++;
98 if (vxl.
indices.size() < 5)
return;
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++)
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];
114 mrpt::math::CMatrixFixed<double, 3, 3> mat_a;
116 for (
size_t i = 0; i < vxl.
indices.size(); i++)
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;
132 mrpt::math::CMatrixFixed<double, 3, 3> eig_vectors;
133 std::vector<double> eig_vals;
134 mat_a.eig_symmetric(eig_vectors, eig_vals);
136 const float e0 = eig_vals[0], e1 = eig_vals[1], e2 = eig_vals[2];
138 mrpt::maps::CPointsMap* dest =
nullptr;
139 if (e2 < max_e20 * e0 && e1 < max_e10 * e0)
144 dest = pc_edges.get();
146 else if (e2 > min_e20 * e0 && e1 > min_e10 * e0 && e1 > min_e1)
153 const auto pl_c = mrpt::math::TPoint3D(mean);
156 const auto ev0 = eig_vectors.extractColumn<mrpt::math::TVector3D>(0);
157 auto pl_n = mrpt::math::TVector3D(ev0.x, ev0.y, ev0.z);
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);
170 if (dot_prod > 0) pl_n = -pl_n;
174 const auto pl = mrpt::math::TPlane3D(pl_c, pl_n);
175 inOut.
planes.emplace_back(pl, pl_c);
178 pc_plane_centroids->insertPointFast(pl_c.x, pl_c.y, pl_c.z);
183 if (std::abs(ev0.z) < 0.9f)
185 dest = pc_planes.get();
192 const auto pt_idx = vxl.
indices[i];
193 dest->insertPointFast(xs[pt_idx], ys[pt_idx], zs[pt_idx]);
201 const auto pt_idx = vxl.
indices[i];
202 pc_full_decim->insertPointFast(xs[pt_idx], ys[pt_idx], zs[pt_idx]);
207 MRPT_LOG_DEBUG_STREAM(
208 "[VoxelGridFilter] Voxel counts: total=" << nTotalVoxels <<
" edges=" << nEdgeVoxels
209 <<
" planes=" << nPlaneVoxels);