ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
#include <approximate_voxel_grid.h>
Classes | |
struct | he |
Public Member Functions | |
ApproximateVoxelGrid () | |
Empty constructor. | |
ApproximateVoxelGrid (const ApproximateVoxelGrid &src) | |
Copy constructor. | |
bool | getDownsampleAllData () const |
Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). | |
Eigen::Vector3f | getLeafSize () const |
Get the voxel grid leaf size. | |
ApproximateVoxelGrid & | operator= (const ApproximateVoxelGrid &src) |
Copy operator. | |
void | setDownsampleAllData (bool downsample) |
Set to true if all fields need to be downsampled, or false if just XYZ. | |
void | setLeafSize (const Eigen::Vector3f &leaf_size) |
Set the voxel grid leaf size. | |
void | setLeafSize (float lx, float ly, float lz) |
Set the voxel grid leaf size. | |
Protected Types | |
typedef pcl::traits::fieldList < PointT >::type | FieldList |
Protected Member Functions | |
void | applyFilter (PointCloud &output) |
Downsample a Point Cloud using a voxelized grid approach. | |
void | flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size) |
Write a single point from the hash to the output cloud. | |
Protected Attributes | |
bool | downsample_all_data_ |
Set to true if all fields need to be downsampled, or false if just XYZ. | |
struct he * | history_ |
history buffer | |
size_t | histsize_ |
history buffer size, power of 2 | |
Eigen::Array3f | inverse_leaf_size_ |
Compute 1/leaf_size_ to avoid division later. | |
Eigen::Vector3f | leaf_size_ |
The size of a leaf. | |
Private Types | |
typedef Filter< PointT > ::PointCloud | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition at line 100 of file approximate_voxel_grid.h.
typedef pcl::traits::fieldList<PointT>::type pcl::ApproximateVoxelGrid< PointT >::FieldList [protected] |
Definition at line 217 of file approximate_voxel_grid.h.
typedef Filter<PointT>::PointCloud pcl::ApproximateVoxelGrid< PointT >::PointCloud [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 107 of file approximate_voxel_grid.h.
typedef PointCloud::ConstPtr pcl::ApproximateVoxelGrid< PointT >::PointCloudConstPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 109 of file approximate_voxel_grid.h.
typedef PointCloud::Ptr pcl::ApproximateVoxelGrid< PointT >::PointCloudPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 108 of file approximate_voxel_grid.h.
pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid | ( | ) | [inline] |
Empty constructor.
Definition at line 122 of file approximate_voxel_grid.h.
pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid | ( | const ApproximateVoxelGrid< PointT > & | src | ) | [inline] |
Copy constructor.
[in] | src | the approximate voxel grid to copy into this. |
Definition at line 135 of file approximate_voxel_grid.h.
void pcl::ApproximateVoxelGrid< PointT >::applyFilter | ( | PointCloud & | output | ) | [protected, virtual] |
Downsample a Point Cloud using a voxelized grid approach.
output | the resultant point cloud message |
Implements pcl::Filter< PointT >.
Definition at line 64 of file approximate_voxel_grid.hpp.
void pcl::ApproximateVoxelGrid< PointT >::flush | ( | PointCloud & | output, |
size_t | op, | ||
he * | hhe, | ||
int | rgba_index, | ||
int | centroid_size | ||
) | [protected] |
Write a single point from the hash to the output cloud.
Definition at line 46 of file approximate_voxel_grid.hpp.
bool pcl::ApproximateVoxelGrid< PointT >::getDownsampleAllData | ( | ) | const [inline] |
Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ).
Definition at line 199 of file approximate_voxel_grid.h.
Eigen::Vector3f pcl::ApproximateVoxelGrid< PointT >::getLeafSize | ( | ) | const [inline] |
Get the voxel grid leaf size.
Definition at line 187 of file approximate_voxel_grid.h.
ApproximateVoxelGrid& pcl::ApproximateVoxelGrid< PointT >::operator= | ( | const ApproximateVoxelGrid< PointT > & | src | ) | [inline] |
Copy operator.
[in] | src | the approximate voxel grid to copy into this. |
Definition at line 152 of file approximate_voxel_grid.h.
void pcl::ApproximateVoxelGrid< PointT >::setDownsampleAllData | ( | bool | downsample | ) | [inline] |
Set to true if all fields need to be downsampled, or false if just XYZ.
downsample | the new value (true/false) |
Definition at line 193 of file approximate_voxel_grid.h.
void pcl::ApproximateVoxelGrid< PointT >::setLeafSize | ( | const Eigen::Vector3f & | leaf_size | ) | [inline] |
Set the voxel grid leaf size.
[in] | leaf_size | the voxel grid leaf size |
Definition at line 168 of file approximate_voxel_grid.h.
void pcl::ApproximateVoxelGrid< PointT >::setLeafSize | ( | float | lx, |
float | ly, | ||
float | lz | ||
) | [inline] |
Set the voxel grid leaf size.
[in] | lx | the leaf size for X |
[in] | ly | the leaf size for Y |
[in] | lz | the leaf size for Z |
Definition at line 180 of file approximate_voxel_grid.h.
bool pcl::ApproximateVoxelGrid< PointT >::downsample_all_data_ [protected] |
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition at line 209 of file approximate_voxel_grid.h.
struct he* pcl::ApproximateVoxelGrid< PointT >::history_ [protected] |
history buffer
Definition at line 215 of file approximate_voxel_grid.h.
size_t pcl::ApproximateVoxelGrid< PointT >::histsize_ [protected] |
history buffer size, power of 2
Definition at line 212 of file approximate_voxel_grid.h.
Eigen::Array3f pcl::ApproximateVoxelGrid< PointT >::inverse_leaf_size_ [protected] |
Compute 1/leaf_size_ to avoid division later.
Definition at line 206 of file approximate_voxel_grid.h.
Eigen::Vector3f pcl::ApproximateVoxelGrid< PointT >::leaf_size_ [protected] |
The size of a leaf.
Definition at line 203 of file approximate_voxel_grid.h.