Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Types
pcl::ApproximateVoxelGrid< PointT > Class Template Reference

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

#include <approximate_voxel_grid.h>

Inheritance diagram for pcl::ApproximateVoxelGrid< PointT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  he

Public Types

typedef boost::shared_ptr
< const ApproximateVoxelGrid
< PointT > > 
ConstPtr
typedef boost::shared_ptr
< ApproximateVoxelGrid< PointT > > 
Ptr

Public Member Functions

 ApproximateVoxelGrid ()
 Empty constructor.
 ApproximateVoxelGrid (const ApproximateVoxelGrid &src)
 Copy constructor.
bool getDownsampleAllData () const
 Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ).
Eigen::Vector3f getLeafSize () const
 Get the voxel grid leaf size.
ApproximateVoxelGridoperator= (const ApproximateVoxelGrid &src)
 Copy operator.
void setDownsampleAllData (bool downsample)
 Set to true if all fields need to be downsampled, or false if just XYZ.
void setLeafSize (const Eigen::Vector3f &leaf_size)
 Set the voxel grid leaf size.
void setLeafSize (float lx, float ly, float lz)
 Set the voxel grid leaf size.
 ~ApproximateVoxelGrid ()
 Destructor.

Protected Types

typedef pcl::traits::fieldList
< PointT >::type 
FieldList

Protected Member Functions

void applyFilter (PointCloud &output)
 Downsample a Point Cloud using a voxelized grid approach.
void flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size)
 Write a single point from the hash to the output cloud.

Protected Attributes

bool downsample_all_data_
 Set to true if all fields need to be downsampled, or false if just XYZ.
struct hehistory_
 history buffer
size_t histsize_
 history buffer size, power of 2
Eigen::Array3f inverse_leaf_size_
 Compute 1/leaf_size_ to avoid division later.
Eigen::Vector3f leaf_size_
 The size of a leaf.

Private Types

typedef Filter< PointT >
::PointCloud 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Detailed Description

template<typename PointT>
class pcl::ApproximateVoxelGrid< PointT >

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

Author:
James Bowman, Radu B. Rusu

Definition at line 100 of file approximate_voxel_grid.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const ApproximateVoxelGrid<PointT> > pcl::ApproximateVoxelGrid< PointT >::ConstPtr

Reimplemented from pcl::Filter< PointT >.

Definition at line 123 of file approximate_voxel_grid.h.

template<typename PointT>
typedef pcl::traits::fieldList<PointT>::type pcl::ApproximateVoxelGrid< PointT >::FieldList [protected]

Definition at line 231 of file approximate_voxel_grid.h.

template<typename PointT>
typedef Filter<PointT>::PointCloud pcl::ApproximateVoxelGrid< PointT >::PointCloud [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 107 of file approximate_voxel_grid.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::ApproximateVoxelGrid< PointT >::PointCloudConstPtr [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 109 of file approximate_voxel_grid.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::ApproximateVoxelGrid< PointT >::PointCloudPtr [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 108 of file approximate_voxel_grid.h.

template<typename PointT>
typedef boost::shared_ptr< ApproximateVoxelGrid<PointT> > pcl::ApproximateVoxelGrid< PointT >::Ptr

Reimplemented from pcl::Filter< PointT >.

Definition at line 122 of file approximate_voxel_grid.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid ( ) [inline]

Empty constructor.

Definition at line 127 of file approximate_voxel_grid.h.

template<typename PointT>
pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid ( const ApproximateVoxelGrid< PointT > &  src) [inline]

Copy constructor.

Parameters:
[in]srcthe approximate voxel grid to copy into this.

Definition at line 140 of file approximate_voxel_grid.h.

template<typename PointT>
pcl::ApproximateVoxelGrid< PointT >::~ApproximateVoxelGrid ( ) [inline]

Destructor.

Definition at line 156 of file approximate_voxel_grid.h.


Member Function Documentation

template<typename PointT >
void pcl::ApproximateVoxelGrid< PointT >::applyFilter ( PointCloud output) [protected, virtual]

Downsample a Point Cloud using a voxelized grid approach.

Parameters:
outputthe resultant point cloud message

Implements pcl::Filter< PointT >.

Definition at line 65 of file approximate_voxel_grid.hpp.

template<typename PointT >
void pcl::ApproximateVoxelGrid< PointT >::flush ( PointCloud output,
size_t  op,
he hhe,
int  rgba_index,
int  centroid_size 
) [protected]

Write a single point from the hash to the output cloud.

Definition at line 47 of file approximate_voxel_grid.hpp.

template<typename PointT>
bool pcl::ApproximateVoxelGrid< 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 213 of file approximate_voxel_grid.h.

template<typename PointT>
Eigen::Vector3f pcl::ApproximateVoxelGrid< PointT >::getLeafSize ( ) const [inline]

Get the voxel grid leaf size.

Definition at line 201 of file approximate_voxel_grid.h.

template<typename PointT>
ApproximateVoxelGrid& pcl::ApproximateVoxelGrid< PointT >::operator= ( const ApproximateVoxelGrid< PointT > &  src) [inline]

Copy operator.

Parameters:
[in]srcthe approximate voxel grid to copy into this.

Definition at line 166 of file approximate_voxel_grid.h.

template<typename PointT>
void pcl::ApproximateVoxelGrid< PointT >::setDownsampleAllData ( bool  downsample) [inline]

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

Parameters:
downsamplethe new value (true/false)

Definition at line 207 of file approximate_voxel_grid.h.

template<typename PointT>
void pcl::ApproximateVoxelGrid< PointT >::setLeafSize ( const Eigen::Vector3f &  leaf_size) [inline]

Set the voxel grid leaf size.

Parameters:
[in]leaf_sizethe voxel grid leaf size

Definition at line 182 of file approximate_voxel_grid.h.

template<typename PointT>
void pcl::ApproximateVoxelGrid< 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 194 of file approximate_voxel_grid.h.


Member Data Documentation

template<typename PointT>
bool pcl::ApproximateVoxelGrid< PointT >::downsample_all_data_ [protected]

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

Definition at line 223 of file approximate_voxel_grid.h.

template<typename PointT>
struct he* pcl::ApproximateVoxelGrid< PointT >::history_ [protected]

history buffer

Definition at line 229 of file approximate_voxel_grid.h.

template<typename PointT>
size_t pcl::ApproximateVoxelGrid< PointT >::histsize_ [protected]

history buffer size, power of 2

Definition at line 226 of file approximate_voxel_grid.h.

template<typename PointT>
Eigen::Array3f pcl::ApproximateVoxelGrid< PointT >::inverse_leaf_size_ [protected]

Compute 1/leaf_size_ to avoid division later.

Definition at line 220 of file approximate_voxel_grid.h.

template<typename PointT>
Eigen::Vector3f pcl::ApproximateVoxelGrid< PointT >::leaf_size_ [protected]

The size of a leaf.

Definition at line 217 of file approximate_voxel_grid.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:39:06