PointCloudToVoxelGridSingle.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 // Used in the PIMP:
15 #include <tsl/robin_map.h>
16 
17 using namespace mp2p_icp_filters;
18 
20 {
22 };
23 
25  : impl_(mrpt::make_impl<Impl>())
26 {
27 }
28 
29 void PointCloudToVoxelGridSingle::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 
40  const mrpt::maps::CPointsMap& p)
41 {
42  using mrpt::max3;
43  using std::abs;
44 
45  const auto& xs = p.getPointsBufferRef_x();
46  const auto& ys = p.getPointsBufferRef_y();
47  const auto& zs = p.getPointsBufferRef_z();
48  const auto npts = xs.size();
49 
50  auto& pts_voxels = impl_->pts_voxels;
51 
52  pts_voxels.reserve(pts_voxels.size() + npts);
53 
54  for (std::size_t i = 0; i < npts; i++)
55  {
56  const auto x = xs[i];
57  const auto y = ys[i];
58  const auto z = zs[i];
59 
60  const indices_t vxl_idx = {coord2idx(x), coord2idx(y), coord2idx(z)};
61 
62  auto itVoxel = pts_voxels.find(vxl_idx);
63 
64  if (itVoxel != pts_voxels.end())
65  {
66  // (const cast: required for tsl::robin_map)
67  auto& vx = const_cast<voxel_t&>(itVoxel->second);
68 
69  if (vx.pointCount == 0)
70  vx = {mrpt::math::TPoint3Df(x, y, z), i, &p, 1};
71  else
72  vx.pointCount++;
73  }
74  else
75  {
76  // insert new
77  pts_voxels[vxl_idx] = {mrpt::math::TPoint3Df(x, y, z), i, &p, 1};
78  }
79  }
80 }
81 
83 {
84  //
85  impl_->pts_voxels.min_load_factor(0.01f);
86  impl_->pts_voxels.clear();
87 }
88 
90  const std::function<void(const indices_t idx, const voxel_t& vxl)>&
91  userCode) const
92 {
93  for (const auto& [idx, vxl] : impl_->pts_voxels) userCode(idx, vxl);
94 }
95 
97 {
98  return impl_->pts_voxels.size();
99 }
mp2p_icp_filters::PointCloudToVoxelGridSingle::size
size_t size() const
Returns the number of occupied voxels.
Definition: PointCloudToVoxelGridSingle.cpp:96
mp2p_icp_filters::PointCloudToVoxelGridSingle::coord2idx
int32_t coord2idx(float xyz) const
Definition: PointCloudToVoxelGridSingle.h:101
mp2p_icp_filters::PointCloudToVoxelGridSingle::processPointCloud
void processPointCloud(const mrpt::maps::CPointsMap &p)
Definition: PointCloudToVoxelGridSingle.cpp:39
mp2p_icp_filters::PointCloudToVoxelGridSingle::clear
void clear()
Definition: PointCloudToVoxelGridSingle.cpp:82
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t::pointCount
uint32_t pointCount
Definition: PointCloudToVoxelGridSingle.h:51
robin_map.h
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mrpt
Definition: LogRecord.h:100
test.x
x
Definition: test.py:4
mp2p_icp_filters::PointCloudToVoxelGridSingle::visit_voxels
void visit_voxels(const std::function< void(const indices_t idx, const voxel_t &vxl)> &userCode) const
Definition: PointCloudToVoxelGridSingle.cpp:89
mp2p_icp_filters::PointCloudToVoxelGridSingle::voxel_t
Definition: PointCloudToVoxelGridSingle.h:44
mp2p_icp_filters::PointCloudToVoxelGridSingle::Impl::pts_voxels
tsl::robin_map< indices_t, voxel_t, IndicesHash > pts_voxels
Definition: PointCloudToVoxelGridSingle.cpp:21
mp2p_icp_filters::PointCloudToVoxelGridSingle::Impl
Definition: PointCloudToVoxelGridSingle.cpp:19
mp2p_icp_filters::PointCloudToVoxelGridSingle::resolution_
float resolution_
Definition: PointCloudToVoxelGridSingle.h:115
mp2p_icp_filters::PointCloudToVoxelGridSingle::PointCloudToVoxelGridSingle
PointCloudToVoxelGridSingle()
Definition: PointCloudToVoxelGridSingle.cpp:24
mp2p_icp_filters::PointCloudToVoxelGridSingle::setResolution
void setResolution(const float voxel_size)
Definition: PointCloudToVoxelGridSingle.cpp:29
PointCloudToVoxelGridSingle.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters::PointCloudToVoxelGridSingle::indices_t
Definition: PointCloudToVoxelGridSingle.h:54
mp2p_icp_filters::PointCloudToVoxelGridSingle::impl_
mrpt::pimpl< Impl > impl_
Definition: PointCloudToVoxelGridSingle.h:119
tsl::robin_map
Definition: robin_map.h:91
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19


mp2p_icp
Author(s):
autogenerated on Wed Oct 23 2024 02:45:40