Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_
38 #define JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <sensor_msgs/Image.h>
50 class PointIndicesToMaskImage:
public jsk_topic_tools::DiagnosticNodelet
70 const PCLIndicesMsg::ConstPtr& indices_msg,
74 const PCLIndicesMsg::ConstPtr& indices_msg);
76 const PCLIndicesMsg::ConstPtr& indices_msg,
77 const sensor_msgs::Image::ConstPtr& image_msg);
PointIndicesToMaskImage()
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::Image > ApproximateSyncPolicy
virtual void mask(const PCLIndicesMsg::ConstPtr &indices_msg)
virtual void convertAndPublish(const PCLIndicesMsg::ConstPtr &indices_msg, const int width, const int height)
pcl::PointIndices PCLIndicesMsg
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
ros::Subscriber sub_input_static_
message_filters::Subscriber< PCLIndicesMsg > sub_input_
virtual ~PointIndicesToMaskImage()
message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::Image > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43