Point Cloud Library (PCL)  1.3.1
Classes | Public Types | Public Member Functions
pcl::VoxelGrid< sensor_msgs::PointCloud2 > Class Reference

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 Types

typedef PointIndices::Ptr PointIndicesPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr

Public Member Functions

 VoxelGrid ()
 Empty constructor.
virtual ~VoxelGrid ()
 Destructor.
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, const 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)
IndicesConstPtr const getRemovedIndices ()
 Get the point indices being removed.
void setFilterFieldName (const std::string &field_name)
 Provide the name of the field to be used for filtering data.
std::string const getFilterFieldName ()
 Get the name of the field used for filtering.
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits.
void getFilterLimits (double &limit_min, double &limit_max)
 Get the field filter limits (min/max) set by the user.
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
bool getFilterLimitsNegative ()
void filter (PointCloud2 &output)
 Calls the filtering method and returns the filtered dataset in output.
void setInputCloud (const PointCloud2ConstPtr &cloud)
 Provide a pointer to the input dataset.
PointCloud2ConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset.
void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used.

Detailed Description

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

Member Typedef Documentation

Definition at line 264 of file pcl_base.h.

Definition at line 263 of file pcl_base.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 376 of file voxel_grid.h.

virtual pcl::VoxelGrid< sensor_msgs::PointCloud2 >::~VoxelGrid ( ) [inline, virtual]

Destructor.

Definition at line 385 of file voxel_grid.h.


Member Function Documentation

void pcl::Filter< sensor_msgs::PointCloud2 >::filter ( PointCloud2 output) [inherited]

Calls the filtering method and returns the filtered dataset in output.

Parameters:
outputthe resultant filtered point cloud dataset

Reimplemented in pcl::FilterIndices< 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 475 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 533 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 468 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 434 of file voxel_grid.h.

std::string const pcl::Filter< sensor_msgs::PointCloud2 >::getFilterFieldName ( ) [inline, inherited]

Get the name of the field used for filtering.

Definition at line 262 of file filter.h.

void pcl::Filter< sensor_msgs::PointCloud2 >::getFilterLimits ( double &  limit_min,
double &  limit_max 
) [inline, inherited]

Get the field filter limits (min/max) set by the user.

The default values are -FLT_MAX, FLT_MAX.

Definition at line 280 of file filter.h.

void pcl::Filter< sensor_msgs::PointCloud2 >::getFilterLimitsNegative ( bool &  limit_negative) [inline, inherited]

Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).

Definition at line 298 of file filter.h.

bool pcl::Filter< sensor_msgs::PointCloud2 >::getFilterLimitsNegative ( ) [inline, inherited]

Definition at line 303 of file filter.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 526 of file voxel_grid.h.

IndicesPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getIndices ( ) [inline, inherited]

Get a pointer to the vector of indices used.

Definition at line 312 of file pcl_base.h.

PointCloud2ConstPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getInputCloud ( ) [inline, inherited]

Get a pointer to the input point cloud dataset.

Definition at line 286 of file pcl_base.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 522 of file voxel_grid.h.

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

Get the voxel grid leaf size.

Definition at line 422 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 456 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 450 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:
xthe X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
ythe Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
zthe Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
relative_coordinatesmatrix 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 489 of file voxel_grid.h.

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

Definition at line 508 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 462 of file voxel_grid.h.

IndicesConstPtr const pcl::Filter< sensor_msgs::PointCloud2 >::getRemovedIndices ( ) [inline, inherited]

Get the point indices being removed.

Definition at line 245 of file filter.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 444 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:
downsamplethe new value (true/false)

Definition at line 428 of file voxel_grid.h.

void pcl::Filter< sensor_msgs::PointCloud2 >::setFilterFieldName ( const std::string &  field_name) [inline, inherited]

Provide the name of the field to be used for filtering data.

In conjunction with setFilterLimits, points having values outside this interval will be discarded.

Parameters:
field_namethe name of the field that contains values used for filtering

Definition at line 255 of file filter.h.

void pcl::Filter< sensor_msgs::PointCloud2 >::setFilterLimits ( const double &  limit_min,
const double &  limit_max 
) [inline, inherited]

Set the field filter limits.

All points having field values outside this interval will be discarded.

Parameters:
limit_minthe minimum allowed field value
limit_maxthe maximum allowed field value

Definition at line 272 of file filter.h.

void pcl::Filter< sensor_msgs::PointCloud2 >::setFilterLimitsNegative ( const bool  limit_negative) [inline, inherited]

Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).

Default: false.

Parameters:
limit_negativereturn data inside the interval (false) or outside (true)

Definition at line 291 of file filter.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const IndicesPtr indices) [inline, inherited]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indicesa pointer to the vector of indices that represents the input data.

Definition at line 292 of file pcl_base.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const PointIndicesConstPtr indices) [inline, inherited]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indicesa pointer to the vector of indices that represents the input data.

Definition at line 303 of file pcl_base.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setInputCloud ( const PointCloud2ConstPtr cloud) [inherited]

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message
void pcl::VoxelGrid< sensor_msgs::PointCloud2 >::setLeafSize ( const Eigen::Vector4f &  leaf_size) [inline]

Set the voxel grid leaf size.

Parameters:
leaf_sizethe voxel grid leaf size

Definition at line 394 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:
lxthe leaf size for X
lythe leaf size for Y
lzthe leaf size for Z

Definition at line 410 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_layoutthe new value (true/false)

Definition at line 440 of file voxel_grid.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines