VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
#include <voxel_grid.h>
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 (PCLPointCloud2 &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 pcl::PCLPointCloud2 | PCLPointCloud2 |
typedef PCLPointCloud2::ConstPtr | PCLPointCloud2ConstPtr |
typedef PCLPointCloud2::Ptr | PCLPointCloud2Ptr |
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.
Definition at line 496 of file voxel_grid.h.
typedef pcl::PCLPointCloud2 pcl::VoxelGrid< pcl::PCLPointCloud2 >::PCLPointCloud2 [private] |
Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.
Definition at line 501 of file voxel_grid.h.
typedef PCLPointCloud2::ConstPtr pcl::VoxelGrid< pcl::PCLPointCloud2 >::PCLPointCloud2ConstPtr [private] |
Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.
Definition at line 503 of file voxel_grid.h.
typedef PCLPointCloud2::Ptr pcl::VoxelGrid< pcl::PCLPointCloud2 >::PCLPointCloud2Ptr [private] |
Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.
Definition at line 502 of file voxel_grid.h.
pcl::VoxelGrid< pcl::PCLPointCloud2 >::VoxelGrid | ( | ) | [inline] |
Empty constructor.
Definition at line 507 of file voxel_grid.h.
virtual pcl::VoxelGrid< pcl::PCLPointCloud2 >::~VoxelGrid | ( | ) | [inline, virtual] |
Destructor.
Definition at line 526 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::applyFilter | ( | PCLPointCloud2 & | output | ) | [protected, virtual] |
Downsample a Point Cloud using a voxelized grid approach.
[out] | output | the resultant point cloud |
Implements pcl::Filter< pcl::PCLPointCloud2 >.
Definition at line 177 of file filters/src/voxel_grid.cpp.
int pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex | ( | float | x, |
float | y, | ||
float | z | ||
) | [inline] |
Returns the index in the resulting downsampled cloud of the specified point.
[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 618 of file voxel_grid.h.
int pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndexAt | ( | const Eigen::Vector3i & | ijk | ) | [inline] |
Returns the index in the downsampled cloud corresponding to a given set of coordinates.
[in] | ijk | the coordinates (i,j,k) in the grid (-1 if empty) |
Definition at line 698 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::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 608 of file voxel_grid.h.
bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::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 574 of file voxel_grid.h.
std::string const pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterFieldName | ( | ) | [inline] |
Get the name of the field used for filtering.
Definition at line 722 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::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.
[out] | limit_min | the minimum allowed field value |
[out] | limit_max | the maximum allowed field value |
Definition at line 743 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimitsNegative | ( | bool & | limit_negative | ) | [inline] |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
[out] | limit_negative | true if data outside the interval [min; max] is to be returned, false otherwise |
Definition at line 763 of file voxel_grid.h.
bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimitsNegative | ( | ) | [inline] |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 772 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getGridCoordinates | ( | float | x, |
float | y, | ||
float | z | ||
) | [inline] |
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
[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 687 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafLayout | ( | ) | [inline] |
Returns the layout of the leafs for fast access to cells relative to current position.
Definition at line 679 of file voxel_grid.h.
Eigen::Vector3f pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafSize | ( | ) | [inline] |
Get the voxel grid leaf size.
Definition at line 562 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMaxBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 596 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMinBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 590 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::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).
[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 |
Definition at line 636 of file voxel_grid.h.
std::vector<int> pcl::VoxelGrid< pcl::PCLPointCloud2 >::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).
[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 |
Definition at line 665 of file voxel_grid.h.
Eigen::Vector3i pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNrDivisions | ( | ) | [inline] |
Get the number of divisions along all 3 axes (after filtering is performed).
Definition at line 602 of file voxel_grid.h.
bool pcl::VoxelGrid< pcl::PCLPointCloud2 >::getSaveLeafLayout | ( | ) | [inline] |
Returns true if leaf layout information will to be saved for later access.
Definition at line 584 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setDownsampleAllData | ( | bool | downsample | ) | [inline] |
Set to true if all fields need to be downsampled, or false if just XYZ.
[in] | downsample | the new value (true/false) |
Definition at line 568 of file voxel_grid.h.
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.
[in] | field_name | the name of the field that contains values used for filtering |
Definition at line 715 of file voxel_grid.h.
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.
[in] | limit_min | the minimum allowed field value |
[in] | limit_max | the maximum allowed field value |
Definition at line 732 of file voxel_grid.h.
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.
[in] | limit_negative | return data inside the interval (false) or outside (true) |
Definition at line 754 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize | ( | const Eigen::Vector4f & | leaf_size | ) | [inline] |
Set the voxel grid leaf size.
[in] | leaf_size | the voxel grid leaf size |
Definition at line 534 of file voxel_grid.h.
void pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize | ( | float | lx, |
float | ly, | ||
float | lz | ||
) | [inline] |
Set the voxel grid leaf size.
[in] | lx | the leaf size for X |
[in] | ly | the leaf size for Y |
[in] | lz | the leaf size for Z |
Definition at line 550 of file voxel_grid.h.
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.
[in] | save_leaf_layout | the new value (true/false) |
Definition at line 580 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::div_b_ [protected] |
Definition at line 800 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::divb_mul_ [protected] |
Definition at line 800 of file voxel_grid.h.
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 785 of file voxel_grid.h.
std::string pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_field_name_ [protected] |
The desired user filter field name.
Definition at line 803 of file voxel_grid.h.
double pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_limit_max_ [protected] |
The maximum allowed filter value a point will be considered from.
Definition at line 809 of file voxel_grid.h.
double pcl::VoxelGrid< pcl::PCLPointCloud2 >::filter_limit_min_ [protected] |
The minimum allowed filter value a point will be considered from.
Definition at line 806 of file voxel_grid.h.
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 812 of file voxel_grid.h.
Eigen::Array4f pcl::VoxelGrid< pcl::PCLPointCloud2 >::inverse_leaf_size_ [protected] |
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Definition at line 782 of file voxel_grid.h.
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 795 of file voxel_grid.h.
Eigen::Vector4f pcl::VoxelGrid< pcl::PCLPointCloud2 >::leaf_size_ [protected] |
The size of a leaf.
Definition at line 779 of file voxel_grid.h.
Eigen::Vector4i pcl::VoxelGrid< pcl::PCLPointCloud2 >::max_b_ [protected] |
Definition at line 800 of file voxel_grid.h.
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 800 of file voxel_grid.h.
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 790 of file voxel_grid.h.