PointCloudToVoxelGrid.h
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  * ------------------------------------------------------------------------- */
13 #pragma once
14 
15 #include <mrpt/core/pimpl.h>
16 #include <mrpt/maps/CPointsMap.h>
17 
18 #include <vector>
19 
21 namespace mp2p_icp_filters
22 {
28 {
29  public:
32 
34  void setResolution(const float voxel_size);
35 
36  void processPointCloud(const mrpt::maps::CPointsMap& p);
37 
40  void clear();
41 
42  struct Parameters
43  {
52  };
53 
55 
57  struct voxel_t
58  {
59  std::vector<std::size_t> indices;
60  };
61 
62  struct indices_t
63  {
64  indices_t(int32_t cx, int32_t cy, int32_t cz)
65  : cx_(cx), cy_(cy), cz_(cz)
66  {
67  }
68 
69  int32_t cx_ = 0, cy_ = 0, cz_ = 0;
70 
71  bool operator==(const indices_t& o) const
72  {
73  return cx_ == o.cx_ && cy_ == o.cy_ && cz_ == o.cz_;
74  }
75  };
76 
84  struct IndicesHash
85  {
87  std::size_t operator()(const indices_t& k) const noexcept
88  {
89  // These are the implicit assumptions of the reinterpret cast below:
90  static_assert(sizeof(indices_t::cx_) == sizeof(uint32_t));
91  static_assert(offsetof(indices_t, cx_) == 0 * sizeof(uint32_t));
92  static_assert(offsetof(indices_t, cy_) == 1 * sizeof(uint32_t));
93  static_assert(offsetof(indices_t, cz_) == 2 * sizeof(uint32_t));
94 
95  const uint32_t* vec = reinterpret_cast<const uint32_t*>(&k);
96  return ((1 << 20) - 1) &
97  (vec[0] * 73856093 ^ vec[1] * 19349663 ^ vec[2] * 83492791);
98  }
99 
100  // k1 < k2?
101  bool operator()(const indices_t& k1, const indices_t& k2) const noexcept
102  {
103  if (k1.cx_ != k2.cx_) return k1.cx_ < k2.cx_;
104  if (k1.cy_ != k2.cy_) return k1.cy_ < k2.cy_;
105  return k1.cz_ < k2.cz_;
106  }
107  };
108 
109  inline int32_t coord2idx(float xyz) const
110  {
111  return static_cast<int32_t>(xyz / resolution_);
112  }
113 
114  void visit_voxels(
115  const std::function<void(const indices_t idx, const voxel_t& vxl)>&
116  userCode) const;
117 
119  size_t size() const;
120 
121  private:
123  float resolution_ = 0.20f;
124 
127  struct Impl;
128  mrpt::pimpl<Impl> impl_;
129 };
130 
131 } // namespace mp2p_icp_filters
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
mp2p_icp_filters::PointCloudToVoxelGrid::~PointCloudToVoxelGrid
~PointCloudToVoxelGrid()
Definition: PointCloudToVoxelGrid.h:31
mp2p_icp_filters::PointCloudToVoxelGrid::IndicesHash::operator()
bool operator()(const indices_t &k1, const indices_t &k2) const noexcept
Definition: PointCloudToVoxelGrid.h:101
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::cx_
int32_t cx_
Definition: PointCloudToVoxelGrid.h:69
mp2p_icp_filters::PointCloudToVoxelGrid::resolution_
float resolution_
Definition: PointCloudToVoxelGrid.h:123
mp2p_icp_filters::PointCloudToVoxelGrid::IndicesHash
Definition: PointCloudToVoxelGrid.h:84
mp2p_icp_filters::PointCloudToVoxelGrid::coord2idx
int32_t coord2idx(float xyz) const
Definition: PointCloudToVoxelGrid.h:109
mp2p_icp_filters::PointCloudToVoxelGrid
Definition: PointCloudToVoxelGrid.h:27
mp2p_icp_filters::PointCloudToVoxelGrid::Parameters
Definition: PointCloudToVoxelGrid.h:42
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_filters::PointCloudToVoxelGrid::indices_t::indices_t
indices_t(int32_t cx, int32_t cy, int32_t cz)
Definition: PointCloudToVoxelGrid.h:64
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::cz_
int32_t cz_
Definition: PointCloudToVoxelGrid.h:69
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::IndicesHash::operator()
std::size_t operator()(const indices_t &k) const noexcept
Hash operator for unordered maps:
Definition: PointCloudToVoxelGrid.h:87
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
mp2p_icp_filters::PointCloudToVoxelGrid::size
size_t size() const
Returns the number of occupied voxels.
Definition: PointCloudToVoxelGrid.cpp:90
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::cy_
int32_t cy_
Definition: PointCloudToVoxelGrid.h:69
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::PointCloudToVoxelGrid::indices_t::operator==
bool operator==(const indices_t &o) const
Definition: PointCloudToVoxelGrid.h:71


mp2p_icp
Author(s):
autogenerated on Wed Oct 2 2024 02:45:25