Protected Member Functions | Protected Attributes
pcl_ros::VoxelGrid Class Reference

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

#include <voxel_grid.h>

Inheritance diagram for pcl_ros::VoxelGrid:
Inheritance graph
[legend]

List of all members.

Protected Member Functions

bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine.
void config_callback (pcl_ros::VoxelGridConfig &config, uint32_t level)
 Dynamic reconfigure callback.
virtual void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
 Call the actual filter.

Protected Attributes

pcl::VoxelGrid
< pcl::PCLPointCloud2 > 
impl_
 The PCL filter implementation used.
boost::shared_ptr
< dynamic_reconfigure::Server
< pcl_ros::VoxelGridConfig > > 
srv_
 Pointer to a dynamic reconfigure service.

Detailed Description

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

Author:
Radu Bogdan Rusu

Definition at line 53 of file voxel_grid.h.


Member Function Documentation

bool pcl_ros::VoxelGrid::child_init ( ros::NodeHandle nh,
bool &  has_service 
) [protected, virtual]

Child initialization routine.

Parameters:
nhROS node handle
has_serviceset to true if the child has a Dynamic Reconfigure service

Reimplemented from pcl_ros::Filter.

Definition at line 43 of file voxel_grid.cpp.

void pcl_ros::VoxelGrid::config_callback ( pcl_ros::VoxelGridConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 72 of file voxel_grid.cpp.

void pcl_ros::VoxelGrid::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
) [protected, virtual]

Call the actual filter.

Parameters:
inputthe input point cloud dataset
indicesthe input set of indices to use from input
outputthe resultant filtered dataset

Implements pcl_ros::Filter.

Definition at line 56 of file voxel_grid.cpp.


Member Data Documentation

pcl::VoxelGrid<pcl::PCLPointCloud2> pcl_ros::VoxelGrid::impl_ [protected]

The PCL filter implementation used.

Definition at line 60 of file voxel_grid.h.

boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig> > pcl_ros::VoxelGrid::srv_ [protected]

Pointer to a dynamic reconfigure service.

Reimplemented from pcl_ros::Filter.

Definition at line 57 of file voxel_grid.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43