#include <mask_image_to_point_indices.h>
Public Member Functions | |
MaskImageToPointIndices () | |
Protected Member Functions | |
virtual void | indices (const sensor_msgs::Image::ConstPtr &image_msg) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
ros::Publisher | pub_ |
ros::Subscriber | sub_ |
Private Attributes | |
int | target_channel_ |
bool | use_multi_channels_ |
Definition at line 47 of file mask_image_to_point_indices.h.
Definition at line 50 of file mask_image_to_point_indices.h.
void jsk_pcl_ros_utils::MaskImageToPointIndices::indices | ( | const sensor_msgs::Image::ConstPtr & | image_msg | ) | [protected, virtual] |
Definition at line 69 of file mask_image_to_point_indices_nodelet.cpp.
void jsk_pcl_ros_utils::MaskImageToPointIndices::onInit | ( | void | ) | [protected, virtual] |
Definition at line 43 of file mask_image_to_point_indices_nodelet.cpp.
void jsk_pcl_ros_utils::MaskImageToPointIndices::subscribe | ( | ) | [protected, virtual] |
Definition at line 57 of file mask_image_to_point_indices_nodelet.cpp.
void jsk_pcl_ros_utils::MaskImageToPointIndices::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 64 of file mask_image_to_point_indices_nodelet.cpp.
Definition at line 65 of file mask_image_to_point_indices.h.
Definition at line 64 of file mask_image_to_point_indices.h.
Definition at line 68 of file mask_image_to_point_indices.h.
Definition at line 67 of file mask_image_to_point_indices.h.