point_cloud_library / 1.12.1 / classpcl_1_1_voxel_grid_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html /

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

#include <pcl/filters/voxel_grid.h>

Public Member Functions

VoxelGrid ()
Empty constructor. More...
~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 () const
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 () const
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 () const
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 () const
Returns true if leaf layout information will to be saved for later access. More...
Eigen::Vector3i getMinBoxCoordinates () const
Get the minimum coordinates of the bounding box (after filtering is performed). More...
Eigen::Vector3i getMaxBoxCoordinates () const
Get the minimum coordinates of the bounding box (after filtering is performed). More...
Eigen::Vector3i getNrDivisions () const
Get the number of divisions along all 3 axes (after filtering is performed). More...
Eigen::Vector3i getDivisionMultiplier () const
Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). More...
int getCentroidIndex (float x, float y, float z) const
Returns the index in the resulting downsampled cloud of the specified point. More...
std::vector< int > getNeighborCentroidIndices (float x, float y, float z, const Eigen::MatrixXi &relative_coordinates) const
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 > getNeighborCentroidIndices (float x, float y, float z, const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > &relative_coordinates) const
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 () const
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) const
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). More...
int getCentroidIndexAt (const Eigen::Vector3i &ijk) const
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...
const std::string getFilterFieldName () const
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) const
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) const
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
bool getFilterLimitsNegative () const
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< pcl::PCLPointCloud2 >
Filter (bool extract_removed_indices=false)
Empty constructor. More...
const IndicesConstPtr getRemovedIndices () const
Get the point indices being removed. More...
void getRemovedIndices (PointIndices &pi)
Get the point indices being removed. More...
void filter (PCLPointCloud2 &output)
Calls the filtering method and returns the filtered dataset in output. More...
- Public Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
PCLBase ()
Empty constructor. More...
virtual ~PCLBase ()=default
destructor. More...
void setInputCloud (const PCLPointCloud2ConstPtr &cloud)
Provide a pointer to the input dataset. More...
const PCLPointCloud2ConstPtr getInputCloud () const
Get a pointer to the input point cloud dataset. More...
void setIndices (const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
void setIndices (const PointIndicesConstPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
const IndicesPtr getIndices () const
Get a pointer to the vector of indices used. More...

Protected Member Functions

void applyFilter (PCLPointCloud2 &output) override
Downsample a Point Cloud using a voxelized grid approach. More...
- Protected Member Functions inherited from pcl::Filter< pcl::PCLPointCloud2 >
const std::string & getClassName () const
Get a string representation of the name of this class. More...
- Protected Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
bool initCompute ()
bool deinitCompute ()

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< pcl::PCLPointCloud2 >
IndicesPtr removed_indices_
Indices of the points that are removed. More...
bool extract_removed_indices_
Set to true if we want to return the indices of the removed points. More...
std::string filter_name_
The filter name. More...
- Protected Attributes inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
PCLPointCloud2ConstPtr 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...
std::vector< uindex_t > field_sizes_
The size of each individual field. More...
index_t x_idx_
The x-y-z fields indices. More...
index_t y_idx_
index_t z_idx_
std::string x_field_name_
The desired x-y-z field names. More...
std::string y_field_name_
std::string z_field_name_

Additional Inherited Members

- Public Types inherited from pcl::Filter< pcl::PCLPointCloud2 >
using Ptr = shared_ptr< Filter< pcl::PCLPointCloud2 > >
using ConstPtr = shared_ptr< const Filter< pcl::PCLPointCloud2 > >
using PCLPointCloud2 = pcl::PCLPointCloud2
using PCLPointCloud2Ptr = PCLPointCloud2::Ptr
using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr
- Public Types inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
using PCLPointCloud2 = pcl::PCLPointCloud2
using PCLPointCloud2Ptr = PCLPointCloud2::Ptr
using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr
using PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr

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

Definition at line 510 of file voxel_grid.h.

Constructor & Destructor Documentation

VoxelGrid()

Empty constructor.

Definition at line 521 of file voxel_grid.h.

~VoxelGrid()

Destructor.

Definition at line 540 of file voxel_grid.h.

Member Function Documentation

applyFilter()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::applyFilter ( PCLPointCloud2 & output )
overrideprotectedvirtual

Downsample a Point Cloud using a voxelized grid approach.

Parameters
[out] output the resultant point cloud

Implements pcl::Filter< pcl::PCLPointCloud2 >.

getCentroidIndex()

int pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex ( float x,
float y,
float z
) const
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] x the X point coordinate to get the index at
[in] y the Y point coordinate to get the index at
[in] z the Z point coordinate to get the index at

Definition at line 643 of file voxel_grid.h.

getCentroidIndexAt()

int pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndexAt ( const Eigen::Vector3i & ijk ) const
inline

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

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

Definition at line 723 of file voxel_grid.h.

getDivisionMultiplier()

Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getDivisionMultiplier ( ) const
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 633 of file voxel_grid.h.

getDownsampleAllData()

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::getDownsampleAllData ( ) const
inline

Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ).

Definition at line 588 of file voxel_grid.h.

getFilterFieldName()

const std::string pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterFieldName ( ) const
inline

Get the name of the field used for filtering.

Definition at line 747 of file voxel_grid.h.

getFilterLimits()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimits ( double & limit_min,
double & limit_max
) const
inline

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

The default values are -FLT_MAX, FLT_MAX.

Parameters
[out] limit_min the minimum allowed field value
[out] limit_max the maximum allowed field value

Definition at line 768 of file voxel_grid.h.

