Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | 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 >:
+ Collaboration diagram for pcl::VoxelGrid< PointT >:

Public Types

using Ptr = shared_ptr< VoxelGrid< PointT > >
 
using ConstPtr = shared_ptr< const VoxelGrid< PointT > >
 
- Public Types inherited from pcl::Filter< PointT >
using Ptr = shared_ptr< Filter< PointT > >
 
using ConstPtr = shared_ptr< const Filter< PointT > >
 
using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
- Public Types inherited from pcl::PCLBase< PointT >
using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointIndicesPtr = PointIndices::Ptr
 
using PointIndicesConstPtr = PointIndices::ConstPtr
 

Public Member Functions

PCL_MAKE_ALIGNED_OPERATOR_NEW VoxelGrid ()
 Empty constructor. More...
 
 ~VoxelGrid () override=default
 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 (const PointT &p) const
 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) 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...
 
std::string const 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< PointT >
 Filter (bool extract_removed_indices=false)
 Empty constructor. More...
 
IndicesConstPtr const getRemovedIndices () const
 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 ()=default
 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 (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr 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[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Types

using PointCloud = typename Filter< PointT >::PointCloud
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using FieldList = typename pcl::traits::fieldList< PointT >::type
 

Protected Member Functions

void applyFilter (PointCloud &output) override
 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_ {true}
 Set to true if all fields need to be downsampled, or false if just XYZ. More...
 
bool save_leaf_layout_ {false}
 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_ {std::numeric_limits<float>::lowest()}
 The minimum allowed filter value a point will be considered from. More...
 
double filter_limit_max_ {std::numeric_limits<float>::max()}
 The maximum allowed filter value a point will be considered from. More...
 
bool filter_limit_negative_ {false}
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). More...
 
unsigned int min_points_per_voxel_ {0}
 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...
 

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

Member Typedef Documentation

◆ ConstPtr

template<typename PointT >
using pcl::VoxelGrid< PointT >::ConstPtr = shared_ptr<const VoxelGrid<PointT> >

Definition at line 191 of file voxel_grid.h.

◆ FieldList

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

Definition at line 482 of file voxel_grid.h.

◆ PointCloud

template<typename PointT >
using pcl::VoxelGrid< PointT >::PointCloud = typename Filter<PointT>::PointCloud
protected

Definition at line 184 of file voxel_grid.h.

◆ PointCloudConstPtr

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

Definition at line 186 of file voxel_grid.h.

◆ PointCloudPtr

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

Definition at line 185 of file voxel_grid.h.

◆ Ptr

template<typename PointT >
using pcl::VoxelGrid< PointT >::Ptr = shared_ptr<VoxelGrid<PointT> >

Definition at line 190 of file voxel_grid.h.

Constructor & Destructor Documentation

◆ VoxelGrid()

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

Empty constructor.

Definition at line 196 of file voxel_grid.h.

References pcl::Filter< PointT >::filter_name_.

◆ ~VoxelGrid()

template<typename PointT >
pcl::VoxelGrid< PointT >::~VoxelGrid ( )
overridedefault

Destructor.

Member Function Documentation

◆ applyFilter()

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

◆ getCentroidIndex()

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

Definition at line 310 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::divb_mul_, pcl::VoxelGrid< PointT >::inverse_leaf_size_, pcl::VoxelGrid< PointT >::leaf_layout_, and pcl::VoxelGrid< PointT >::min_b_.

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

◆ getCentroidIndexAt()

template<typename PointT >
int pcl::VoxelGrid< PointT >::getCentroidIndexAt ( const Eigen::Vector3i &  ijk) const
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 367 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::divb_mul_, pcl::VoxelGrid< PointT >::leaf_layout_, and pcl::VoxelGrid< PointT >::min_b_.

◆ getDivisionMultiplier()

template<typename PointT >
Eigen::Vector3i pcl::VoxelGrid< PointT >::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 299 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::divb_mul_.

◆ getDownsampleAllData()

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

References pcl::VoxelGrid< PointT >::downsample_all_data_.

◆ getFilterFieldName()

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

Get the name of the field used for filtering.

Definition at line 391 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::filter_field_name_.

◆ getFilterLimits()

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

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

The default values are std::numeric_limits<float>::lowest(), std::numeric_limits<float>::max().

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

Definition at line 413 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::filter_limit_max_, and pcl::VoxelGrid< PointT >::filter_limit_min_.

◆ getFilterLimitsNegative() [1/2]

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

References pcl::VoxelGrid< PointT >::filter_limit_negative_.

◆ getFilterLimitsNegative() [2/2]

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

References pcl::VoxelGrid< PointT >::filter_limit_negative_.

◆ getGridCoordinates()

template<typename PointT >
Eigen::Vector3i pcl::VoxelGrid< PointT >::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]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 356 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::inverse_leaf_size_.

◆ getLeafLayout()

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

References pcl::VoxelGrid< PointT >::leaf_layout_.

