37 #ifndef JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_ 38 #define JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_ 41 #include <sensor_msgs/Image.h> 69 const PCLIndicesMsg::ConstPtr& indices_msg,
73 const PCLIndicesMsg::ConstPtr& indices_msg);
75 const PCLIndicesMsg::ConstPtr& indices_msg,
76 const sensor_msgs::Image::ConstPtr& image_msg);
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
ros::Subscriber sub_input_static_
PointIndicesToMaskImage()
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::Image > ApproximateSyncPolicy
virtual void convertAndPublish(const PCLIndicesMsg::ConstPtr &indices_msg, const int width, const int height)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< PCLIndicesMsg > sub_input_
pcl::PointIndices PCLIndicesMsg
message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::Image > SyncPolicy
virtual void mask(const PCLIndicesMsg::ConstPtr &indices_msg)