Point Cloud Library (PCL)  1.8.1-dev
List of all members | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::VoxelGrid< PointT > Class Template 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< PointT >:

Public Member Functions

 VoxelGrid ()
 Empty constructor. More...
 
virtual ~VoxelGrid ()
 Destructor. More...
 
void setLeafSize (const Eigen::Vector4f &leaf_size)
 Set the voxel grid leaf size. More...
 
void setLeafSize (float lx, float ly, float lz)
 Set the voxel grid leaf size. More...
 
Eigen::Vector3f getLeafSize ()
 Get the voxel grid leaf size. More...
 
void setDownsampleAllData (bool downsample)
 Set to true if all fields need to be downsampled, or false if just XYZ. More...
 
bool getDownsampleAllData ()
 Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). More...
 
void setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel)
 Set the minimum number of points required for a voxel to be used. More...
 
unsigned int getMinimumPointsNumberPerVoxel ()
 Return the minimum number of points required for a voxel to be used. More...
 
void setSaveLeafLayout (bool save_leaf_layout)
 Set to true if leaf layout information needs to be saved for later access. More...
 
bool getSaveLeafLayout ()
 Returns true if leaf layout information will to be saved for later access. More...
 
Eigen::Vector3i getMinBoxCoordinates ()
 Get the minimum coordinates of the bounding box (after filtering is performed). More...
 
Eigen::Vector3i getMaxBoxCoordinates ()
 Get the minimum coordinates of the bounding box (after filtering is performed). More...
 
Eigen::Vector3i getNrDivisions ()
 Get the number of divisions along all 3 axes (after filtering is performed). More...
 
Eigen::Vector3i getDivisionMultiplier ()
 Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). More...
 
int getCentroidIndex (const PointT &p)
 Returns the index in the resulting downsampled cloud of the specified point. More...
 
std::vector< int > getNeighborCentroidIndices (const PointT &reference_point, 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). More...
 
std::vector< int > getLeafLayout ()
 Returns the layout of the leafs for fast access to cells relative to current position. More...
 
Eigen::Vector3i getGridCoordinates (float x, float y, float z)
 Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). More...
 
int getCentroidIndexAt (const Eigen::Vector3i &ijk)
 Returns the index in the downsampled cloud corresponding to a given set of coordinates. More...
 
void setFilterFieldName (const std::string &field_name)
 Provide the name of the field to be used for filtering data. More...
 
std::string const getFilterFieldName ()
 Get the name of the field used for filtering. More...
 
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits. More...
 
void getFilterLimits (double &limit_min, double &limit_max)
 Get the field filter limits (min/max) set by the user. More...
 
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). More...
 
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
bool getFilterLimitsNegative ()
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
- Public Member Functions inherited from pcl::Filter< PointT >
 Filter (bool extract_removed_indices=false)
 Empty constructor. More...
 
virtual ~Filter ()
 Empty destructor. More...
 
IndicesConstPtr const getRemovedIndices ()
 Get the point indices being removed. More...
 
void getRemovedIndices (PointIndices &pi)
 Get the point indices being removed. More...
 
void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output. More...
 
- Public Member Functions inherited from pcl::PCLBase< PointT >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointToperator[] (size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Types

typedef Filter< PointT >
::PointCloud 
PointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef boost::shared_ptr
< VoxelGrid< PointT > > 
Ptr
 
typedef boost::shared_ptr
< const VoxelGrid< PointT > > 
ConstPtr
 
typedef pcl::traits::fieldList
< PointT >::type 
FieldList
 

Protected Member Functions

void applyFilter (PointCloud &output)
 Downsample a Point Cloud using a voxelized grid approach. More...
 
- Protected Member Functions inherited from pcl::Filter< PointT >
const std::string & getClassName () const
 Get a string representation of the name of this class. More...
 
- Protected Member Functions inherited from pcl::PCLBase< PointT >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Protected Attributes

Eigen::Vector4f leaf_size_
 The size of a leaf. More...
 
Eigen::Array4f inverse_leaf_size_
 Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. More...
 
bool downsample_all_data_
 Set to true if all fields need to be downsampled, or false if just XYZ. More...
 
bool save_leaf_layout_
 Set to true if leaf layout information needs to be saved in leaf_layout_. More...
 
std::vector< int > leaf_layout_
 The leaf layout information for fast access to cells relative to current position. More...
 
Eigen::Vector4i min_b_
 The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. More...
 
Eigen::Vector4i max_b_
 
Eigen::Vector4i div_b_
 
Eigen::Vector4i divb_mul_
 
std::string filter_field_name_
 The desired user filter field name. More...
 
double filter_limit_min_
 The minimum allowed filter value a point will be considered from. More...
 
double filter_limit_max_
 The maximum allowed filter value a point will be considered from. More...
 
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). More...
 
