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

#include <pointcloud_to_mask_image.h>

List of all members.

Public Types

typedef PointCloudToMaskImageConfig Config

Public Member Functions

 PointCloudToMaskImage ()

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual void convert (const sensor_msgs::Image::ConstPtr &image_msg)
virtual void convert (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

boost::mutex mutex_
ros::Publisher pub_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_cloud_
ros::Subscriber sub_image_
float z_far_
float z_near_

Detailed Description

Definition at line 51 of file pointcloud_to_mask_image.h.


Member Typedef Documentation

typedef PointCloudToMaskImageConfig jsk_pcl_ros_utils::PointCloudToMaskImage::Config

Definition at line 54 of file pointcloud_to_mask_image.h.


Constructor & Destructor Documentation

Definition at line 55 of file pointcloud_to_mask_image.h.


Member Function Documentation

void jsk_pcl_ros_utils::PointCloudToMaskImage::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 72 of file pointcloud_to_mask_image_nodelet.cpp.

void jsk_pcl_ros_utils::PointCloudToMaskImage::convert ( const sensor_msgs::Image::ConstPtr &  image_msg) [protected, virtual]

Definition at line 116 of file pointcloud_to_mask_image_nodelet.cpp.

void jsk_pcl_ros_utils::PointCloudToMaskImage::convert ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg) [protected, virtual]

Definition at line 81 of file pointcloud_to_mask_image_nodelet.cpp.

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

Definition at line 45 of file pointcloud_to_mask_image_nodelet.cpp.

Definition at line 58 of file pointcloud_to_mask_image_nodelet.cpp.

Definition at line 66 of file pointcloud_to_mask_image_nodelet.cpp.


Member Data Documentation

Definition at line 71 of file pointcloud_to_mask_image.h.

Definition at line 75 of file pointcloud_to_mask_image.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros_utils::PointCloudToMaskImage::srv_ [protected]

Definition at line 72 of file pointcloud_to_mask_image.h.

Definition at line 73 of file pointcloud_to_mask_image.h.

Definition at line 74 of file pointcloud_to_mask_image.h.

Definition at line 70 of file pointcloud_to_mask_image.h.

Definition at line 70 of file pointcloud_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