#include <extract_indices.h>
| Public Types | |
| typedef message_filters::sync_policies::ApproximateTime < PCLIndicesMsg, sensor_msgs::PointCloud2 > | ApproximateSyncPolicy | 
| typedef message_filters::sync_policies::ExactTime < PCLIndicesMsg, sensor_msgs::PointCloud2 > | SyncPolicy | 
| Public Member Functions | |
| ExtractIndices () | |
| Protected Member Functions | |
| virtual void | convert (const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| virtual void | onInit () | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| bool | approximate_sync_ | 
| boost::shared_ptr < message_filters::Synchronizer < ApproximateSyncPolicy > > | async_ | 
| bool | keep_organized_ | 
| int | max_queue_size_ | 
| bool | negative_ | 
| ros::Publisher | pub_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_cloud_ | 
| message_filters::Subscriber < PCLIndicesMsg > | sub_indices_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
Definition at line 50 of file extract_indices.h.
| typedef message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > jsk_pcl_ros::ExtractIndices::ApproximateSyncPolicy | 
Definition at line 58 of file extract_indices.h.
| typedef message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > jsk_pcl_ros::ExtractIndices::SyncPolicy | 
Definition at line 55 of file extract_indices.h.
| jsk_pcl_ros::ExtractIndices::ExtractIndices | ( | ) |  [inline] | 
Definition at line 60 of file extract_indices.h.
| void jsk_pcl_ros::ExtractIndices::convert | ( | const PCLIndicesMsg::ConstPtr & | indices_msg, | 
| const sensor_msgs::PointCloud2::ConstPtr & | msg | ||
| ) |  [protected, virtual] | 
Definition at line 85 of file extract_indices_nodelet.cpp.
| void jsk_pcl_ros::ExtractIndices::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 50 of file extract_indices_nodelet.cpp.
| void jsk_pcl_ros::ExtractIndices::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 61 of file extract_indices_nodelet.cpp.
| void jsk_pcl_ros::ExtractIndices::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 79 of file extract_indices_nodelet.cpp.
| bool jsk_pcl_ros::ExtractIndices::approximate_sync_  [protected] | 
Definition at line 72 of file extract_indices.h.
| boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros::ExtractIndices::async_  [protected] | 
Definition at line 74 of file extract_indices.h.
| bool jsk_pcl_ros::ExtractIndices::keep_organized_  [protected] | 
Definition at line 69 of file extract_indices.h.
| int jsk_pcl_ros::ExtractIndices::max_queue_size_  [protected] | 
Definition at line 71 of file extract_indices.h.
| bool jsk_pcl_ros::ExtractIndices::negative_  [protected] | 
Definition at line 70 of file extract_indices.h.
| ros::Publisher jsk_pcl_ros::ExtractIndices::pub_  [protected] | 
Definition at line 75 of file extract_indices.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::ExtractIndices::sub_cloud_  [protected] | 
Definition at line 76 of file extract_indices.h.
Definition at line 77 of file extract_indices.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::ExtractIndices::sync_  [protected] | 
Definition at line 73 of file extract_indices.h.