pcl_ros::StatisticalOutlierRemoval Class Reference

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check: More...

#include <statistical_outlier_removal.h>

Inheritance diagram for pcl_ros::StatisticalOutlierRemoval:
Inheritance graph
[legend]

List of all members.

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 IndicesConstPtr &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.

Detailed Description

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:

Note:
setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
Author:
Radu Bogdan Rusu

Definition at line 59 of file statistical_outlier_removal.h.


Member Function Documentation

bool pcl_ros::StatisticalOutlierRemoval::child_init ( ros::NodeHandle &  nh,
bool &  has_service 
) [protected, virtual]

Child initialization routine.

Parameters:
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.

Parameters:
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 IndicesConstPtr indices,
PointCloud2 output 
) [inline, protected, virtual]

Call the actual filter.

Parameters:
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 58 of file statistical_outlier_removal.h.


Member Data Documentation

The PCL filter implementation used.

Definition at line 81 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 50 of file statistical_outlier_removal.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:15:55 2013