Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
pcl_ros::Filter Class Referenceabstract

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]

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 Types inherited from pcl_ros::PCLNodelet
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef pcl_msgs::ModelCoefficients ModelCoefficients
 
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
 
typedef ModelCoefficients::Ptr ModelCoefficientsPtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 

Public Member Functions

 Filter ()
 
- Public Member Functions inherited from pcl_ros::PCLNodelet
 PCLNodelet ()
 Empty constructor. More...
 
- Public Member Functions inherited from nodelet_topic_tools::NodeletLazy
 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine. More...
 
void computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
 Call the child filter () method, optionally transform the result, and publish it. More...
 
virtual void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)=0
 Virtual abstract filter method. To be implemented by every child. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
virtual void subscribe ()
 Lazy transport subscribe routine. More...
 
virtual void unsubscribe ()
 Lazy transport unsubscribe routine. More...
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointIndicesConstPtr &indices, const std::string &topic_name="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
bool isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

std::string filter_field_name_
 The desired user filter field name. More...
 
double filter_limit_max_
 The maximum allowed filter value a point will be considered from. More...
 
double filter_limit_min_
 The minimum allowed filter value a point will be considered from. More...
 
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false. More...
 
boost::mutex mutex_
 Internal mutex. More...
 
ros::Subscriber sub_input_
 The input PointCloud subscriber. More...
 
message_filters::Subscriber< PointCloud2sub_input_filter_
 
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
std::string tf_input_orig_frame_
 The original data input TF frame. More...
 
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
- Protected Attributes inherited from pcl_ros::PCLNodelet
bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
bool latched_indices_
 Set to true if the indices topic is latched. More...
 
int max_queue_size_
 The maximum queue size (default: 3). More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
message_filters::Subscriber< PointIndicessub_indices_filter_
 The message filter subscriber for PointIndices. More...
 
message_filters::Subscriber< PointCloudsub_input_filter_
 The message filter subscriber for PointCloud2. More...
 
tf::TransformListener tf_listener_
 TF listener object. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

Private Member Functions

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

Private Attributes

boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
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. More...
 

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

Definition at line 63 of file filter.h.

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

Definition at line 62 of file filter.h.

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

Definition at line 60 of file filter.h.

Constructor & Destructor Documentation

pcl_ros::Filter::Filter ( )
inline

Definition at line 65 of file filter.h.

Member Function Documentation

virtual bool pcl_ros::Filter::child_init ( ros::NodeHandle nh,
bool &  has_service 
)
inlineprotectedvirtual

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 
)
privatevirtual

Dynamic reconfigure service callback.

Reimplemented in pcl_ros::PassThrough.

Definition at line 177 of file filter.cpp.

virtual void pcl_ros::Filter::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
)
protectedpure 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::VoxelGrid, pcl_ros::RadiusOutlierRemoval, 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 194 of file filter.cpp.

void Filter::onInit ( )
protectedvirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::ProjectInliers.

Definition at line 149 of file filter.cpp.

void Filter::subscribe ( )
protectedvirtual

Lazy transport subscribe routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::ProjectInliers.

Definition at line 107 of file filter.cpp.

void Filter::unsubscribe ( )
protectedvirtual

Lazy transport unsubscribe routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::ProjectInliers.

Definition at line 136 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.

double pcl_ros::Filter::filter_limit_max_
protected

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

Definition at line 80 of file filter.h.

double pcl_ros::Filter::filter_limit_min_
protected

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

Definition at line 77 of file filter.h.

bool pcl_ros::Filter::filter_limit_negative_
protected

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.

Definition at line 138 of file filter.h.

ros::Subscriber pcl_ros::Filter::sub_input_
protected

The input PointCloud subscriber.

Definition at line 69 of file filter.h.

message_filters::Subscriber<PointCloud2> pcl_ros::Filter::sub_input_filter_
protected

Definition at line 71 of file filter.h.

Definition at line 142 of file filter.h.

Synchronized input, and indices.

Definition at line 141 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 Jun 5 2019 19:52:53