◆ getLeafSize()

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

Get the voxel grid leaf size.

Definition at line 242 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::leaf_size_.

◆ getMaxBoxCoordinates()

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

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

Definition at line 287 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::max_b_.

◆ getMinBoxCoordinates()

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

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

Definition at line 281 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::min_b_.

◆ getMinimumPointsNumberPerVoxel()

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

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

Definition at line 265 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::min_points_per_voxel_.

◆ getNeighborCentroidIndices()

template<typename PointT >
std::vector<int> pcl::VoxelGrid< PointT >::getNeighborCentroidIndices ( const PointT reference_point,
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]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 324 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::divb_mul_, pcl::VoxelGrid< PointT >::inverse_leaf_size_, pcl::VoxelGrid< PointT >::leaf_layout_, pcl::VoxelGrid< PointT >::max_b_, and pcl::VoxelGrid< PointT >::min_b_.

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

◆ getNrDivisions()

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

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

Definition at line 293 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::div_b_.

◆ getSaveLeafLayout()

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

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

Definition at line 275 of file voxel_grid.h.

References pcl::VoxelGrid< PointT >::save_leaf_layout_.

◆ setDownsampleAllData()

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

References pcl::VoxelGrid< PointT >::downsample_all_data_.

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

◆ setFilterFieldName()

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

References pcl::VoxelGrid< PointT >::filter_field_name_.

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

◆ setFilterLimits()

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

References pcl::VoxelGrid< PointT >::filter_limit_max_, and pcl::VoxelGrid< PointT >::filter_limit_min_.

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

◆ setFilterLimitsNegative()

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

References pcl::VoxelGrid< PointT >::filter_limit_negative_.

◆ setLeafSize() [1/2]

template<typename PointT >
void pcl::VoxelGrid< PointT >::setLeafSize ( const Eigen::Vector4f &  leaf_size)
inline

◆ setLeafSize() [2/2]

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

References pcl::VoxelGrid< PointT >::inverse_leaf_size_, and pcl::VoxelGrid< PointT >::leaf_size_.

◆ setMinimumPointsNumberPerVoxel()

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

References pcl::VoxelGrid< PointT >::min_points_per_voxel_.

◆ setSaveLeafLayout()

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

References pcl::VoxelGrid< PointT >::save_leaf_layout_.

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

Member Data Documentation

◆ div_b_

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

Definition at line 465 of file voxel_grid.h.

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

◆ divb_mul_

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

◆ downsample_all_data_

template<typename PointT >
bool pcl::VoxelGrid< PointT >::downsample_all_data_ {true}
protected

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

Definition at line 456 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< PointT >::getDownsampleAllData(), pcl::VoxelGrid< PointT >::setDownsampleAllData(), and pcl::VoxelGridCovariance< PointT >::VoxelGridCovariance().

◆ filter_field_name_

template<typename PointT >
std::string pcl::VoxelGrid< PointT >::filter_field_name_
protected

The desired user filter field name.

Definition at line 468 of file voxel_grid.h.

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

◆ filter_limit_max_

template<typename PointT >
double pcl::VoxelGrid< PointT >::filter_limit_max_ {std::numeric_limits<float>::max()}
protected

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

Definition at line 474 of file voxel_grid.h.

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

◆ filter_limit_min_

template<typename PointT >
double pcl::VoxelGrid< PointT >::filter_limit_min_ {std::numeric_limits<float>::lowest()}
protected

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

Definition at line 471 of file voxel_grid.h.

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

◆ filter_limit_negative_

template<typename PointT >
bool pcl::VoxelGrid< PointT >::filter_limit_negative_ {false}
protected

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

Default: false.

Definition at line 477 of file voxel_grid.h.

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

◆ inverse_leaf_size_

template<typename PointT >
Eigen::Array4f pcl::VoxelGrid< PointT >::inverse_leaf_size_
protected

◆ leaf_layout_

template<typename PointT >
std::vector<int> pcl::VoxelGrid< PointT >::leaf_layout_
protected

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

Definition at line 462 of file voxel_grid.h.

Referenced by pcl::VoxelGrid< PointT >::getCentroidIndex(), pcl::VoxelGrid< PointT >::getCentroidIndexAt(), pcl::VoxelGrid< PointT >::getLeafLayout(), and pcl::VoxelGrid< PointT >::getNeighborCentroidIndices().

◆ leaf_size_

template<typename PointT >
Eigen::Vector4f pcl::VoxelGrid< PointT >::leaf_size_
protected

◆ max_b_

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

◆ min_b_

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

◆ min_points_per_voxel_

template<typename PointT >
unsigned int pcl::VoxelGrid< PointT >::min_points_per_voxel_ {0}
protected

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

Definition at line 480 of file voxel_grid.h.

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

◆ save_leaf_layout_

template<typename PointT >
bool pcl::VoxelGrid< PointT >::save_leaf_layout_ {false}
protected

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

Definition at line 459 of file voxel_grid.h.

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


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