38 #ifndef PCL_ROS_FILTERS_VOXEL_H_ 39 #define PCL_ROS_FILTERS_VOXEL_H_ 42 #include <pcl/filters/voxel_grid.h> 46 #include "pcl_ros/VoxelGridConfig.h" 60 pcl::VoxelGrid<pcl::PCLPointCloud2>
impl_;
85 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
89 #endif //#ifndef PCL_ROS_FILTERS_VOXEL_H_ virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
pcl::IndicesPtr IndicesPtr
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::VoxelGridConfig > > srv_
Pointer to a dynamic reconfigure service.
sensor_msgs::PointCloud2 PointCloud2
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data...
void config_callback(pcl_ros::VoxelGridConfig &config, uint32_t level)
Dynamic reconfigure callback.
pcl::VoxelGrid< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.