Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
jsk_pcl_ros::OrganizedPassThrough Class Reference

#include <organized_pass_through.h>

Inheritance diagram for jsk_pcl_ros::OrganizedPassThrough:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
jsk_pcl_ros::OrganizedPassThroughConfig 
Config
typedef pcl::PointXYZRGB PointT

Public Member Functions

 OrganizedPassThrough ()

Protected Types

enum  FilterField { FIELD_X, FIELD_Y }

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual void filter (const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual pcl::PointIndices::Ptr filterIndices (const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)

Protected Attributes

FilterField filter_field_
bool filter_limit_negative_
jsk_topic_tools::Counter filtered_points_counter_
bool keep_organized_
int max_index_
int min_index_
boost::mutex mutex_
ros::Publisher pub_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_

Detailed Description

Definition at line 48 of file organized_pass_through.h.


Member Typedef Documentation

typedef jsk_pcl_ros::OrganizedPassThroughConfig jsk_pcl_ros::OrganizedPassThrough::Config

Definition at line 51 of file organized_pass_through.h.

Definition at line 52 of file organized_pass_through.h.


Member Enumeration Documentation

Enumerator:
FIELD_X 
FIELD_Y 

Definition at line 86 of file organized_pass_through.h.


Constructor & Destructor Documentation

Definition at line 41 of file organized_pass_through_nodelet.cpp.


Member Function Documentation

void jsk_pcl_ros::OrganizedPassThrough::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 78 of file organized_pass_through_nodelet.cpp.

void jsk_pcl_ros::OrganizedPassThrough::filter ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]

Definition at line 114 of file organized_pass_through_nodelet.cpp.

pcl::PointIndices::Ptr jsk_pcl_ros::OrganizedPassThrough::filterIndices ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]

Definition at line 93 of file organized_pass_through_nodelet.cpp.

void jsk_pcl_ros::OrganizedPassThrough::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 47 of file organized_pass_through_nodelet.cpp.

void jsk_pcl_ros::OrganizedPassThrough::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::OrganizedPassThrough::unsubscribe ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 136 of file organized_pass_through_nodelet.cpp.


Member Data Documentation

Definition at line 94 of file organized_pass_through.h.

Definition at line 97 of file organized_pass_through.h.

Definition at line 84 of file organized_pass_through.h.

Definition at line 98 of file organized_pass_through.h.

Definition at line 96 of file organized_pass_through.h.

Definition at line 95 of file organized_pass_through.h.

Definition at line 79 of file organized_pass_through.h.

Definition at line 77 of file organized_pass_through.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::OrganizedPassThrough::srv_ [protected]

Definition at line 78 of file organized_pass_through.h.

Definition at line 76 of file organized_pass_through.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49