Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl_ros::Filter Class Reference

Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods. More...

#include <filter.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef sensor_msgs::PointCloud2 PointCloud2

Public Member Functions

 Filter ()

Protected Member Functions

virtual bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine.
void computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
 Call the child filter () method, optionally transform the result, and publish it.
virtual void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)=0
 Virtual abstract filter method. To be implemented by every child.
virtual void onInit ()
 Nodelet initialization routine.

Protected Attributes

std::string filter_field_name_
 The desired user filter field name.
double filter_limit_max_
 The maximum allowed filter value a point will be considered from.
double filter_limit_min_
 The minimum allowed filter value a point will be considered from.
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
boost::mutex mutex_
 Internal mutex.
ros::Subscriber sub_input_
 The input PointCloud subscriber.
message_filters::Subscriber
< PointCloud2
sub_input_filter_
 The message filter subscriber for PointCloud2.
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different.
std::string tf_input_orig_frame_
 The original data input TF frame.
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different.

Private Member Functions

virtual void config_callback (pcl_ros::FilterConfig &config, uint32_t level)
 Dynamic reconfigure service callback.
void input_indices_callback (const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
 PointCloud2 + Indices data callback.

Private Attributes

boost::shared_ptr
< dynamic_reconfigure::Server
< pcl_ros::FilterConfig > > 
srv_
 Pointer to a dynamic reconfigure service.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloud2, PointIndices > > > 
sync_input_indices_a_
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloud2, PointIndices > > > 
sync_input_indices_e_
 Synchronized input, and indices.

Detailed Description

Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.

Author:
Radu Bogdan Rusu

Definition at line 57 of file filter.h.


Member Typedef Documentation

typedef boost::shared_ptr<const std::vector<int> > pcl_ros::Filter::IndicesConstPtr

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 63 of file filter.h.

typedef boost::shared_ptr<std::vector<int> > pcl_ros::Filter::IndicesPtr

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 62 of file filter.h.

typedef sensor_msgs::PointCloud2 pcl_ros::Filter::PointCloud2

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 60 of file filter.h.


Constructor & Destructor Documentation

Definition at line 65 of file filter.h.


Member Function Documentation

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

Child initialization routine.

Parameters:
nhROS node handle
has_serviceset to true if the child has a Dynamic Reconfigure service

Reimplemented in pcl_ros::StatisticalOutlierRemoval, pcl_ros::CropBox, pcl_ros::ExtractIndices, pcl_ros::RadiusOutlierRemoval, pcl_ros::PassThrough, and pcl_ros::VoxelGrid.

Definition at line 102 of file filter.h.

void Filter::computePublish ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices 
) [protected]

Call the child filter () method, optionally transform the result, and publish it.

Parameters:
inputthe input point cloud dataset.
indicesa pointer to the vector of point indices to use.

Definition at line 64 of file filter.cpp.

void Filter::config_callback ( pcl_ros::FilterConfig &  config,
uint32_t  level 
) [private, virtual]

Dynamic reconfigure service callback.

Reimplemented in pcl_ros::PassThrough.

Definition at line 159 of file filter.cpp.

virtual void pcl_ros::Filter::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
) [protected, pure virtual]

Virtual abstract filter method. To be implemented by every child.

Parameters:
inputthe input point cloud dataset.
indicesa pointer to the vector of point indices to use.
outputthe resultant filtered PointCloud2

Implemented in pcl_ros::StatisticalOutlierRemoval, pcl_ros::CropBox, pcl_ros::ProjectInliers, pcl_ros::RadiusOutlierRemoval, pcl_ros::VoxelGrid, pcl_ros::ExtractIndices, and pcl_ros::PassThrough.

void Filter::input_indices_callback ( const PointCloud2::ConstPtr &  cloud,
const PointIndicesConstPtr indices 
) [private]

PointCloud2 + Indices data callback.

DEBUG

Definition at line 176 of file filter.cpp.

void Filter::onInit ( ) [protected, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::ProjectInliers.

Definition at line 107 of file filter.cpp.


Member Data Documentation

std::string pcl_ros::Filter::filter_field_name_ [protected]

The desired user filter field name.

Definition at line 74 of file filter.h.

The maximum allowed filter value a point will be considered from.

Definition at line 80 of file filter.h.

The minimum allowed filter value a point will be considered from.

Definition at line 77 of file filter.h.

Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.

Definition at line 83 of file filter.h.

boost::mutex pcl_ros::Filter::mutex_ [protected]

Internal mutex.

Definition at line 95 of file filter.h.

boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::FilterConfig> > pcl_ros::Filter::srv_ [private]

Pointer to a dynamic reconfigure service.

Reimplemented in pcl_ros::StatisticalOutlierRemoval, pcl_ros::CropBox, pcl_ros::RadiusOutlierRemoval, pcl_ros::ExtractIndices, pcl_ros::VoxelGrid, and pcl_ros::PassThrough.

Definition at line 130 of file filter.h.

The input PointCloud subscriber.

Definition at line 69 of file filter.h.

The message filter subscriber for PointCloud2.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 71 of file filter.h.

Definition at line 134 of file filter.h.

Synchronized input, and indices.

Definition at line 133 of file filter.h.

std::string pcl_ros::Filter::tf_input_frame_ [protected]

The input TF frame the data should be transformed into, if input.header.frame_id is different.

Definition at line 86 of file filter.h.

std::string pcl_ros::Filter::tf_input_orig_frame_ [protected]

The original data input TF frame.

Definition at line 89 of file filter.h.

std::string pcl_ros::Filter::tf_output_frame_ [protected]

The output TF frame the data should be transformed into, if input.header.frame_id is different.

Definition at line 92 of file filter.h.


The documentation for this class was generated from the following files:


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Aug 26 2015 15:25:31