#include <point_indices_to_mask_image.h>
|
virtual void | convertAndPublish (const PCLIndicesMsg::ConstPtr &indices_msg, const int width, const int height) |
|
virtual void | mask (const PCLIndicesMsg::ConstPtr &indices_msg) |
|
virtual void | mask (const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::Image::ConstPtr &image_msg) |
|
virtual void | onInit () |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
◆ ApproximateSyncPolicy
◆ SyncPolicy
◆ PointIndicesToMaskImage()
jsk_pcl_ros_utils::PointIndicesToMaskImage::PointIndicesToMaskImage |
( |
| ) |
|
|
inline |
◆ ~PointIndicesToMaskImage()
jsk_pcl_ros_utils::PointIndicesToMaskImage::~PointIndicesToMaskImage |
( |
| ) |
|
|
virtual |
◆ convertAndPublish()
void jsk_pcl_ros_utils::PointIndicesToMaskImage::convertAndPublish |
( |
const PCLIndicesMsg::ConstPtr & |
indices_msg, |
|
|
const int |
width, |
|
|
const int |
height |
|
) |
| |
|
protectedvirtual |
◆ mask() [1/2]
void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask |
( |
const PCLIndicesMsg::ConstPtr & |
indices_msg | ) |
|
|
protectedvirtual |
◆ mask() [2/2]
void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask |
( |
const PCLIndicesMsg::ConstPtr & |
indices_msg, |
|
|
const sensor_msgs::Image::ConstPtr & |
image_msg |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros_utils::PointIndicesToMaskImage::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros_utils::PointIndicesToMaskImage::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros_utils::PointIndicesToMaskImage::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ approximate_sync_
bool jsk_pcl_ros_utils::PointIndicesToMaskImage::approximate_sync_ |
|
protected |
◆ async_
◆ height_
int jsk_pcl_ros_utils::PointIndicesToMaskImage::height_ |
|
protected |
◆ pub_
◆ queue_size_
int jsk_pcl_ros_utils::PointIndicesToMaskImage::queue_size_ |
|
protected |
◆ static_image_size_
bool jsk_pcl_ros_utils::PointIndicesToMaskImage::static_image_size_ |
|
protected |
◆ sub_image_
◆ sub_input_
◆ sub_input_static_
ros::Subscriber jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_static_ |
|
protected |
◆ sync_
◆ width_
int jsk_pcl_ros_utils::PointIndicesToMaskImage::width_ |
|
protected |
The documentation for this class was generated from the following files: