#include <selected_cluster_publisher.h>
Public Types | |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::Int32Stamped > | SyncPolicy |
Protected Member Functions | |
virtual void | extract (const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices, const jsk_recognition_msgs::Int32Stamped::ConstPtr &index) |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
ros::Publisher | pub_ |
message_filters::Subscriber < jsk_recognition_msgs::Int32Stamped > | sub_index_ |
message_filters::Subscriber < jsk_recognition_msgs::ClusterPointIndices > | sub_indices_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
Private Member Functions | |
virtual void | onInit () |
Private Attributes | |
bool | keep_organized_ |
Definition at line 50 of file selected_cluster_publisher.h.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::Int32Stamped> jsk_pcl_ros::SelectedClusterPublisher::SyncPolicy |
Definition at line 53 of file selected_cluster_publisher.h.
void jsk_pcl_ros::SelectedClusterPublisher::extract | ( | const sensor_msgs::PointCloud2::ConstPtr & | input, |
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & | indices, | ||
const jsk_recognition_msgs::Int32Stamped::ConstPtr & | index | ||
) | [protected, virtual] |
Definition at line 68 of file selected_cluster_publisher_nodelet.cpp.
void jsk_pcl_ros::SelectedClusterPublisher::onInit | ( | void | ) | [private, virtual] |
Definition at line 43 of file selected_cluster_publisher_nodelet.cpp.
void jsk_pcl_ros::SelectedClusterPublisher::subscribe | ( | ) | [protected, virtual] |
Definition at line 51 of file selected_cluster_publisher_nodelet.cpp.
void jsk_pcl_ros::SelectedClusterPublisher::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 61 of file selected_cluster_publisher_nodelet.cpp.
bool jsk_pcl_ros::SelectedClusterPublisher::keep_organized_ [private] |
Definition at line 69 of file selected_cluster_publisher.h.
Definition at line 55 of file selected_cluster_publisher.h.
message_filters::Subscriber<jsk_recognition_msgs::Int32Stamped> jsk_pcl_ros::SelectedClusterPublisher::sub_index_ [protected] |
Definition at line 58 of file selected_cluster_publisher.h.
message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::SelectedClusterPublisher::sub_indices_ [protected] |
Definition at line 57 of file selected_cluster_publisher.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::SelectedClusterPublisher::sub_input_ [protected] |
Definition at line 56 of file selected_cluster_publisher.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::SelectedClusterPublisher::sync_ [protected] |
Definition at line 59 of file selected_cluster_publisher.h.