PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...
#include <passthrough.h>
Protected Member Functions | |
bool | child_init (ros::NodeHandle &nh, bool &has_service) |
Child initialization routine. | |
void | config_callback (pcl_ros::FilterConfig &config, uint32_t level) |
Dynamic reconfigure service callback. | |
void | filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) |
Call the actual filter. | |
Protected Attributes | |
boost::shared_ptr < dynamic_reconfigure::Server < pcl_ros::FilterConfig > > | srv_ |
Pointer to a dynamic reconfigure service. | |
Private Attributes | |
pcl::PassThrough < pcl::PCLPointCloud2 > | impl_ |
The PCL filter implementation used. |
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints.
Definition at line 51 of file passthrough.h.
bool pcl_ros::PassThrough::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 passthrough.cpp.
void pcl_ros::PassThrough::config_callback | ( | pcl_ros::FilterConfig & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Dynamic reconfigure service callback.
config | the dynamic reconfigure FilterConfig object |
level | the dynamic reconfigure level |
Reimplemented from pcl_ros::Filter.
Definition at line 56 of file passthrough.cpp.
void pcl_ros::PassThrough::filter | ( | const PointCloud2::ConstPtr & | input, |
const IndicesPtr & | indices, | ||
PointCloud2 & | output | ||
) | [inline, 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 63 of file passthrough.h.
pcl::PassThrough<pcl::PCLPointCloud2> pcl_ros::PassThrough::impl_ [private] |
The PCL filter implementation used.
Definition at line 92 of file passthrough.h.
boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::FilterConfig> > pcl_ros::PassThrough::srv_ [protected] |
Pointer to a dynamic reconfigure service.
Reimplemented from pcl_ros::Filter.
Definition at line 55 of file passthrough.h.