32 #include <sensor_msgs/Image.h>
33 #include <sensor_msgs/CompressedImage.h>
35 #include <sensor_msgs/CameraInfo.h>
45 #include <opencv2/highgui/highgui.hpp>
47 #include <boost/thread.hpp>
49 #include "rtabmap_msgs/RGBDImage.h"
85 void callback(
const rtabmap_msgs::RGBDImageConstPtr& input)
90 sensor_msgs::CameraInfo outputCameraInfo;
91 outputImage.header = outputCameraInfo.header = input->header;
92 outputCameraInfo = input->rgb_camera_info;
94 if(!input->rgb.data.empty())
97 outputImage = input->rgb;
99 else if(!input->rgb_compressed.data.empty())
101 #ifdef CV_BRIDGE_HYDRO
102 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
113 sensor_msgs::CameraInfo outputCameraInfo;
114 outputCameraInfo = input->depth_camera_info;
116 if(!input->depth.data.empty())
119 outputImage = input->depth;
121 else if(!input->depth_compressed.data.empty())
123 #ifdef CV_BRIDGE_HYDRO
124 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
129 outputImage.header = outputCameraInfo.header = input->header;