VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
#include <voxel_grid.h>
Classes | |
struct | Leaf |
Simple structure to hold an nD centroid and the number of points in a leaf. More... | |
Public Member Functions | |
int | getCentroidIndex (PointT p) |
Returns the index in the resulting downsampled cloud of the specified point. | |
int | getCentroidIndexAt (Eigen::Vector3i ijk, bool verbose=true) |
Returns the index in the downsampled cloud corresponding to coordinates (i,j,k) in the grid (-1 if empty). | |
Eigen::Vector3i | getDivisionMultiplier () |
Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). | |
bool | getDownsampleAllData () |
Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). | |
Eigen::Vector3i | getGridCoordinates (float x, float y, float z) |
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). | |
std::vector< int > | getLeafLayout () |
Returns the layout of the leafs for fast access to cells relative to current position. | |
Eigen::Vector3f | getLeafSize () |
Get the voxel grid leaf size. | |
Eigen::Vector3i | getMaxBoxCoordinates () |
Get the minimum coordinates of the bounding box (after filtering is performed). | |
Eigen::Vector3i | getMinBoxCoordinates () |
Get the minimum coordinates of the bounding box (after filtering is performed). | |
std::vector< int > | getNeighborCentroidIndices (PointT reference_point, Eigen::MatrixXi relative_coordinates) |
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). | |
Eigen::Vector3i | getNrDivisions () |
Get the number of divisions along all 3 axes (after filtering is performed). | |
bool | getSaveLeafLayout () |
Returns true if leaf layout information will to be saved for later access. | |
void | setDownsampleAllData (bool downsample) |
Set to true if all fields need to be downsampled, or false if just XYZ. | |
void | setLeafSize (float lx, float ly, float lz) |
Set the voxel grid leaf size. | |
void | setLeafSize (const Eigen::Vector4f &leaf_size) |
Set the voxel grid leaf size. | |
void | setSaveLeafLayout (bool save_leaf_layout) |
Set to true if leaf layout information needs to be saved for later access. | |
VoxelGrid () | |
Empty constructor. | |
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. | |
Protected Attributes | |
Eigen::Vector4i | div_b_ |
Eigen::Vector4i | divb_mul_ |
bool | downsample_all_data_ |
Set to true if all fields need to be downsampled, or false if just XYZ. | |
std::vector< int > | leaf_layout_ |
The leaf layout information for fast access to cells relative to current position. | |
Eigen::Vector4f | leaf_size_ |
The size of a leaf. | |
std::map< size_t, Leaf > | leaves_ |
The 3D grid leaves. | |
Eigen::Vector4i | max_b_ |
Eigen::Vector4i | min_b_ |
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. | |
bool | save_leaf_layout_ |
Set to true if leaf layout information needs to be saved in leaf_layout_. | |
Private Types | |
typedef Filter< PointT > ::PointCloud | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition at line 125 of file voxel_grid.h.
typedef pcl::traits::fieldList<PointT>::type pcl::VoxelGrid< PointT >::FieldList [protected] |
Definition at line 297 of file voxel_grid.h.
typedef Filter<PointT>::PointCloud pcl::VoxelGrid< PointT >::PointCloud [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 136 of file voxel_grid.h.
typedef PointCloud::ConstPtr pcl::VoxelGrid< PointT >::PointCloudConstPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 138 of file voxel_grid.h.
typedef PointCloud::Ptr pcl::VoxelGrid< PointT >::PointCloudPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 137 of file voxel_grid.h.
pcl::VoxelGrid< PointT >::VoxelGrid | ( | ) | [inline] |
Empty constructor.
Definition at line 142 of file voxel_grid.h.
void pcl::VoxelGrid< PointT >::applyFilter | ( | PointCloud & | output | ) | [inline, protected, virtual] |
Downsample a Point Cloud using a voxelized grid approach.
output | the resultant point cloud message |
Implements pcl::Filter< PointT >.
Definition at line 93 of file voxel_grid.hpp.
int pcl::VoxelGrid< PointT >::getCentroidIndex | ( | PointT | p | ) | [inline] |
Returns the index in the resulting downsampled cloud of the specified point.
Definition at line 213 of file voxel_grid.h.
int pcl::VoxelGrid< PointT >::getCentroidIndexAt | ( | Eigen::Vector3i | ijk, | |
bool | verbose = true | |||
) | [inline] |
Returns the index in the downsampled cloud corresponding to coordinates (i,j,k) in the grid (-1 if empty).
Definition at line 258 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< PointT >::getDivisionMultiplier | ( | ) | [inline] |
Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed).
Definition at line 206 of file voxel_grid.h.
bool pcl::VoxelGrid< PointT >::getDownsampleAllData | ( | ) | [inline] |
Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ).
Definition at line 180 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< PointT >::getGridCoordinates | ( | float | x, | |
float | y, | |||
float | z | |||
) | [inline] |
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
Definition at line 251 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< PointT >::getLeafLayout | ( | ) | [inline] |
Returns the layout of the leafs for fast access to cells relative to current position.
Definition at line 247 of file voxel_grid.h.
Eigen::Vector3f pcl::VoxelGrid< PointT >::getLeafSize | ( | ) | [inline] |
Get the voxel grid leaf size.
Definition at line 169 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< PointT >::getMaxBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 198 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< PointT >::getMinBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 194 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< PointT >::getNeighborCentroidIndices | ( | PointT | reference_point, | |
Eigen::MatrixXi | relative_coordinates | |||
) | [inline] |
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds).
reference_point | the coordinates of the reference point (corresponding cell is allowed to be empty/out of bounds) | |
relative_coordinates | matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell |
Definition at line 225 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< PointT >::getNrDivisions | ( | ) | [inline] |
Get the number of divisions along all 3 axes (after filtering is performed).
Definition at line 202 of file voxel_grid.h.
bool pcl::VoxelGrid< PointT >::getSaveLeafLayout | ( | ) | [inline] |
Returns true if leaf layout information will to be saved for later access.
Definition at line 190 of file voxel_grid.h.
void pcl::VoxelGrid< 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 175 of file voxel_grid.h.
void pcl::VoxelGrid< PointT >::setLeafSize | ( | float | lx, | |
float | ly, | |||
float | lz | |||
) | [inline] |
Set the voxel grid leaf size.
lx | the leaf size for X | |
ly | the leaf size for Y | |
lz | the leaf size for Z |
Definition at line 162 of file voxel_grid.h.
void pcl::VoxelGrid< PointT >::setLeafSize | ( | const Eigen::Vector4f & | leaf_size | ) | [inline] |
Set the voxel grid leaf size.
leaf_size | the voxel grid leaf size |
Definition at line 154 of file voxel_grid.h.
void pcl::VoxelGrid< PointT >::setSaveLeafLayout | ( | bool | save_leaf_layout | ) | [inline] |
Set to true if leaf layout information needs to be saved for later access.
save_leaf_layout | the new value (true/false) |
Definition at line 186 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< PointT >::div_b_ [protected] |
Definition at line 295 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< PointT >::divb_mul_ [protected] |
Definition at line 295 of file voxel_grid.h.
bool pcl::VoxelGrid< PointT >::downsample_all_data_ [protected] |
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition at line 286 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< PointT >::leaf_layout_ [protected] |
The leaf layout information for fast access to cells relative to current position.
Definition at line 292 of file voxel_grid.h.
Eigen::Vector4f pcl::VoxelGrid< PointT >::leaf_size_ [protected] |
The size of a leaf.
Definition at line 283 of file voxel_grid.h.
std::map<size_t, Leaf> pcl::VoxelGrid< PointT >::leaves_ [protected] |
The 3D grid leaves.
Definition at line 280 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< PointT >::max_b_ [protected] |
Definition at line 295 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< PointT >::min_b_ [protected] |
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Definition at line 295 of file voxel_grid.h.
bool pcl::VoxelGrid< PointT >::save_leaf_layout_ [protected] |
Set to true if leaf layout information needs to be saved in leaf_layout_.
Definition at line 289 of file voxel_grid.h.