PointCloudToVoxelGrid.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 
15 // Used in the PIMP:
16 #include <tsl/robin_map.h>
17 
18 using namespace mp2p_icp_filters;
19 
21 {
23 };
24 
26 {
27 }
28 
29 void PointCloudToVoxelGrid::setResolution(const float voxel_size)
30 {
31  MRPT_START
32 
33  impl_->pts_voxels.clear();
34  resolution_ = voxel_size;
35 
36  MRPT_END
37 }
38 
39 void PointCloudToVoxelGrid::processPointCloud(const mrpt::maps::CPointsMap& p)
40 {
41  using mrpt::max3;
42  using std::abs;
43 
44  const auto& xs = p.getPointsBufferRef_x();
45  const auto& ys = p.getPointsBufferRef_y();
46  const auto& zs = p.getPointsBufferRef_z();
47  const auto npts = xs.size();
48 
49  // Previous point:
50  float x0, y0, z0;
51  x0 = y0 = z0 = std::numeric_limits<float>::max();
52 
53  auto& pts_voxels = impl_->pts_voxels;
54 
55  pts_voxels.reserve(pts_voxels.size() + npts);
56 
57  for (std::size_t i = 0; i < npts; i++)
58  {
59  // Skip this point?
60  if (params_.min_consecutive_distance != .0f &&
61  max3(abs(x0 - xs[i]), abs(y0 - ys[i]), abs(z0 - zs[i])) <
63  continue;
64 
65  // Save for the next point:
66  x0 = xs[i];
67  y0 = ys[i];
68  z0 = zs[i];
69 
70  const indices_t vxl_idx = {coord2idx(x0), coord2idx(y0), coord2idx(z0)};
71 
72  auto& cell = pts_voxels[vxl_idx];
73  cell.indices.push_back(i); // only if not out of grid range
74  }
75 }
76 
78 {
79  //
80  impl_->pts_voxels.clear();
81 }
82 
84  const std::function<void(const indices_t idx, const voxel_t& vxl)>&
85  userCode) const
86 {
87  for (const auto& [idx, vxl] : impl_->pts_voxels) userCode(idx, vxl);
88 }
89 
90 size_t PointCloudToVoxelGrid::size() const { return impl_->pts_voxels.size(); }
mp2p_icp_filters::PointCloudToVoxelGrid::Parameters::min_consecutive_distance
float min_consecutive_distance
Definition: PointCloudToVoxelGrid.h:51
mp2p_icp_filters::PointCloudToVoxelGrid::Impl
Definition: PointCloudToVoxelGrid.cpp:20
robin_map.h
mp2p_icp_filters::PointCloudToVoxelGrid::resolution_
float resolution_
Definition: PointCloudToVoxelGrid.h:123
mrpt
Definition: LogRecord.h:100
mp2p_icp_filters::PointCloudToVoxelGrid::Impl::pts_voxels
tsl::robin_map< indices_t, voxel_t, IndicesHash > pts_voxels
Definition: PointCloudToVoxelGrid.cpp:22
mp2p_icp_filters::PointCloudToVoxelGrid::coord2idx
int32_t coord2idx(float xyz) const
Definition: PointCloudToVoxelGrid.h:109
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t
Definition: PointCloudToVoxelGrid.h:62
PointCloudToVoxelGrid.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters::PointCloudToVoxelGrid::impl_
mrpt::pimpl< Impl > impl_
Definition: PointCloudToVoxelGrid.h:127
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t
Definition: PointCloudToVoxelGrid.h:57
mp2p_icp_filters::PointCloudToVoxelGrid::params_
Parameters params_
Definition: PointCloudToVoxelGrid.h:54
mp2p_icp_filters::PointCloudToVoxelGrid::clear
void clear()
Definition: PointCloudToVoxelGrid.cpp:77
mp2p_icp_filters::PointCloudToVoxelGrid::processPointCloud
void processPointCloud(const mrpt::maps::CPointsMap &p)
Definition: PointCloudToVoxelGrid.cpp:39
mp2p_icp_filters::PointCloudToVoxelGrid::PointCloudToVoxelGrid
PointCloudToVoxelGrid()
Definition: PointCloudToVoxelGrid.cpp:25
mp2p_icp_filters::PointCloudToVoxelGrid::setResolution
void setResolution(const float voxel_size)
Definition: PointCloudToVoxelGrid.cpp:29
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:83
tsl::robin_map
Definition: robin_map.h:91
mp2p_icp_filters::PointCloudToVoxelGrid::size
size_t size() const
Returns the number of occupied voxels.
Definition: PointCloudToVoxelGrid.cpp:90
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19


mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12