Point Cloud Library (PCL)
1.7.2
|
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... | |
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... | |
![]() | |
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... | |
![]() | |
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 PointT & | operator[] (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... | |
![]() | |
const std::string & | getClassName () const |
Get a string representation of the name of this class. More... | |
![]() | |
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... | |
![]() | |
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... | |
![]() | |
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 | |
![]() | |
typedef boost::shared_ptr< Filter< PointT > > | Ptr |
typedef boost::shared_ptr< const Filter< PointT > > | ConstPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
![]() | |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef boost::shared_ptr< PointIndices > | PointIndicesPtr |
typedef boost::shared_ptr< PointIndices const > | PointIndicesConstPtr |
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 178 of file voxel_grid.h.
|
protected |
Definition at line 190 of file voxel_grid.h.
|
protected |
Definition at line 489 of file voxel_grid.h.
|
protected |
Definition at line 186 of file voxel_grid.h.
|
protected |
Definition at line 188 of file voxel_grid.h.
|
protected |
Definition at line 187 of file voxel_grid.h.
|
protected |
Definition at line 189 of file voxel_grid.h.
|
inline |
Empty constructor.
Definition at line 195 of file voxel_grid.h.
|
inlinevirtual |
Destructor.
Definition at line 215 of file voxel_grid.h.
|
protectedvirtual |
Downsample a Point Cloud using a voxelized grid approach.
[out] | output | the resultant point cloud message |
Implements pcl::Filter< PointT >.
Reimplemented in pcl::VoxelGridCovariance< PointT >, and pcl::VoxelGridCovariance< PointTarget >.
Definition at line 213 of file voxel_grid.hpp.
References pcl::getFieldIndex(), pcl::PointCloud< PointT >::height, cloud_point_index_idx::idx, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::points, and pcl::PointCloud< PointT >::width.
|
inline |
Returns the index in the resulting downsampled cloud of the specified point.
[in] | p | the point to get the index at |
Definition at line 319 of file voxel_grid.h.
Referenced by pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().
|
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 376 of file voxel_grid.h.
|
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.
|
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.
|
inline |
Get the name of the field used for filtering.
Definition at line 400 of file voxel_grid.h.
|
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 421 of file voxel_grid.h.
|
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 441 of file voxel_grid.h.
|
inline |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 450 of file voxel_grid.h.
|
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 365 of file voxel_grid.h.
|
inline |
Returns the layout of the leafs for fast access to cells relative to current position.
Definition at line 357 of file voxel_grid.h.
|
inline |
Get the voxel grid leaf size.
Definition at line 251 of file voxel_grid.h.
|
inline |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 296 of file voxel_grid.h.
|
inline |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 290 of file voxel_grid.h.
|
inline |
Return the minimum number of points required for a voxel to be used.
Definition at line 274 of file voxel_grid.h.
|
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] | reference_point | the coordinates of the reference point (corresponding cell is allowed to be empty/out of bounds) |
[in] | relative_coordinates | matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell |
Definition at line 333 of file voxel_grid.h.
|
inline |
Get the number of divisions along all 3 axes (after filtering is performed).
Definition at line 302 of file voxel_grid.h.
|
inline |
Returns true if leaf layout information will to be saved for later access.
Definition at line 284 of file voxel_grid.h.
|
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 257 of file voxel_grid.h.
Referenced by pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud().
|
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 393 of file voxel_grid.h.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter().
|
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 410 of file voxel_grid.h.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter().
|
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 432 of file voxel_grid.h.
|
inline |
Set the voxel grid leaf size.
[in] | leaf_size | the voxel grid leaf size |
Definition at line 223 of file voxel_grid.h.
Referenced by pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::init(), pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), and pcl::GlobalHypothesesVerification< ModelT, SceneT >::verify().
|
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 239 of file voxel_grid.h.
|
inline |
Set the minimum number of points required for a voxel to be used.
[in] | min_points_per_voxel | the minimum number of points for required for a voxel to be used |
Definition at line 269 of file voxel_grid.h.
|
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 280 of file voxel_grid.h.
Referenced by pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), and pcl::VoxelGridOcclusionEstimation< PointT >::VoxelGridOcclusionEstimation().
|
protected |
Definition at line 472 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getNrDivisions(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNrDivisions().
|
protected |
Definition at line 472 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndex(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndexAt(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndexAt(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getDivisionMultiplier(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getDivisionMultiplier(), pcl::VoxelGridCovariance< PointTarget >::getLeaf(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getNeighborCentroidIndices(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices().
|
protected |
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition at line 463 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getDownsampleAllData(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getDownsampleAllData(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setDownsampleAllData(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::setDownsampleAllData(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
protected |
The desired user filter field name.
Definition at line 475 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getFilterFieldName(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterFieldName(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterFieldName(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setFilterFieldName().
|
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(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimits(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimits(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setFilterLimits().
|
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(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimits(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimits(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setFilterLimits().
|
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(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getFilterLimitsNegative(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setFilterLimitsNegative(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setFilterLimitsNegative().
|
protected |
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Definition at line 460 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndex(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getGridCoordinates(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getGridCoordinates(), pcl::VoxelGridOcclusionEstimation< PointT >::getGridCoordinatesRound(), pcl::VoxelGridCovariance< PointTarget >::getLeaf(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getNeighborCentroidIndices(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setLeafSize(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize().
|
protected |
The leaf layout information for fast access to cells relative to current position.
Definition at line 469 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndex(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndexAt(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndexAt(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getLeafLayout(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafLayout(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getNeighborCentroidIndices(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices().
|
protected |
The size of a leaf.
Definition at line 457 of file voxel_grid.h.
Referenced by pcl::VoxelGridOcclusionEstimation< PointT >::getCentroidCoordinate(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getLeafSize(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getLeafSize(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setLeafSize(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::setLeafSize(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
protected |
Definition at line 472 of file voxel_grid.h.
Referenced by pcl::VoxelGrid< pcl::PointXYZRGBL >::getMaxBoxCoordinates(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMaxBoxCoordinates(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getNeighborCentroidIndices(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
protected |
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Definition at line 472 of file voxel_grid.h.
Referenced by pcl::VoxelGridOcclusionEstimation< PointT >::getCentroidCoordinate(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndex(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndex(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getCentroidIndexAt(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getCentroidIndexAt(), pcl::VoxelGridCovariance< PointTarget >::getLeaf(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getMinBoxCoordinates(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMinBoxCoordinates(), pcl::VoxelGrid< pcl::PointXYZRGBL >::getNeighborCentroidIndices(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getNeighborCentroidIndices(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
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(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::getMinimumPointsNumberPerVoxel(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setMinimumPointsNumberPerVoxel(), and pcl::VoxelGrid< pcl::PCLPointCloud2 >::setMinimumPointsNumberPerVoxel().
|
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::PCLPointCloud2 >::getSaveLeafLayout(), pcl::VoxelGrid< pcl::PointXYZRGBL >::setSaveLeafLayout(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::setSaveLeafLayout(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().