A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling. More...
#include <mls.h>
Classes | |
struct | Leaf |
Public Types | |
typedef std::map< uint64_t, Leaf > | HashMap |
Public Member Functions | |
void | dilate () |
void | getCellIndex (const Eigen::Vector3f &p, Eigen::Vector3i &index) const |
void | getIndexIn1D (const Eigen::Vector3i &index, uint64_t &index_1d) const |
void | getIndexIn3D (uint64_t index_1d, Eigen::Vector3i &index_3d) const |
void | getPosition (const uint64_t &index_1d, Eigen::Vector3f &point) const |
MLSVoxelGrid (PointCloudInConstPtr &cloud, IndicesPtr &indices, float voxel_size) | |
Public Attributes | |
Eigen::Vector4f | bounding_max_ |
Eigen::Vector4f | bounding_min_ |
uint64_t | data_size_ |
HashMap | voxel_grid_ |
float | voxel_size_ |
A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling.
typedef std::map<uint64_t, Leaf> pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::HashMap |
pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::MLSVoxelGrid | ( | PointCloudInConstPtr & | cloud, |
IndicesPtr & | indices, | ||
float | voxel_size | ||
) |
void pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::dilate | ( | ) |
void pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::getCellIndex | ( | const Eigen::Vector3f & | p, |
Eigen::Vector3i & | index | ||
) | const [inline] |
void pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::getIndexIn1D | ( | const Eigen::Vector3i & | index, |
uint64_t & | index_1d | ||
) | const [inline] |
void pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::getIndexIn3D | ( | uint64_t | index_1d, |
Eigen::Vector3i & | index_3d | ||
) | const [inline] |
void pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::getPosition | ( | const uint64_t & | index_1d, |
Eigen::Vector3f & | point | ||
) | const [inline] |
Eigen::Vector4f pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::bounding_max_ |
Eigen::Vector4f pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::bounding_min_ |
uint64_t pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::data_size_ |
HashMap pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::voxel_grid_ |
float pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::voxel_size_ |