VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
#include <voxel_grid.h>

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 IndicesConstPtr &indices, PointCloud2 &output) |
| Call the actual filter. | |
Protected Attributes | |
| pcl::VoxelGrid < sensor_msgs::PointCloud2 > | impl_ |
| The PCL filter implementation used. | |
| boost::shared_ptr < dynamic_reconfigure::Server < pcl_ros::VoxelGridConfig > > | srv_ |
| Pointer to a dynamic reconfigure service. | |
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition at line 51 of file voxel_grid.h.
| bool pcl_ros::VoxelGrid::child_init | ( | ros::NodeHandle & | nh, | |
| bool & | has_service | |||
| ) | [protected, virtual] |
Child initialization routine.
| nh | ROS node handle | |
| has_service | set 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.
| config | the config object | |
| level | the dynamic reconfigure level |
Definition at line 69 of file voxel_grid.cpp.
| void pcl_ros::VoxelGrid::filter | ( | const PointCloud2::ConstPtr & | input, | |
| const IndicesConstPtr & | indices, | |||
| PointCloud2 & | output | |||
| ) | [protected, virtual] |
Call the actual filter.
| input | the input point cloud dataset | |
| indices | the input set of indices to use from input | |
| output | the resultant filtered dataset |
Implements pcl_ros::Filter.
Definition at line 56 of file voxel_grid.cpp.
pcl::VoxelGrid<sensor_msgs::PointCloud2> pcl_ros::VoxelGrid::impl_ [protected] |
The PCL filter implementation used.
Definition at line 53 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 50 of file voxel_grid.h.