getFilterLimitsNegative() [1/2]

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimitsNegative ( ) const
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 798 of file voxel_grid.h.

getFilterLimitsNegative() [2/2]

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimitsNegative ( bool & limit_negative ) const
inline

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

Parameters
[out] limit_negative true if data outside the interval [min; max] is to be returned, false otherwise
Deprecated:
Scheduled for removal in version 1 . 16 : "use bool getFilterLimitsNegative() instead"

Definition at line 789 of file voxel_grid.h.

getGridCoordinates()

Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getGridCoordinates ( float x,
float y,
float z
) const
inline

Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).

Parameters
[in] x the X point coordinate to get the (i, j, k) index at
[in] y the Y point coordinate to get the (i, j, k) index at
[in] z the Z point coordinate to get the (i, j, k) index at

Definition at line 712 of file voxel_grid.h.

getLeafLayout()

std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafLayout ( ) const
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 704 of file voxel_grid.h.

getLeafSize()

Eigen::Vector3f pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafSize ( ) const
inline

Get the voxel grid leaf size.

Definition at line 576 of file voxel_grid.h.

getMaxBoxCoordinates()

Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMaxBoxCoordinates ( ) const
inline

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

Definition at line 621 of file voxel_grid.h.

getMinBoxCoordinates()

Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMinBoxCoordinates ( ) const
inline

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

Definition at line 615 of file voxel_grid.h.

getMinimumPointsNumberPerVoxel()

unsigned int pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMinimumPointsNumberPerVoxel ( ) const
inline

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

Definition at line 599 of file voxel_grid.h.

getNeighborCentroidIndices() [1/2]

std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices ( float x,
float y,
float z,
const Eigen::MatrixXi & relative_coordinates
) const
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] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[out] 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 661 of file voxel_grid.h.

getNeighborCentroidIndices() [2/2]

std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices ( float x,
float y,
float z,
const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > & relative_coordinates
) const
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] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
[out] relative_coordinates vector 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 690 of file voxel_grid.h.

getNrDivisions()

Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNrDivisions ( ) const
inline

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

Definition at line 627 of file voxel_grid.h.

getSaveLeafLayout()

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::getSaveLeafLayout ( ) const
inline

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

Definition at line 609 of file voxel_grid.h.

setDownsampleAllData()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setDownsampleAllData ( bool downsample )
inline

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

Parameters
[in] downsample the new value (true/false)

Definition at line 582 of file voxel_grid.h.

setFilterFieldName()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::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_name the name of the field that contains values used for filtering

Definition at line 740 of file voxel_grid.h.

setFilterLimits()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::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_min the minimum allowed field value
[in] limit_max the maximum allowed field value

Definition at line 757 of file voxel_grid.h.

setFilterLimitsNegative()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::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_negative return data inside the interval (false) or outside (true)

Definition at line 779 of file voxel_grid.h.

setLeafSize() [1/2]

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize ( const Eigen::Vector4f & leaf_size )
inline

Set the voxel grid leaf size.

Parameters
[in] leaf_size the voxel grid leaf size

Definition at line 548 of file voxel_grid.h.

setLeafSize() [2/2]

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize ( float lx,
float ly,
float lz
)
inline

Set the voxel grid leaf size.

Parameters
[in] lx the leaf size for X
[in] ly the leaf size for Y
[in] lz the leaf size for Z

Definition at line 564 of file voxel_grid.h.

setMinimumPointsNumberPerVoxel()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::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_voxel the minimum number of points for required for a voxel to be used

Definition at line 594 of file voxel_grid.h.

setSaveLeafLayout()

void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setSaveLeafLayout ( bool save_leaf_layout )
inline

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

Parameters
[in] save_leaf_layout the new value (true/false)

Definition at line 605 of file voxel_grid.h.

Member Data Documentation

div_b_

Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::div_b_
protected

Definition at line 826 of file voxel_grid.h.

divb_mul_

Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::divb_mul_
protected

Definition at line 826 of file voxel_grid.h.

downsample_all_data_

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::downsample_all_data_
protected

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

Definition at line 811 of file voxel_grid.h.

filter_field_name_

std::string pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_field_name_
protected

The desired user filter field name.

Definition at line 829 of file voxel_grid.h.

filter_limit_max_

double pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_limit_max_
protected

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

Definition at line 835 of file voxel_grid.h.

filter_limit_min_

double pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_limit_min_
protected

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

Definition at line 832 of file voxel_grid.h.

filter_limit_negative_

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::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 838 of file voxel_grid.h.

inverse_leaf_size_

Eigen::Array4f pcl::VoxelGrid< pcl::PCLPointCloud2 >::inverse_leaf_size_
protected

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

Definition at line 808 of file voxel_grid.h.

leaf_layout_

std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::leaf_layout_
protected

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

Definition at line 821 of file voxel_grid.h.

leaf_size_

Eigen::Vector4f pcl::VoxelGrid< pcl::PCLPointCloud2 >::leaf_size_
protected

The size of a leaf.

Definition at line 805 of file voxel_grid.h.

max_b_

Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::max_b_
protected

Definition at line 826 of file voxel_grid.h.

min_b_

Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::min_b_
protected

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

Definition at line 826 of file voxel_grid.h.

min_points_per_voxel_

unsigned int pcl::VoxelGrid< pcl::PCLPointCloud2 >::min_points_per_voxel_
protected

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

Definition at line 841 of file voxel_grid.h.

save_leaf_layout_

bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::save_leaf_layout_
protected

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

Definition at line 816 of file voxel_grid.h.


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_voxel_grid_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html