Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_IMAGE_CREATOR_H_ 
   37 #define JSK_PCL_ROS_IMAGE_CREATOR_H_ 
   43 #include <dynamic_reconfigure/server.h> 
   45 #include <pcl/range_image/range_image_planar.h> 
   46 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) 
   47 #include <pcl/common/transforms.h> 
   49 #include <pcl/common/transform.h> 
   52 #include <sensor_msgs/Image.h> 
   53 #include <sensor_msgs/CameraInfo.h> 
   54 #include <sensor_msgs/PointCloud2.h> 
   56 #include <stereo_msgs/DisparityImage.h> 
   58 #include <opencv2/opencv.hpp> 
   60 #include <std_srvs/Empty.h> 
   61 #include <boost/thread/mutex.hpp> 
   63 #include <jsk_topic_tools/connection_based_nodelet.h> 
   68   class DepthImageCreator : 
public jsk_topic_tools::ConnectionBasedNodelet
 
  101     typedef pcl::PointXYZRGB 
Point;
 
  107                      std_srvs::Empty::Response &
res);
 
  109     void callback_sync(
const sensor_msgs::CameraInfoConstPtr& info,
 
  110                        const sensor_msgs::PointCloud2ConstPtr& pcloud2);
 
  112     void callback_cloud(
const sensor_msgs::PointCloud2ConstPtr& pcloud2);
 
  114     void callback_info(
const sensor_msgs::CameraInfoConstPtr& info);
 
  117                         const sensor_msgs::PointCloud2ConstPtr& pcloud2);
 
  
void callback_cloud(const sensor_msgs::PointCloud2ConstPtr &pcloud2)
ros::Publisher pub_cloud_
void callback_sync(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
ros::Subscriber sub_as_cloud_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_a_
tf::StampedTransform fixed_transform
sensor_msgs::PointCloud2ConstPtr points_ptr_
void publish_points(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
ros::Publisher pub_disp_image_
ros::ServiceServer service_
ros::Publisher pub_image_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
boost::mutex mutex_points
bool service_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual ~DepthImageCreator()
void callback_info(const sensor_msgs::CameraInfoConstPtr &info)
pcl::PointCloud< Point > PointCloud
boost::mutex mutex
global mutex.
ros::Publisher pub_depth_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_e_
tf::TransformListener * tf_listener_
ros::Subscriber sub_as_info_
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11