#include <apply_mask_image.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image > | ApproximateSyncPolicy |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, sensor_msgs::Image > | SyncPolicy |
Public Member Functions | |
ApplyMaskImage () | |
Protected Member Functions | |
virtual void | apply (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
bool | approximate_sync_ |
boost::shared_ptr < message_filters::Synchronizer < ApproximateSyncPolicy > > | async_ |
bool | mask_black_to_transparent_ |
ros::Publisher | pub_image_ |
ros::Publisher | pub_mask_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_image_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_mask_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
Definition at line 49 of file apply_mask_image.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > jsk_perception::ApplyMaskImage::ApproximateSyncPolicy |
Definition at line 54 of file apply_mask_image.h.
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > jsk_perception::ApplyMaskImage::SyncPolicy |
Definition at line 57 of file apply_mask_image.h.
jsk_perception::ApplyMaskImage::ApplyMaskImage | ( | ) | [inline] |
Definition at line 58 of file apply_mask_image.h.
void jsk_perception::ApplyMaskImage::apply | ( | const sensor_msgs::Image::ConstPtr & | image_msg, |
const sensor_msgs::Image::ConstPtr & | mask_msg | ||
) | [protected, virtual] |
Definition at line 77 of file apply_mask_image.cpp.
void jsk_perception::ApplyMaskImage::onInit | ( | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 44 of file apply_mask_image.cpp.
void jsk_perception::ApplyMaskImage::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 55 of file apply_mask_image.cpp.
void jsk_perception::ApplyMaskImage::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 71 of file apply_mask_image.cpp.
bool jsk_perception::ApplyMaskImage::approximate_sync_ [protected] |
Definition at line 68 of file apply_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_perception::ApplyMaskImage::async_ [protected] |
Definition at line 71 of file apply_mask_image.h.
bool jsk_perception::ApplyMaskImage::mask_black_to_transparent_ [protected] |
Definition at line 69 of file apply_mask_image.h.
Definition at line 74 of file apply_mask_image.h.
Definition at line 75 of file apply_mask_image.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ApplyMaskImage::sub_image_ [protected] |
Definition at line 72 of file apply_mask_image.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ApplyMaskImage::sub_mask_ [protected] |
Definition at line 73 of file apply_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::ApplyMaskImage::sync_ [protected] |
Definition at line 70 of file apply_mask_image.h.