unsigned int min_points_per_voxel_
 Minimum number of points per voxel for the centroid to be computed. More...
 
- Protected Attributes inherited from pcl::Filter< PointT >
IndicesPtr removed_indices_
 Indices of the points that are removed. More...
 
std::string filter_name_
 The filter name. More...
 
bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points. More...
 
- Protected Attributes inherited from pcl::PCLBase< PointT >
PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

Additional Inherited Members

- Public Types inherited from pcl::Filter< PointT >
typedef boost::shared_ptr
< Filter< PointT > > 
Ptr
 
typedef boost::shared_ptr
< const Filter< PointT > > 
ConstPtr
 
typedef pcl::PointCloud< PointTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
- Public Types inherited from pcl::PCLBase< PointT >
typedef pcl::PointCloud< PointTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr
 
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
 

Detailed Description

template<typename PointT>
class pcl::VoxelGrid< PointT >

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

Definition at line 178 of file voxel_grid.h.

Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const VoxelGrid<PointT> > pcl::VoxelGrid< PointT >::ConstPtr
protected

Definition at line 190 of file voxel_grid.h.

template<typename PointT>
typedef pcl::traits::fieldList<PointT>::type pcl::VoxelGrid< PointT >::FieldList
protected

Definition at line 489 of file voxel_grid.h.

template<typename PointT>
typedef Filter<PointT>::PointCloud pcl::VoxelGrid< PointT >::PointCloud
protected

Definition at line 186 of file voxel_grid.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::VoxelGrid< PointT >::PointCloudConstPtr
protected

Definition at line 188 of file voxel_grid.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::VoxelGrid< PointT >::PointCloudPtr
protected

Definition at line 187 of file voxel_grid.h.

template<typename PointT>
typedef boost::shared_ptr< VoxelGrid<PointT> > pcl::VoxelGrid< PointT >::Ptr
protected

Definition at line 189 of file voxel_grid.h.

Constructor & Destructor Documentation

template<typename PointT>
pcl::VoxelGrid< PointT >::VoxelGrid ( )
inline

Empty constructor.

Definition at line 195 of file voxel_grid.h.

template<typename PointT>
virtual pcl::VoxelGrid< PointT >::~VoxelGrid ( )
inlinevirtual

Destructor.

Definition at line 215 of file voxel_grid.h.

Member Function Documentation

template<typename PointT >
void pcl::VoxelGrid< PointT >::applyFilter ( PointCloud output)
protectedvirtual

Downsample a Point Cloud using a voxelized grid approach.

Parameters
[out]outputthe resultant point cloud message

Implements pcl::Filter< PointT >.

Reimplemented in pcl::VoxelGridCovariance< PointT >, and pcl::VoxelGridCovariance< PointTarget >.

Definition at line 214 of file voxel_grid.hpp.

References pcl::CentroidPoint< PointT >::add(), pcl::CentroidPoint< PointT >::get(), pcl::getFieldIndex(), pcl::PointCloud< T >::height, pcl::PointCloud< T >::is_dense, pcl::PointCloud< T >::points, and pcl::PointCloud< T >::width.

template<typename PointT>
int pcl::VoxelGrid< PointT >::getCentroidIndex ( const PointT p)
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]pthe point to get the index at

Definition at line 319 of file voxel_grid.h.

Referenced by pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().

template<typename PointT>
int pcl::VoxelGrid< PointT >::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 376 of file voxel_grid.h.

template<typename PointT>
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 308 of file voxel_grid.h.

template<typename PointT>
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 263 of file voxel_grid.h.

template<typename PointT>
std::string const pcl::VoxelGrid< PointT >::getFilterFieldName ( )
inline

Get the name of the field used for filtering.

Definition at line 400 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 421 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 441 of file voxel_grid.h.

template<typename PointT>
bool pcl::VoxelGrid< PointT >::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 450 of file voxel_grid.h.

template<typename PointT>
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).

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 365 of file voxel_grid.h.

template<typename PointT>
std::vector<int> pcl::VoxelGrid< PointT >::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 357 of file voxel_grid.h.

