Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros_utils::PointIndicesToMaskImage Class Reference

#include <point_indices_to_mask_image.h>

Inheritance diagram for jsk_pcl_ros_utils::PointIndicesToMaskImage:
Inheritance graph
[legend]

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 ()
 
virtual ~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< PCLIndicesMsgsub_input_
 
ros::Subscriber sub_input_static_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
int width_
 

Detailed Description

Definition at line 82 of file point_indices_to_mask_image.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

Definition at line 119 of file point_indices_to_mask_image.h.

◆ SyncPolicy

Definition at line 122 of file point_indices_to_mask_image.h.

Constructor & Destructor Documentation

◆ PointIndicesToMaskImage()

jsk_pcl_ros_utils::PointIndicesToMaskImage::PointIndicesToMaskImage ( )
inline

Definition at line 124 of file point_indices_to_mask_image.h.

◆ ~PointIndicesToMaskImage()

jsk_pcl_ros_utils::PointIndicesToMaskImage::~PointIndicesToMaskImage ( )
virtual

Definition at line 53 of file point_indices_to_mask_image_nodelet.cpp.

Member Function Documentation

◆ convertAndPublish()

void jsk_pcl_ros_utils::PointIndicesToMaskImage::convertAndPublish ( const PCLIndicesMsg::ConstPtr &  indices_msg,
const int  width,
const int  height 
)
protectedvirtual

Definition at line 97 of file point_indices_to_mask_image_nodelet.cpp.

◆ mask() [1/2]

void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask ( const PCLIndicesMsg::ConstPtr &  indices_msg)
protectedvirtual

Definition at line 119 of file point_indices_to_mask_image_nodelet.cpp.

◆ mask() [2/2]

void jsk_pcl_ros_utils::PointIndicesToMaskImage::mask ( const PCLIndicesMsg::ConstPtr &  indices_msg,
const sensor_msgs::Image::ConstPtr &  image_msg 
)
protectedvirtual

Definition at line 126 of file point_indices_to_mask_image_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros_utils::PointIndicesToMaskImage::onInit ( )
protectedvirtual

Definition at line 43 of file point_indices_to_mask_image_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros_utils::PointIndicesToMaskImage::subscribe ( )
protectedvirtual

Definition at line 65 of file point_indices_to_mask_image_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros_utils::PointIndicesToMaskImage::unsubscribe ( )
protectedvirtual

Definition at line 89 of file point_indices_to_mask_image_nodelet.cpp.

Member Data Documentation

◆ approximate_sync_

bool jsk_pcl_ros_utils::PointIndicesToMaskImage::approximate_sync_
protected

Definition at line 146 of file point_indices_to_mask_image.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros_utils::PointIndicesToMaskImage::async_
protected

Definition at line 152 of file point_indices_to_mask_image.h.

◆ height_

int jsk_pcl_ros_utils::PointIndicesToMaskImage::height_
protected

Definition at line 150 of file point_indices_to_mask_image.h.

◆ pub_

ros::Publisher jsk_pcl_ros_utils::PointIndicesToMaskImage::pub_
protected

Definition at line 156 of file point_indices_to_mask_image.h.

◆ queue_size_

int jsk_pcl_ros_utils::PointIndicesToMaskImage::queue_size_
protected

Definition at line 147 of file point_indices_to_mask_image.h.

◆ static_image_size_

bool jsk_pcl_ros_utils::PointIndicesToMaskImage::static_image_size_
protected

Definition at line 148 of file point_indices_to_mask_image.h.

◆ sub_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_image_
protected

Definition at line 155 of file point_indices_to_mask_image.h.

◆ sub_input_

message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_
protected

Definition at line 154 of file point_indices_to_mask_image.h.

◆ sub_input_static_

ros::Subscriber jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_static_
protected

Definition at line 153 of file point_indices_to_mask_image.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros_utils::PointIndicesToMaskImage::sync_
protected

Definition at line 151 of file point_indices_to_mask_image.h.

◆ width_

int jsk_pcl_ros_utils::PointIndicesToMaskImage::width_
protected

Definition at line 149 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 Fri May 16 2025 03:11:44