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"
83 void callback(
const rtabmap_msgs::RGBDImageConstPtr& input)
94 rtabmap_msgs::RGBDImage output;
95 output.header = input->header;
96 output.rgb_camera_info = input->rgb_camera_info;
97 output.depth_camera_info = input->depth_camera_info;
98 output.key_points = input->key_points;
99 output.points = input->points;
100 output.descriptors = input->descriptors;
101 output.global_descriptor = input->global_descriptor;
107 if(!input->rgb_compressed.data.empty())
110 output.rgb_compressed = input->rgb_compressed;
112 else if(!input->rgb.data.empty())
114 #ifdef CV_BRIDGE_HYDRO
115 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
122 if(!input->depth_compressed.data.empty())
125 output.depth_compressed = input->depth_compressed;
127 else if(!input->depth.data.empty())
133 imageRightPtr->toCompressedImageMsg(output.depth_compressed,
cv_bridge::JPG);
140 output.depth_compressed.format =
"png";
146 if(!input->rgb.data.empty())
149 output.rgb = input->rgb;
151 if(!input->rgb_compressed.data.empty())
153 #ifdef CV_BRIDGE_HYDRO
154 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
160 if(!input->depth.data.empty())
163 output.depth = input->depth;
165 else if(input->depth_compressed.format.compare(
"jpg")==0)
168 #ifdef CV_BRIDGE_HYDRO
169 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
178 ptr->header = input->depth_compressed.header;
180 ROS_ASSERT(ptr->image.empty() || ptr->image.type() == CV_32FC1 || ptr->image.type() == CV_16UC1);
182 ptr->toImageMsg(output.depth);