Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
pcl::VoxelGrid< sensor_msgs::PointCloud2 > Class Template Reference

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

#include <voxel_grid.h>

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

List of all members.

Public Member Functions

int getCentroidIndex (float x, float y, float z)
 Returns the index in the resulting downsampled cloud of the specified point.
int getCentroidIndexAt (const Eigen::Vector3i &ijk)
 Returns the index in the downsampled cloud corresponding to a given set of coordinates.
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).
std::string const getFilterFieldName ()
 Get the name of the field used for filtering.
void getFilterLimits (double &limit_min, double &limit_max)
 Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_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 ()
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
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 (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)
 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 setFilterFieldName (const std::string &field_name)
 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.
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits. All points having field values outside this interval will be discarded.
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). Default: false.
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.
void setSaveLeafLayout (bool save_leaf_layout)
 Set to true if leaf layout information needs to be saved for later access.
 VoxelGrid ()
 Empty constructor.
virtual ~VoxelGrid ()
 Destructor.

Protected Member Functions

void applyFilter (PointCloud2 &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::string filter_field_name_
 The desired user filter field name.
double filter_limit_max_
 The maximum allowed filter value a point will be considered from.
double filter_limit_min_
 The minimum allowed filter value a point will be considered from.
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
Eigen::Array4f inverse_leaf_size_
 Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
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.
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 sensor_msgs::PointCloud2 PointCloud2
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
typedef PointCloud2::Ptr PointCloud2Ptr

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 B. Rusu, Bastian Steder, Radoslaw Cybulski

Definition at line 476 of file voxel_grid.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl::VoxelGrid< sensor_msgs::PointCloud2 >::PointCloud2 [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 481 of file voxel_grid.h.

typedef PointCloud2::ConstPtr pcl::VoxelGrid< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 483 of file voxel_grid.h.

typedef PointCloud2::Ptr pcl::VoxelGrid< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 482 of file voxel_grid.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 487 of file voxel_grid.h.

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

Destructor.

Definition at line 506 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:
[out]outputthe resultant point cloud

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

Definition at line 175 of file filters/src/voxel_grid.cpp.

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)
Parameters:
[in]xthe X point coordinate to get the index at
[in]ythe Y point coordinate to get the index at
[in]zthe Z point coordinate to get the index at

Definition at line 598 of file voxel_grid.h.

int pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getCentroidIndexAt ( const Eigen::Vector3i &  ijk) [inline]

Returns the index in the downsampled cloud corresponding to a given set of coordinates.

Parameters:
[in]ijkthe coordinates (i,j,k) in the grid (-1 if empty)

Definition at line 678 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 588 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 554 of file voxel_grid.h.

std::string const pcl::VoxelGrid< sensor_msgs::PointCloud2 >::getFilterFieldName ( ) [inline]

Get the name of the field used for filtering.

Definition at line 702 of file voxel_grid.h.

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

Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX.

Parameters:
[out]limit_minthe minimum allowed field value
[out]limit_maxthe maximum allowed field value

Definition at line 723 of file voxel_grid.h.

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

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

Parameters:
[out]limit_negativetrue if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 743 of file voxel_grid.h.

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

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

Returns:
true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 752 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).

Parameters:
[in]xthe X point coordinate to get the (i, j, k) index at
[in]ythe Y point coordinate to get the (i, j, k) index at
[in]zthe Z point coordinate to get the (i, j, k) index at

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

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

Get the voxel grid leaf size.

Definition at line 542 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 576 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 570 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:
[in]xthe X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in]ythe Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in]zthe Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[out]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 616 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]

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:
[in]xthe X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in]ythe Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in]zthe Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[out]relative_coordinatesvector with the elements 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 645 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 582 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 564 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:
[in]downsamplethe new value (true/false)

Definition at line 548 of file voxel_grid.h.

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

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:
[in]field_namethe name of the field that contains values used for filtering

Definition at line 695 of file voxel_grid.h.

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

Set the field filter limits. All points having field values outside this interval will be discarded.

Parameters:
[in]limit_minthe minimum allowed field value
[in]limit_maxthe maximum allowed field value

Definition at line 712 of file voxel_grid.h.

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

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

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

Definition at line 734 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:
[in]leaf_sizethe voxel grid leaf size

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

Definition at line 530 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:
[in]save_leaf_layoutthe new value (true/false)

Definition at line 560 of file voxel_grid.h.


Member Data Documentation

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

Definition at line 780 of file voxel_grid.h.

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

Definition at line 780 of file voxel_grid.h.

bool pcl::VoxelGrid< sensor_msgs::PointCloud2 >::downsample_all_data_ [protected]

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

Definition at line 765 of file voxel_grid.h.

std::string pcl::VoxelGrid< sensor_msgs::PointCloud2 >::filter_field_name_ [protected]

The desired user filter field name.

Definition at line 783 of file voxel_grid.h.

double pcl::VoxelGrid< sensor_msgs::PointCloud2 >::filter_limit_max_ [protected]

The maximum allowed filter value a point will be considered from.

Definition at line 789 of file voxel_grid.h.

double pcl::VoxelGrid< sensor_msgs::PointCloud2 >::filter_limit_min_ [protected]

The minimum allowed filter value a point will be considered from.

Definition at line 786 of file voxel_grid.h.

bool pcl::VoxelGrid< sensor_msgs::PointCloud2 >::filter_limit_negative_ [protected]

Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.

Definition at line 792 of file voxel_grid.h.

Eigen::Array4f pcl::VoxelGrid< sensor_msgs::PointCloud2 >::inverse_leaf_size_ [protected]

Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.

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

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

The size of a leaf.

Definition at line 759 of file voxel_grid.h.

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

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

bool pcl::VoxelGrid< sensor_msgs::PointCloud2 >::save_leaf_layout_ [protected]

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

Definition at line 770 of file voxel_grid.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:18