3 #include <sensor_msgs/Image.h>
4 #include <sensor_msgs/CameraInfo.h>
5 #include <sensor_msgs/PointCloud2.h>
13 class RgbdImageTransport;
72 void publish(
const sensor_msgs::Image& rgb_image,
const sensor_msgs::CameraInfo& rgb_info,
73 const sensor_msgs::Image& depth_image,
const sensor_msgs::CameraInfo& depth_info)
const;
78 void publish(
const sensor_msgs::Image& rgb_image,
const sensor_msgs::CameraInfo& rgb_info,
79 const sensor_msgs::Image& depth_image,
const sensor_msgs::CameraInfo& depth_info,
80 const sensor_msgs::PointCloud2& pcl)
const;
85 void publish(
const sensor_msgs::ImageConstPtr& rgb_image,
const sensor_msgs::CameraInfoConstPtr& rgb_info,
86 const sensor_msgs::ImageConstPtr& depth_image,
const sensor_msgs::CameraInfoConstPtr& depth_info)
const;
91 void publish(
const sensor_msgs::ImageConstPtr& rgb_image,
const sensor_msgs::CameraInfoConstPtr& rgb_info,
92 const sensor_msgs::ImageConstPtr& depth_image,
const sensor_msgs::CameraInfoConstPtr& depth_info,
93 const sensor_msgs::PointCloud2ConstPtr& pcl)
const;
102 void publish(sensor_msgs::Image& rgb_image, sensor_msgs::CameraInfo& rgb_info,
103 sensor_msgs::Image& depth_image, sensor_msgs::CameraInfo& depth_info,
ros::Time stamp)
const;
112 void publish(sensor_msgs::Image& rgb_image, sensor_msgs::CameraInfo& rgb_info,
113 sensor_msgs::Image& depth_image, sensor_msgs::CameraInfo& depth_info,
114 sensor_msgs::PointCloud2& pcl,
ros::Time stamp)
const;
121 explicit operator void*()
const;
128 const std::string& rgb_base_topic,
const std::string& depth_base_topic,
size_t queue_size,
140 const std::string& rgb_base_topic,
const std::string& depth_base_topic,
const std::string& pcl_topic,
155 std::shared_ptr<Impl>
impl;