Protected Types | Protected Member Functions | Protected Attributes
jsk_pcl_ros::DepthImageCreator Class Reference

#include <depth_image_creator.h>

Inheritance diagram for jsk_pcl_ros::DepthImageCreator:
Inheritance graph
[legend]

List of all members.

Protected Types

typedef pcl::PointXYZ Point
typedef pcl::PointCloud< PointPointCloud

Protected Member Functions

void callback_cloud (const sensor_msgs::PointCloud2ConstPtr &pcloud2)
void callback_info (const sensor_msgs::CameraInfoConstPtr &info)
void callback_sync (const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
void onInit ()
void publish_points (const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
bool service_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void subscribe ()
void unsubscribe ()

Protected Attributes

tf::StampedTransform fixed_transform
int info_counter_
int info_throttle_
int max_queue_size_
boost::mutex mutex_points
sensor_msgs::PointCloud2ConstPtr points_ptr_
ros::Publisher pub_cloud_
ros::Publisher pub_disp_image_
ros::Publisher pub_image_
double scale_depth
ros::ServiceServer service_
ros::Subscriber sub_as_cloud_
ros::Subscriber sub_as_info_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub_cloud_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_info_
boost::shared_ptr
< message_filters::Synchronizer
< message_filters::sync_policies::ApproximateTime
< sensor_msgs::CameraInfo,
sensor_msgs::PointCloud2 > > > 
sync_inputs_a_
boost::shared_ptr
< message_filters::Synchronizer
< message_filters::sync_policies::ExactTime
< sensor_msgs::CameraInfo,
sensor_msgs::PointCloud2 > > > 
sync_inputs_e_
tf::TransformListenertf_listener_
bool use_approximate
bool use_asynchronous
bool use_fixed_transform
bool use_service

Detailed Description

Definition at line 68 of file depth_image_creator.h.


Member Typedef Documentation

typedef pcl::PointXYZ jsk_pcl_ros::DepthImageCreator::Point [protected]

Definition at line 95 of file depth_image_creator.h.

Definition at line 96 of file depth_image_creator.h.


Member Function Documentation

void jsk_pcl_ros::DepthImageCreator::callback_cloud ( const sensor_msgs::PointCloud2ConstPtr &  pcloud2) [protected]

Definition at line 142 of file depth_image_creator_nodelet.cpp.

void jsk_pcl_ros::DepthImageCreator::callback_info ( const sensor_msgs::CameraInfoConstPtr &  info) [protected]

Definition at line 148 of file depth_image_creator_nodelet.cpp.

void jsk_pcl_ros::DepthImageCreator::callback_sync ( const sensor_msgs::CameraInfoConstPtr &  info,
const sensor_msgs::PointCloud2ConstPtr &  pcloud2 
) [protected]

Definition at line 136 of file depth_image_creator_nodelet.cpp.

void jsk_pcl_ros::DepthImageCreator::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 39 of file depth_image_creator_nodelet.cpp.

void jsk_pcl_ros::DepthImageCreator::publish_points ( const sensor_msgs::CameraInfoConstPtr &  info,
const sensor_msgs::PointCloud2ConstPtr &  pcloud2 
) [protected]

Definition at line 159 of file depth_image_creator_nodelet.cpp.

bool jsk_pcl_ros::DepthImageCreator::service_cb ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 131 of file depth_image_creator_nodelet.cpp.

void jsk_pcl_ros::DepthImageCreator::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::DepthImageCreator::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 92 of file depth_image_creator.h.

Definition at line 90 of file depth_image_creator.h.

Definition at line 89 of file depth_image_creator.h.

Definition at line 91 of file depth_image_creator.h.

Definition at line 84 of file depth_image_creator.h.

sensor_msgs::PointCloud2ConstPtr jsk_pcl_ros::DepthImageCreator::points_ptr_ [protected]

Definition at line 80 of file depth_image_creator.h.

Definition at line 76 of file depth_image_creator.h.

Definition at line 77 of file depth_image_creator.h.

Definition at line 75 of file depth_image_creator.h.

Definition at line 94 of file depth_image_creator.h.

Definition at line 78 of file depth_image_creator.h.

Definition at line 74 of file depth_image_creator.h.

Definition at line 73 of file depth_image_creator.h.

Definition at line 72 of file depth_image_creator.h.

Definition at line 71 of file depth_image_creator.h.

boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > jsk_pcl_ros::DepthImageCreator::sync_inputs_a_ [protected]

Definition at line 83 of file depth_image_creator.h.

boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > jsk_pcl_ros::DepthImageCreator::sync_inputs_e_ [protected]

Definition at line 82 of file depth_image_creator.h.

Definition at line 93 of file depth_image_creator.h.

Definition at line 88 of file depth_image_creator.h.

Definition at line 87 of file depth_image_creator.h.

Definition at line 85 of file depth_image_creator.h.

Definition at line 86 of file depth_image_creator.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49