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>
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. |
Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.
typedef boost::shared_ptr<const std::vector<int> > pcl_ros::Filter::IndicesConstPtr |
Reimplemented from pcl_ros::PCLNodelet.
typedef boost::shared_ptr<std::vector<int> > pcl_ros::Filter::IndicesPtr |
Reimplemented from pcl_ros::PCLNodelet.
typedef sensor_msgs::PointCloud2 pcl_ros::Filter::PointCloud2 |
Reimplemented from pcl_ros::PCLNodelet.
pcl_ros::Filter::Filter | ( | ) | [inline] |
virtual bool pcl_ros::Filter::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 in pcl_ros::StatisticalOutlierRemoval, pcl_ros::CropBox, pcl_ros::ExtractIndices, pcl_ros::RadiusOutlierRemoval, pcl_ros::PassThrough, and pcl_ros::VoxelGrid.
void Filter::computePublish | ( | const PointCloud2::ConstPtr & | input, |
const IndicesPtr & | indices | ||
) | [protected] |
Call the child filter () method, optionally transform the result, and publish it.
input | the input point cloud dataset. |
indices | a 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.
input | the input point cloud dataset. |
indices | a pointer to the vector of point indices to use. |
output | the 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] |
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.
std::string pcl_ros::Filter::filter_field_name_ [protected] |
double pcl_ros::Filter::filter_limit_max_ [protected] |
double pcl_ros::Filter::filter_limit_min_ [protected] |
bool pcl_ros::Filter::filter_limit_negative_ [protected] |
boost::mutex pcl_ros::Filter::mutex_ [protected] |
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.
ros::Subscriber pcl_ros::Filter::sub_input_ [protected] |
The message filter subscriber for PointCloud2.
Reimplemented from pcl_ros::PCLNodelet.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices> > > pcl_ros::Filter::sync_input_indices_a_ [private] |
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices> > > pcl_ros::Filter::sync_input_indices_e_ [private] |
std::string pcl_ros::Filter::tf_input_frame_ [protected] |
std::string pcl_ros::Filter::tf_input_orig_frame_ [protected] |
std::string pcl_ros::Filter::tf_output_frame_ [protected] |