Classes | Public Member Functions | Protected Member Functions | Protected Attributes

pcl::VoxelGrid< sensor_msgs::PointCloud2 > Class Template Reference
[Module filters]

VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...

#include <pcl/filters/voxel_grid.h>

Inheritance diagram for pcl::VoxelGrid< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]
Collaboration diagram for pcl::VoxelGrid< sensor_msgs::PointCloud2 >:
Collaboration graph
[legend]

List of all members.

Classes

struct  Leaf
 Simple structure to hold an nD centroid and the number of points in a leaf. More...

Public Member Functions

 VoxelGrid ()
 Empty constructor.
void setLeafSize (const Eigen::Vector4f &leaf_size)
 Set the voxel grid leaf size.
void setLeafSize (float lx, float ly, float lz)
 Set the voxel grid leaf size.
Eigen::Vector3f getLeafSize ()
 Get the voxel grid leaf size.
void setDownsampleAllData (bool downsample)
 Set to true if all fields need to be downsampled, or false if just XYZ.
bool getDownsampleAllData ()
 Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ).
void setSaveLeafLayout (bool save_leaf_layout)
 Set to true if leaf layout information needs to be saved for later access.
bool getSaveLeafLayout ()
 Returns true if leaf layout information will to be saved for later access.
Eigen::Vector3i getMinBoxCoordinates ()
 Get the minimum coordinates of the bounding box (after filtering is performed).
Eigen::Vector3i getMaxBoxCoordinates ()
 Get the minimum coordinates of the bounding box (after filtering is performed).
Eigen::Vector3i getNrDivisions ()
 Get the number of divisions along all 3 axes (after filtering is performed).
Eigen::Vector3i getDivisionMultiplier ()
 Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed).
int getCentroidIndex (float x, float y, float z)
 Returns the index in the resulting downsampled cloud of the specified point.
std::vector< int > getNeighborCentroidIndices (float x, float y, float z, const 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).
std::vector< int > getNeighborCentroidIndices (float x, float y, float z, std::vector< Eigen::Vector3i > relative_coordinates)
std::vector< int > getLeafLayout ()
 Returns the layout of the leafs for fast access to cells relative to current position.
Eigen::Vector3i getGridCoordinates (float x, float y, float z)
 Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
int getCentroidIndexAt (const 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).

Protected Member Functions

void applyFilter (PointCloud2 &output)
 Downsample a Point Cloud using a voxelized grid approach.

Protected Attributes

std::map< size_t, Leaf > leaves_
 The 3D grid leaves.
Eigen::Vector4f leaf_size_
 The size of a leaf.
bool downsample_all_data_
 Set to true if all fields need to be downsampled, or false if just XYZ.
bool save_leaf_layout_
 Set to true if leaf layout information needs to be saved in leaf_layout.
std::vector< int > leaf_layout_
 The leaf layout information for fast access to cells relative to current position.
Eigen::Vector4i min_b_
 The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Eigen::Vector4i max_b_
Eigen::Vector4i div_b_
Eigen::Vector4i divb_mul_

Detailed Description

template<>
class pcl::VoxelGrid< sensor_msgs::PointCloud2 >

VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.

The VoxelGrid class creates a *3D voxel grid* (think about a voxel grid as a set of tiny 3D boxes in space) over the input point cloud data. Then, in each *voxel* (i.e., 3D box), all the points present will be approximated (i.e., *downsampled*) with their centroid. This approach is a bit slower than approximating them with the center of the voxel, but it represents the underlying surface more accurately.

Author:
Radu Bogdan Rusu, Bastian Steder

Definition at line 338 of file voxel_grid.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 349 of file voxel_grid.h.


Member Function Documentation

void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::applyFilter ( PointCloud2 output  )  [protected, virtual]

Downsample a Point Cloud using a voxelized grid approach.

Parameters:
output the resultant point cloud

Implements pcl::Filter< sensor_msgs::PointCloud2 >.

int pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getCentroidIndex ( float  x,
float  y,
float  z 
) [inline]

Returns the index in the resulting downsampled cloud of the specified point.

Note:
for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed, and that the point is inside the grid, to avoid invalid access (or use getGridCoordinates+getCentroidIndexAt)

Definition at line 429 of file voxel_grid.h.

int pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getCentroidIndexAt ( const 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 487 of file voxel_grid.h.

Eigen::Vector3i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::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 422 of file voxel_grid.h.

bool pcl::VoxelGrid< sensor_msgs::PointCloud2 >::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 388 of file voxel_grid.h.

Eigen::Vector3i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::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 480 of file voxel_grid.h.

std::vector<int> pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getLeafLayout (  )  [inline]

Returns the layout of the leafs for fast access to cells relative to current position.

Note:
position at (i-min_x) + (j-min_y)*div_x + (k-min_z)*div_x*div_y holds the index of the element at coordinates (i,j,k) in the grid (-1 if empty)

Definition at line 476 of file voxel_grid.h.

Eigen::Vector3f pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getLeafSize (  )  [inline]

Get the voxel grid leaf size.

Definition at line 376 of file voxel_grid.h.

Eigen::Vector3i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getMaxBoxCoordinates (  )  [inline]

Get the minimum coordinates of the bounding box (after filtering is performed).

Definition at line 410 of file voxel_grid.h.

Eigen::Vector3i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getMinBoxCoordinates (  )  [inline]

Get the minimum coordinates of the bounding box (after filtering is performed).

Definition at line 404 of file voxel_grid.h.

std::vector<int> pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getNeighborCentroidIndices ( float  x,
float  y,
float  z,
const 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).

Parameters:
x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
z the Z coordinate 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
Note:
for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed

Definition at line 443 of file voxel_grid.h.

std::vector<int> pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getNeighborCentroidIndices ( float  x,
float  y,
float  z,
std::vector< Eigen::Vector3i >  relative_coordinates 
) [inline]

Definition at line 462 of file voxel_grid.h.

Eigen::Vector3i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getNrDivisions (  )  [inline]

Get the number of divisions along all 3 axes (after filtering is performed).

Definition at line 416 of file voxel_grid.h.

bool pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getSaveLeafLayout (  )  [inline]

Returns true if leaf layout information will to be saved for later access.

Definition at line 398 of file voxel_grid.h.

void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::setDownsampleAllData ( bool  downsample  )  [inline]

Set to true if all fields need to be downsampled, or false if just XYZ.

Parameters:
downsample the new value (true/false)

Definition at line 382 of file voxel_grid.h.

void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::setLeafSize ( const Eigen::Vector4f &  leaf_size  )  [inline]

Set the voxel grid leaf size.

Parameters:
leaf_size the voxel grid leaf size

Definition at line 361 of file voxel_grid.h.

void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::setLeafSize ( float  lx,
float  ly,
float  lz 
) [inline]

Set the voxel grid leaf size.

Parameters:
lx the leaf size for X
ly the leaf size for Y
lz the leaf size for Z

Definition at line 369 of file voxel_grid.h.

void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::setSaveLeafLayout ( bool  save_leaf_layout  )  [inline]

Set to true if leaf layout information needs to be saved for later access.

Parameters:
save_leaf_layout the new value (true/false)

Definition at line 394 of file voxel_grid.h.


Member Data Documentation

Eigen::Vector4i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::div_b_ [protected]

Definition at line 531 of file voxel_grid.h.

Eigen::Vector4i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::divb_mul_ [protected]

Definition at line 531 of file voxel_grid.h.

Set to true if all fields need to be downsampled, or false if just XYZ.

Definition at line 516 of file voxel_grid.h.

std::vector<int> pcl::VoxelGrid< sensor_msgs::PointCloud2 >::leaf_layout_ [protected]

The leaf layout information for fast access to cells relative to current position.

Definition at line 526 of file voxel_grid.h.

Eigen::Vector4f pcl::VoxelGrid< sensor_msgs::PointCloud2 >::leaf_size_ [protected]

The size of a leaf.

Definition at line 513 of file voxel_grid.h.

std::map<size_t, Leaf> pcl::VoxelGrid< sensor_msgs::PointCloud2 >::leaves_ [protected]

The 3D grid leaves.

Definition at line 510 of file voxel_grid.h.

Eigen::Vector4i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::max_b_ [protected]

Definition at line 531 of file voxel_grid.h.

Eigen::Vector4i pcl::VoxelGrid< sensor_msgs::PointCloud2 >::min_b_ [protected]

The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.

Definition at line 531 of file voxel_grid.h.

Set to true if leaf layout information needs to be saved in leaf_layout.

Definition at line 521 of file voxel_grid.h.


The documentation for this class was generated from the following file: