$search
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check: More...
#include <statistical_outlier_removal.h>
Protected Member Functions | |
bool | child_init (ros::NodeHandle &nh, bool &has_service) |
Child initialization routine. | |
void | config_callback (pcl_ros::StatisticalOutlierRemovalConfig &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::StatisticalOutlierRemovalConfig > > | srv_ |
Pointer to a dynamic reconfigure service. | |
Private Attributes | |
pcl::StatisticalOutlierRemoval < sensor_msgs::PointCloud2 > | impl_ |
The PCL filter implementation used. |
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:
Definition at line 61 of file statistical_outlier_removal.h.
bool pcl_ros::StatisticalOutlierRemoval::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 statistical_outlier_removal.cpp.
void pcl_ros::StatisticalOutlierRemoval::config_callback | ( | pcl_ros::StatisticalOutlierRemovalConfig & | config, | |
uint32_t | level | |||
) | [protected] |
Dynamic reconfigure callback.
config | the config object | |
level | the dynamic reconfigure level |
Definition at line 56 of file statistical_outlier_removal.cpp.
void pcl_ros::StatisticalOutlierRemoval::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 73 of file statistical_outlier_removal.h.
pcl::StatisticalOutlierRemoval<sensor_msgs::PointCloud2> pcl_ros::StatisticalOutlierRemoval::impl_ [private] |
The PCL filter implementation used.
Definition at line 96 of file statistical_outlier_removal.h.
boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig> > pcl_ros::StatisticalOutlierRemoval::srv_ [protected] |
Pointer to a dynamic reconfigure service.
Reimplemented from pcl_ros::Filter.
Definition at line 65 of file statistical_outlier_removal.h.