#include <point_indices_to_mask_image.h>
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 () |
virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
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_ |
Definition at line 50 of file point_indices_to_mask_image.h.
typedef message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::Image > jsk_pcl_ros_utils::PointIndicesToMaskImage::ApproximateSyncPolicy |
Definition at line 55 of file point_indices_to_mask_image.h.
typedef message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::Image > jsk_pcl_ros_utils::PointIndicesToMaskImage::SyncPolicy |
Definition at line 58 of file point_indices_to_mask_image.h.
Definition at line 60 of file point_indices_to_mask_image.h.
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] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 43 of file point_indices_to_mask_image_nodelet.cpp.
void jsk_pcl_ros_utils::PointIndicesToMaskImage::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 53 of file point_indices_to_mask_image_nodelet.cpp.
void jsk_pcl_ros_utils::PointIndicesToMaskImage::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 77 of file point_indices_to_mask_image_nodelet.cpp.
void jsk_pcl_ros_utils::PointIndicesToMaskImage::updateDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 122 of file point_indices_to_mask_image_nodelet.cpp.
bool jsk_pcl_ros_utils::PointIndicesToMaskImage::approximate_sync_ [protected] |
Definition at line 83 of file point_indices_to_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros_utils::PointIndicesToMaskImage::async_ [protected] |
Definition at line 89 of file point_indices_to_mask_image.h.
int jsk_pcl_ros_utils::PointIndicesToMaskImage::height_ [protected] |
Definition at line 87 of file point_indices_to_mask_image.h.
Definition at line 93 of file point_indices_to_mask_image.h.
int jsk_pcl_ros_utils::PointIndicesToMaskImage::queue_size_ [protected] |
Definition at line 84 of file point_indices_to_mask_image.h.
bool jsk_pcl_ros_utils::PointIndicesToMaskImage::static_image_size_ [protected] |
Definition at line 85 of file point_indices_to_mask_image.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_image_ [protected] |
Definition at line 92 of file point_indices_to_mask_image.h.
message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_ [protected] |
Definition at line 91 of file point_indices_to_mask_image.h.
Definition at line 90 of file point_indices_to_mask_image.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros_utils::PointIndicesToMaskImage::sync_ [protected] |
Definition at line 88 of file point_indices_to_mask_image.h.
int jsk_pcl_ros_utils::PointIndicesToMaskImage::width_ [protected] |
Definition at line 86 of file point_indices_to_mask_image.h.