Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::DepthImageCreator Class Reference

#include <depth_image_creator.h>

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

Public Member Functions

virtual ~DepthImageCreator ()
 

Protected Types

typedef pcl::PointXYZRGB 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

float fill_value
 
tf::StampedTransform fixed_transform
 
int info_counter_
 
int info_throttle_
 
int max_pub_queue_size_
 
int max_queue_size_
 
int max_sub_queue_size_
 
boost::mutex mutex_points
 
bool organize_cloud_
 
sensor_msgs::PointCloud2ConstPtr points_ptr_
 
ros::Publisher pub_cloud_
 
ros::Publisher pub_depth_
 
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_
 
double tf_duration_
 
tf::TransformListenertf_listener_
 
bool use_approximate
 
bool use_asynchronous
 
bool use_fixed_transform
 
bool use_service
 

Detailed Description

Definition at line 100 of file depth_image_creator.h.

Member Typedef Documentation

◆ Point

typedef pcl::PointXYZRGB jsk_pcl_ros::DepthImageCreator::Point
protected

Definition at line 165 of file depth_image_creator.h.

◆ PointCloud

typedef pcl::PointCloud< Point > jsk_pcl_ros::DepthImageCreator::PointCloud
protected

Definition at line 166 of file depth_image_creator.h.

Constructor & Destructor Documentation

◆ ~DepthImageCreator()

jsk_pcl_ros::DepthImageCreator::~DepthImageCreator ( )
virtual

Definition at line 109 of file depth_image_creator_nodelet.cpp.

Member Function Documentation

◆ callback_cloud()

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

Definition at line 177 of file depth_image_creator_nodelet.cpp.

◆ callback_info()

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

Definition at line 183 of file depth_image_creator_nodelet.cpp.

◆ callback_sync()

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

Definition at line 171 of file depth_image_creator_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::DepthImageCreator::onInit ( )
protected

Definition at line 44 of file depth_image_creator_nodelet.cpp.

◆ publish_points()

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

Definition at line 196 of file depth_image_creator_nodelet.cpp.

◆ service_cb()

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

Definition at line 166 of file depth_image_creator_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::DepthImageCreator::subscribe ( )
protected

Definition at line 121 of file depth_image_creator_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::DepthImageCreator::unsubscribe ( )
protected

Definition at line 150 of file depth_image_creator_nodelet.cpp.

Member Data Documentation

◆ fill_value

float jsk_pcl_ros::DepthImageCreator::fill_value
protected

Definition at line 164 of file depth_image_creator.h.

◆ fixed_transform

tf::StampedTransform jsk_pcl_ros::DepthImageCreator::fixed_transform
protected

Definition at line 160 of file depth_image_creator.h.

◆ info_counter_

int jsk_pcl_ros::DepthImageCreator::info_counter_
protected

Definition at line 156 of file depth_image_creator.h.

◆ info_throttle_

int jsk_pcl_ros::DepthImageCreator::info_throttle_
protected

Definition at line 155 of file depth_image_creator.h.

◆ max_pub_queue_size_

int jsk_pcl_ros::DepthImageCreator::max_pub_queue_size_
protected

Definition at line 158 of file depth_image_creator.h.

◆ max_queue_size_

int jsk_pcl_ros::DepthImageCreator::max_queue_size_
protected

Definition at line 157 of file depth_image_creator.h.

◆ max_sub_queue_size_

int jsk_pcl_ros::DepthImageCreator::max_sub_queue_size_
protected

Definition at line 159 of file depth_image_creator.h.

◆ mutex_points

boost::mutex jsk_pcl_ros::DepthImageCreator::mutex_points
protected

Definition at line 149 of file depth_image_creator.h.

◆ organize_cloud_

bool jsk_pcl_ros::DepthImageCreator::organize_cloud_
protected

Definition at line 154 of file depth_image_creator.h.

◆ points_ptr_

sensor_msgs::PointCloud2ConstPtr jsk_pcl_ros::DepthImageCreator::points_ptr_
protected

Definition at line 145 of file depth_image_creator.h.

◆ pub_cloud_

ros::Publisher jsk_pcl_ros::DepthImageCreator::pub_cloud_
protected

Definition at line 141 of file depth_image_creator.h.

◆ pub_depth_

ros::Publisher jsk_pcl_ros::DepthImageCreator::pub_depth_
protected

Definition at line 139 of file depth_image_creator.h.

◆ pub_disp_image_

ros::Publisher jsk_pcl_ros::DepthImageCreator::pub_disp_image_
protected

Definition at line 142 of file depth_image_creator.h.

◆ pub_image_

ros::Publisher jsk_pcl_ros::DepthImageCreator::pub_image_
protected

Definition at line 140 of file depth_image_creator.h.

◆ scale_depth

double jsk_pcl_ros::DepthImageCreator::scale_depth
protected

Definition at line 162 of file depth_image_creator.h.

◆ service_

ros::ServiceServer jsk_pcl_ros::DepthImageCreator::service_
protected

Definition at line 143 of file depth_image_creator.h.

◆ sub_as_cloud_

ros::Subscriber jsk_pcl_ros::DepthImageCreator::sub_as_cloud_
protected

Definition at line 138 of file depth_image_creator.h.

◆ sub_as_info_

ros::Subscriber jsk_pcl_ros::DepthImageCreator::sub_as_info_
protected

Definition at line 137 of file depth_image_creator.h.

◆ sub_cloud_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::DepthImageCreator::sub_cloud_
protected

Definition at line 136 of file depth_image_creator.h.

◆ sub_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::DepthImageCreator::sub_info_
protected

Definition at line 135 of file depth_image_creator.h.

◆ sync_inputs_a_

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 148 of file depth_image_creator.h.

◆ sync_inputs_e_

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 147 of file depth_image_creator.h.

◆ tf_duration_

double jsk_pcl_ros::DepthImageCreator::tf_duration_
protected

Definition at line 163 of file depth_image_creator.h.

◆ tf_listener_

tf::TransformListener* jsk_pcl_ros::DepthImageCreator::tf_listener_
protected

Definition at line 161 of file depth_image_creator.h.

◆ use_approximate

bool jsk_pcl_ros::DepthImageCreator::use_approximate
protected

Definition at line 153 of file depth_image_creator.h.

◆ use_asynchronous

bool jsk_pcl_ros::DepthImageCreator::use_asynchronous
protected

Definition at line 152 of file depth_image_creator.h.

◆ use_fixed_transform

bool jsk_pcl_ros::DepthImageCreator::use_fixed_transform
protected

Definition at line 150 of file depth_image_creator.h.

◆ use_service

bool jsk_pcl_ros::DepthImageCreator::use_service
protected

Definition at line 151 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 Tue Jan 7 2025 04:05:45