RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K. More...
#include <radius_outlier_removal.h>

Protected Member Functions | |
| virtual bool | child_init (ros::NodeHandle &nh, bool &has_service) |
| Child initialization routine. | |
| void | config_callback (pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level) |
| Dynamic reconfigure 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::RadiusOutlierRemovalConfig > > | srv_ |
| Pointer to a dynamic reconfigure service. | |
Private Attributes | |
| pcl::RadiusOutlierRemoval < pcl::PCLPointCloud2 > | impl_ |
| The PCL filter implementation used. | |
RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K.
Definition at line 55 of file radius_outlier_removal.h.
| bool pcl_ros::RadiusOutlierRemoval::child_init | ( | ros::NodeHandle & | nh, |
| bool & | has_service | ||
| ) | [inline, 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 radius_outlier_removal.cpp.
| void pcl_ros::RadiusOutlierRemoval::config_callback | ( | pcl_ros::RadiusOutlierRemovalConfig & | config, |
| uint32_t | level | ||
| ) | [protected] |
Dynamic reconfigure callback.
| config | the config object |
| level | the dynamic reconfigure level |
Definition at line 56 of file radius_outlier_removal.cpp.
| void pcl_ros::RadiusOutlierRemoval::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 67 of file radius_outlier_removal.h.
pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> pcl_ros::RadiusOutlierRemoval::impl_ [private] |
The PCL filter implementation used.
Definition at line 94 of file radius_outlier_removal.h.
boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig> > pcl_ros::RadiusOutlierRemoval::srv_ [protected] |
Pointer to a dynamic reconfigure service.
Reimplemented from pcl_ros::Filter.
Definition at line 59 of file radius_outlier_removal.h.