Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros_utils::PointIndicesToMaskImage Class Reference

#include <point_indices_to_mask_image.h>

List of all members.

Public Types

typedef
message_filters::sync_policies::ApproximateTime
< PCLIndicesMsg,
sensor_msgs::Image > 
ApproximateSyncPolicy
typedef
message_filters::sync_policies::ExactTime
< PCLIndicesMsg,
sensor_msgs::Image > 
SyncPolicy

Public Member Functions

 PointIndicesToMaskImage ()

Protected Member Functions

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 ()

Protected Attributes

bool approximate_sync_
boost::shared_ptr
< message_filters::Synchronizer
< ApproximateSyncPolicy > > 
async_
int height_
ros::Publisher pub_
int queue_size_
bool static_image_size_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_image_
message_filters::Subscriber
< PCLIndicesMsg
sub_input_
ros::Subscriber sub_input_static_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
int width_

Detailed Description

Definition at line 50 of file point_indices_to_mask_image.h.


Member Typedef Documentation

Definition at line 55 of file point_indices_to_mask_image.h.

Definition at line 58 of file point_indices_to_mask_image.h.


Constructor & Destructor Documentation

Definition at line 60 of file point_indices_to_mask_image.h.


Member Function Documentation

void jsk_pcl_ros_utils::PointIndicesToMaskImage::convertAndPublish ( const PCLIndicesMsg::ConstPtr &  indices_msg,
const int  width,
const int  height 
) [protected, virtual]

Definition at line 85 of file point_indices_to_mask_image_nodelet.cpp.

void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask ( const PCLIndicesMsg::ConstPtr &  indices_msg) [protected, virtual]

Definition at line 107 of file point_indices_to_mask_image_nodelet.cpp.

void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask ( const PCLIndicesMsg::ConstPtr &  indices_msg,
const sensor_msgs::Image::ConstPtr &  image_msg 
) [protected, virtual]

Definition at line 114 of file point_indices_to_mask_image_nodelet.cpp.

void jsk_pcl_ros_utils::PointIndicesToMaskImage::onInit ( void  ) [protected, virtual]

Definition at line 43 of file point_indices_to_mask_image_nodelet.cpp.

Definition at line 53 of file point_indices_to_mask_image_nodelet.cpp.

Definition at line 77 of file point_indices_to_mask_image_nodelet.cpp.


Member Data Documentation

Definition at line 81 of file point_indices_to_mask_image.h.

Definition at line 87 of file point_indices_to_mask_image.h.

Definition at line 85 of file point_indices_to_mask_image.h.

Definition at line 91 of file point_indices_to_mask_image.h.

Definition at line 82 of file point_indices_to_mask_image.h.

Definition at line 83 of file point_indices_to_mask_image.h.

Definition at line 90 of file point_indices_to_mask_image.h.

Definition at line 89 of file point_indices_to_mask_image.h.

Definition at line 88 of file point_indices_to_mask_image.h.

Definition at line 86 of file point_indices_to_mask_image.h.

Definition at line 84 of file point_indices_to_mask_image.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:40:52