#include <multiply_mask_image.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image > | ApproxSyncPolicy |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, sensor_msgs::Image > | SyncPolicy |
Public Member Functions | |
MultiplyMaskImage () | |
Protected Member Functions | |
virtual void | multiply (const sensor_msgs::Image::ConstPtr &src1_msg, const sensor_msgs::Image::ConstPtr &src2_msg) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
bool | approximate_sync_ |
boost::shared_ptr < message_filters::Synchronizer < ApproxSyncPolicy > > | async_ |
ros::Publisher | pub_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_src1_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_src2_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
Definition at line 50 of file multiply_mask_image.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > jsk_perception::MultiplyMaskImage::ApproxSyncPolicy |
Definition at line 58 of file multiply_mask_image.h.
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > jsk_perception::MultiplyMaskImage::SyncPolicy |
Definition at line 55 of file multiply_mask_image.h.
jsk_perception::MultiplyMaskImage::MultiplyMaskImage | ( | ) | [inline] |
Definition at line 60 of file multiply_mask_image.h.
void jsk_perception::MultiplyMaskImage::multiply | ( | const sensor_msgs::Image::ConstPtr & | src1_msg, |
const sensor_msgs::Image::ConstPtr & | src2_msg | ||
) | [protected, virtual] |
Definition at line 73 of file multiply_mask_image.cpp.
void jsk_perception::MultiplyMaskImage::onInit | ( | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 43 of file multiply_mask_image.cpp.
void jsk_perception::MultiplyMaskImage::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 51 of file multiply_mask_image.cpp.
void jsk_perception::MultiplyMaskImage::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 67 of file multiply_mask_image.cpp.
bool jsk_perception::MultiplyMaskImage::approximate_sync_ [protected] |
Definition at line 69 of file multiply_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<ApproxSyncPolicy> > jsk_perception::MultiplyMaskImage::async_ [protected] |
Definition at line 74 of file multiply_mask_image.h.
Definition at line 70 of file multiply_mask_image.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_perception::MultiplyMaskImage::sub_src1_ [protected] |
Definition at line 71 of file multiply_mask_image.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_perception::MultiplyMaskImage::sub_src2_ [protected] |
Definition at line 72 of file multiply_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::MultiplyMaskImage::sync_ [protected] |
Definition at line 73 of file multiply_mask_image.h.