template<typename PointT>
Eigen::Vector3f pcl::VoxelGrid< PointT >::getLeafSize ( )
inline

Get the voxel grid leaf size.

Definition at line 251 of file voxel_grid.h.

template<typename PointT>
Eigen::Vector3i pcl::VoxelGrid< PointT >::getMaxBoxCoordinates ( )
inline

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

Definition at line 296 of file voxel_grid.h.

template<typename PointT>
Eigen::Vector3i pcl::VoxelGrid< PointT >::getMinBoxCoordinates ( )
inline

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

Definition at line 290 of file voxel_grid.h.

template<typename PointT>
unsigned int pcl::VoxelGrid< PointT >::getMinimumPointsNumberPerVoxel ( )
inline

Return the minimum number of points required for a voxel to be used.

Definition at line 274 of file voxel_grid.h.

template<typename PointT>
std::vector<int> pcl::VoxelGrid< PointT >::getNeighborCentroidIndices ( const PointT reference_point,
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]reference_pointthe coordinates of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in]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 333 of file voxel_grid.h.

Referenced by pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature().

template<typename PointT>
Eigen::Vector3i pcl::VoxelGrid< PointT >::getNrDivisions ( )
inline

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

Definition at line 302 of file voxel_grid.h.

template<typename PointT>
bool pcl::VoxelGrid< PointT >::getSaveLeafLayout ( )
inline

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

Definition at line 284 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 257 of file voxel_grid.h.

Referenced by pcl::CrfSegmentation< PointT >::createVoxelGrid(), and pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud().

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 393 of file voxel_grid.h.

Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter().

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 410 of file voxel_grid.h.

Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter().

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 432 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::setLeafSize ( const Eigen::Vector4f &  leaf_size)
inline
template<typename PointT>
void pcl::VoxelGrid< PointT >::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 239 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::setMinimumPointsNumberPerVoxel ( unsigned int  min_points_per_voxel)
inline

Set the minimum number of points required for a voxel to be used.

Parameters
[in]min_points_per_voxelthe minimum number of points for required for a voxel to be used

Definition at line 269 of file voxel_grid.h.

template<typename PointT>
void pcl::VoxelGrid< PointT >::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 280 of file voxel_grid.h.

Referenced by pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), and pcl::VoxelGridOcclusionEstimation< PointT >::VoxelGridOcclusionEstimation().

Member Data Documentation

template<typename PointT>
Eigen::Vector4i pcl::VoxelGrid< PointT >::div_b_
protected

Definition at line 472 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getNrDivisions().

template<typename PointT>
Eigen::Vector4i pcl::VoxelGrid< PointT >::divb_mul_
protected
template<typename PointT>
bool pcl::VoxelGrid< PointT >::downsample_all_data_
protected
template<typename PointT>
std::string pcl::VoxelGrid< PointT >::filter_field_name_
protected

The desired user filter field name.

Definition at line 475 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getFilterFieldName(), and pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterFieldName().

template<typename PointT>
double pcl::VoxelGrid< PointT >::filter_limit_max_
protected

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

Definition at line 481 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getFilterLimits(), and pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimits().

template<typename PointT>
double pcl::VoxelGrid< PointT >::filter_limit_min_
protected

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

Definition at line 478 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getFilterLimits(), and pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimits().

template<typename PointT>
bool pcl::VoxelGrid< PointT >::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 484 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getFilterLimitsNegative(), and pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimitsNegative().

template<typename PointT>
Eigen::Array4f pcl::VoxelGrid< PointT >::inverse_leaf_size_
protected
template<typename PointT>
std::vector<int> pcl::VoxelGrid< PointT >::leaf_layout_
protected
template<typename PointT>
Eigen::Vector4f pcl::VoxelGrid< PointT >::leaf_size_
protected
template<typename PointT>
Eigen::Vector4i pcl::VoxelGrid< PointT >::max_b_
protected
template<typename PointT>
Eigen::Vector4i pcl::VoxelGrid< PointT >::min_b_
protected
template<typename PointT>
unsigned int pcl::VoxelGrid< PointT >::min_points_per_voxel_
protected

Minimum number of points per voxel for the centroid to be computed.

Definition at line 487 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getMinimumPointsNumberPerVoxel(), and pcl::VoxelGrid< pcl::PointXYZRGBL >::setMinimumPointsNumberPerVoxel().

template<typename PointT>
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 466 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getSaveLeafLayout(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setSaveLeafLayout(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().


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