37 #ifndef JSK_PERCEPTION_APPLY_MASK_IMAGE_H_ 38 #define JSK_PERCEPTION_APPLY_MASK_IMAGE_H_ 41 #include <sensor_msgs/Image.h> 42 #include <sensor_msgs/CameraInfo.h> 66 const sensor_msgs::Image::ConstPtr& image_msg,
67 const sensor_msgs::Image::ConstPtr& mask_msg);
69 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
ros::Subscriber sub_info_
ros::Publisher pub_camera_info_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > ApproximateSyncPolicy
bool use_rectified_image_
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg)
sensor_msgs::CameraInfo::ConstPtr camera_info_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
ros::Publisher pub_image_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
bool negative_before_clip_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
bool mask_black_to_transparent_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_