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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
13 #pragma once
14 
15 #include <mrpt/containers/CDynamicGrid3D.h>
16 #include <mrpt/maps/CPointsMap.h>
17 #include <mrpt/math/TPoint3D.h>
18 
19 #include <vector>
20 
22 namespace mp2p_icp_filters
23 {
29 {
30  public:
31  PointCloudToVoxelGrid() = default;
33 
34  void resize(
35  const mrpt::math::TPoint3D& min_corner,
36  const mrpt::math::TPoint3D& max_corner, const float voxel_size);
37  void processPointCloud(const mrpt::maps::CPointsMap& p);
38  void clear();
39 
40  struct Parameters
41  {
50  };
51 
53 
55  struct voxel_t
56  {
57  std::vector<std::size_t> indices;
58  bool is_empty{true};
59  };
60  using grid_t = mrpt::containers::CDynamicGrid3D<voxel_t, float>;
61 
65 
66  std::vector<uint32_t> used_voxel_indices;
67 };
68 
69 } // namespace mp2p_icp_filters
mp2p_icp_filters::PointCloudToVoxelGrid::Parameters::min_consecutive_distance
float min_consecutive_distance
Definition: PointCloudToVoxelGrid.h:49
mp2p_icp_filters::PointCloudToVoxelGrid::~PointCloudToVoxelGrid
~PointCloudToVoxelGrid()
Definition: PointCloudToVoxelGrid.h:32
mp2p_icp_filters::PointCloudToVoxelGrid::grid_t
mrpt::containers::CDynamicGrid3D< voxel_t, float > grid_t
Definition: PointCloudToVoxelGrid.h:60
mp2p_icp_filters::PointCloudToVoxelGrid::PointCloudToVoxelGrid
PointCloudToVoxelGrid()=default
mp2p_icp_filters::PointCloudToVoxelGrid
Definition: PointCloudToVoxelGrid.h:28
mp2p_icp_filters::PointCloudToVoxelGrid::used_voxel_indices
std::vector< uint32_t > used_voxel_indices
Definition: PointCloudToVoxelGrid.h:66
mp2p_icp_filters::PointCloudToVoxelGrid::Parameters
Definition: PointCloudToVoxelGrid.h:40
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t::indices
std::vector< std::size_t > indices
Definition: PointCloudToVoxelGrid.h:57
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t::is_empty
bool is_empty
Definition: PointCloudToVoxelGrid.h:58
mp2p_icp_filters::PointCloudToVoxelGrid::resize
void resize(const mrpt::math::TPoint3D &min_corner, const mrpt::math::TPoint3D &max_corner, const float voxel_size)
Definition: PointCloudToVoxelGrid.cpp:22
mp2p_icp_filters::PointCloudToVoxelGrid::voxel_t
Definition: PointCloudToVoxelGrid.h:55
mp2p_icp_filters::PointCloudToVoxelGrid::params_
Parameters params_
Definition: PointCloudToVoxelGrid.h:52
mp2p_icp_filters::PointCloudToVoxelGrid::clear
void clear()
Definition: PointCloudToVoxelGrid.cpp:84
mp2p_icp_filters::PointCloudToVoxelGrid::processPointCloud
void processPointCloud(const mrpt::maps::CPointsMap &p)
Definition: PointCloudToVoxelGrid.cpp:39
mp2p_icp_filters::PointCloudToVoxelGrid::pts_voxels
grid_t pts_voxels
Definition: PointCloudToVoxelGrid.h:64
mp2p_icp_filters
Definition: FilterBase.h:25


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04