#include <apply_mask_image.h>
|
virtual void | apply (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg) |
|
virtual void | infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg) |
|
virtual void | onInit () |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
Definition at line 82 of file apply_mask_image.h.
◆ ApproximateSyncPolicy
◆ SyncPolicy
◆ ApplyMaskImage()
jsk_perception::ApplyMaskImage::ApplyMaskImage |
( |
| ) |
|
|
inline |
◆ ~ApplyMaskImage()
jsk_perception::ApplyMaskImage::~ApplyMaskImage |
( |
| ) |
|
|
virtual |
◆ apply()
void jsk_perception::ApplyMaskImage::apply |
( |
const sensor_msgs::Image::ConstPtr & |
image_msg, |
|
|
const sensor_msgs::Image::ConstPtr & |
mask_msg |
|
) |
| |
|
protectedvirtual |
◆ infoCallback()
void jsk_perception::ApplyMaskImage::infoCallback |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
info_msg | ) |
|
|
protectedvirtual |
◆ onInit()
void jsk_perception::ApplyMaskImage::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_perception::ApplyMaskImage::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_perception::ApplyMaskImage::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ approximate_sync_
bool jsk_perception::ApplyMaskImage::approximate_sync_ |
|
protected |
◆ async_
◆ camera_info_
sensor_msgs::CameraInfo::ConstPtr jsk_perception::ApplyMaskImage::camera_info_ |
|
protected |
◆ clip_
bool jsk_perception::ApplyMaskImage::clip_ |
|
protected |
◆ cval_
int jsk_perception::ApplyMaskImage::cval_ |
|
protected |
◆ mask_black_to_transparent_
bool jsk_perception::ApplyMaskImage::mask_black_to_transparent_ |
|
protected |
◆ max_interval_duration_
double jsk_perception::ApplyMaskImage::max_interval_duration_ |
|
protected |
◆ mutex_
boost::mutex jsk_perception::ApplyMaskImage::mutex_ |
|
protected |
◆ negative_
bool jsk_perception::ApplyMaskImage::negative_ |
|
protected |
◆ negative_before_clip_
bool jsk_perception::ApplyMaskImage::negative_before_clip_ |
|
protected |
◆ pub_camera_info_
◆ pub_image_
◆ pub_mask_
◆ queue_size_
int jsk_perception::ApplyMaskImage::queue_size_ |
|
protected |
◆ sub_camera_info_
◆ sub_image_
◆ sub_info_
◆ sub_mask_
◆ sync_
◆ use_rectified_image_
bool jsk_perception::ApplyMaskImage::use_rectified_image_ |
|
protected |
The documentation for this class was generated from the following files: