|
Point Cloud Library (PCL)
1.5.1
|
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
#include <pcl/filters/voxel_grid.h>


Public Types | |
| typedef boost::shared_ptr < Filter< PointT > > | Ptr |
| typedef boost::shared_ptr < const Filter< PointT > > | ConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
Public Member Functions | |
| VoxelGrid () | |
| Empty constructor. | |
| virtual | ~VoxelGrid () |
| Destructor. | |
| 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. | |
| Eigen::Vector3f | getLeafSize () |
| Get the voxel grid leaf size. | |
| void | setDownsampleAllData (bool downsample) |
| Set to true if all fields need to be downsampled, or false if just XYZ. | |
| bool | getDownsampleAllData () |
| Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). | |
| void | setSaveLeafLayout (bool save_leaf_layout) |
| Set to true if leaf layout information needs to be saved for later access. | |
| bool | getSaveLeafLayout () |
| Returns true if leaf layout information will to be saved for later access. | |
| Eigen::Vector3i | getMinBoxCoordinates () |
| Get the minimum coordinates of the bounding box (after filtering is performed). | |
| Eigen::Vector3i | getMaxBoxCoordinates () |
| Get the minimum coordinates of the bounding box (after filtering is performed). | |
| Eigen::Vector3i | getNrDivisions () |
| Get the number of divisions along all 3 axes (after filtering is performed). | |
| Eigen::Vector3i | getDivisionMultiplier () |
| Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). | |
| int | getCentroidIndex (const PointT &p) |
| Returns the index in the resulting downsampled cloud of the specified point. | |
| 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). | |
| std::vector< int > | getLeafLayout () |
| Returns the layout of the leafs for fast access to cells relative to current position. | |
| Eigen::Vector3i | getGridCoordinates (float x, float y, float z) |
| Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). | |
| int | getCentroidIndexAt (const Eigen::Vector3i &ijk) |
| Returns the index in the downsampled cloud corresponding to a given set of coordinates. | |
| void | setFilterFieldName (const std::string &field_name) |
| Provide the name of the field to be used for filtering data. | |
| std::string const | getFilterFieldName () |
| Get the name of the field used for filtering. | |
| void | setFilterLimits (const double &limit_min, const double &limit_max) |
| Set the field filter limits. | |
| void | getFilterLimits (double &limit_min, double &limit_max) |
| Get the field filter limits (min/max) set by the user. | |
| void | setFilterLimitsNegative (const bool limit_negative) |
| Set to true if we want to return the data outside the interval specified by setFilterLimits (min, 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). | |
| IndicesConstPtr const | getRemovedIndices () |
| Get the point indices being removed. | |
| void | filter (PointCloud &output) |
| Calls the filtering method and returns the filtered dataset in output. | |
| virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
| Provide a pointer to the input dataset. | |
| PointCloudConstPtr const | getInputCloud () |
| Get a pointer to the input point cloud dataset. | |
| void | setIndices (const IndicesPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| void | setIndices (const IndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| void | setIndices (const PointIndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| 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. | |
| IndicesPtr const | getIndices () |
| Get a pointer to the vector of indices used. | |
| const PointT & | operator[] (size_t pos) |
| Override PointCloud operator[] to shorten code. | |
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 161 of file voxel_grid.h.
typedef boost::shared_ptr< const Filter<PointT> > pcl::Filter< PointT >::ConstPtr [inherited] |
typedef PointIndices::ConstPtr pcl::PCLBase< PointT >::PointIndicesConstPtr [inherited] |
Reimplemented in pcl::EuclideanClusterExtraction< PointT >, pcl::ExtractPolygonalPrismData< PointT >, pcl::SegmentDifferences< PointT >, pcl::LabeledEuclideanClusterExtraction< PointT >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::PCA< PointT >.
Definition at line 79 of file pcl_base.h.
typedef PointIndices::Ptr pcl::PCLBase< PointT >::PointIndicesPtr [inherited] |
Reimplemented in pcl::EuclideanClusterExtraction< PointT >, pcl::ExtractPolygonalPrismData< PointT >, pcl::SegmentDifferences< PointT >, pcl::LabeledEuclideanClusterExtraction< PointT >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::PCA< PointT >.
Definition at line 78 of file pcl_base.h.
typedef boost::shared_ptr< Filter<PointT> > pcl::Filter< PointT >::Ptr [inherited] |
| pcl::VoxelGrid< PointT >::VoxelGrid | ( | ) | [inline] |
Empty constructor.
Definition at line 175 of file voxel_grid.h.
| virtual pcl::VoxelGrid< PointT >::~VoxelGrid | ( | ) | [inline, virtual] |
Destructor.
Definition at line 188 of file voxel_grid.h.
| void pcl::Filter< PointT >::filter | ( | PointCloud & | output | ) | [inline, inherited] |
Calls the filtering method and returns the filtered dataset in output.
| [out] | output | the resultant filtered point cloud dataset |
Reimplemented in pcl::FilterIndices< PointT >.
| int pcl::VoxelGrid< PointT >::getCentroidIndex | ( | const PointT & | p | ) | [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 281 of file voxel_grid.h.
| int pcl::VoxelGrid< PointT >::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 332 of file voxel_grid.h.
| 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 270 of file voxel_grid.h.
| 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 236 of file voxel_grid.h.
| std::string const pcl::VoxelGrid< PointT >::getFilterFieldName | ( | ) | [inline] |
Get the name of the field used for filtering.
Definition at line 356 of file voxel_grid.h.
| 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.
| [out] | limit_min | the minimum allowed field value |
| [out] | limit_max | the maximum allowed field value |
Definition at line 377 of file voxel_grid.h.
| 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).
| [out] | limit_negative | true if data outside the interval [min; max] is to be returned, false otherwise |
Definition at line 397 of file voxel_grid.h.
| bool pcl::VoxelGrid< PointT >::getFilterLimitsNegative | ( | ) | [inline] |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 406 of file voxel_grid.h.
| 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).
| [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 323 of file voxel_grid.h.
| IndicesPtr const pcl::PCLBase< PointT >::getIndices | ( | ) | [inline, inherited] |
Get a pointer to the vector of indices used.
Definition at line 190 of file pcl_base.h.
| PointCloudConstPtr const pcl::PCLBase< PointT >::getInputCloud | ( | ) | [inline, inherited] |
Get a pointer to the input point cloud dataset.
Definition at line 107 of file pcl_base.h.
| std::vector<int> pcl::VoxelGrid< PointT >::getLeafLayout | ( | ) | [inline] |
Returns the layout of the leafs for fast access to cells relative to current position.
Definition at line 315 of file voxel_grid.h.
| Eigen::Vector3f pcl::VoxelGrid< PointT >::getLeafSize | ( | ) | [inline] |
Get the voxel grid leaf size.
Definition at line 224 of file voxel_grid.h.
| Eigen::Vector3i pcl::VoxelGrid< PointT >::getMaxBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 258 of file voxel_grid.h.
| Eigen::Vector3i pcl::VoxelGrid< PointT >::getMinBoxCoordinates | ( | ) | [inline] |
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition at line 252 of file voxel_grid.h.
| 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).
| [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 293 of file voxel_grid.h.
| Eigen::Vector3i pcl::VoxelGrid< PointT >::getNrDivisions | ( | ) | [inline] |
Get the number of divisions along all 3 axes (after filtering is performed).
Definition at line 264 of file voxel_grid.h.
| IndicesConstPtr const pcl::Filter< PointT >::getRemovedIndices | ( | ) | [inline, inherited] |
| bool pcl::VoxelGrid< PointT >::getSaveLeafLayout | ( | ) | [inline] |
Returns true if leaf layout information will to be saved for later access.
Definition at line 246 of file voxel_grid.h.
| const PointT& pcl::PCLBase< PointT >::operator[] | ( | size_t | pos | ) | [inline, inherited] |
Override PointCloud operator[] to shorten code.
| pos | position in indices_ vector |
Definition at line 197 of file pcl_base.h.
| void pcl::VoxelGrid< PointT >::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 230 of file voxel_grid.h.
| 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.
| [in] | field_name | the name of the field that contains values used for filtering |
Definition at line 349 of file voxel_grid.h.
| 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.
| [in] | limit_min | the minimum allowed field value |
| [in] | limit_max | the maximum allowed field value |
Definition at line 366 of file voxel_grid.h.
| 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.
| [in] | limit_negative | return data inside the interval (false) or outside (true) |
Definition at line 388 of file voxel_grid.h.
| void pcl::PCLBase< PointT >::setIndices | ( | const IndicesPtr & | indices | ) | [inline, inherited] |
Provide a pointer to the vector of indices that represents the input data.
| indices | a pointer to the vector of indices that represents the input data. |
Definition at line 113 of file pcl_base.h.
| void pcl::PCLBase< PointT >::setIndices | ( | const IndicesConstPtr & | indices | ) | [inline, inherited] |
Provide a pointer to the vector of indices that represents the input data.
| indices | a pointer to the vector of indices that represents the input data. |
Definition at line 124 of file pcl_base.h.
| void pcl::PCLBase< PointT >::setIndices | ( | const PointIndicesConstPtr & | indices | ) | [inline, inherited] |
Provide a pointer to the vector of indices that represents the input data.
| indices | a pointer to the vector of indices that represents the input data. |
Definition at line 135 of file pcl_base.h.
| void pcl::PCLBase< PointT >::setIndices | ( | size_t | row_start, |
| size_t | col_start, | ||
| size_t | nb_rows, | ||
| size_t | nb_cols | ||
| ) | [inline, inherited] |
Set the indices for the points laying within an interest region of the point cloud.
| row_start | the offset on rows |
| col_start | the offset on columns |
| nb_rows | the number of rows to be considered row_start included |
| nb_cols | the number of columns to be considered col_start included |
Definition at line 151 of file pcl_base.h.
| virtual void pcl::PCLBase< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual, inherited] |
Provide a pointer to the input dataset.
| cloud | the const boost shared pointer to a PointCloud message |
Reimplemented in pcl::PCA< PointT >, and pcl::GeneralizedIterativeClosestPoint< PointT, PointT >.
Definition at line 103 of file pcl_base.h.
| void pcl::VoxelGrid< PointT >::setLeafSize | ( | const Eigen::Vector4f & | leaf_size | ) | [inline] |
Set the voxel grid leaf size.
| [in] | leaf_size | the voxel grid leaf size |
Definition at line 196 of file voxel_grid.h.
| void pcl::VoxelGrid< PointT >::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 212 of file voxel_grid.h.
| void pcl::VoxelGrid< PointT >::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 242 of file voxel_grid.h.
1.8.0