$search
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) |
Child initialization routine. | |
void | filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) |
Call the actual filter. | |
Private Attributes | |
pcl::RadiusOutlierRemoval < sensor_msgs::PointCloud2 > | 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 52 of file radius_outlier_removal.h.
virtual bool pcl_ros::RadiusOutlierRemoval::child_init | ( | ros::NodeHandle & | nh | ) | [inline, protected, virtual] |
Child initialization routine.
nh | ROS node handle |
Definition at line 72 of file radius_outlier_removal.h.
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 61 of file radius_outlier_removal.h.
The PCL filter implementation used.
Definition at line 76 of file radius_outlier_removal.h.