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 int syncQueueSize = 10;
86 bool approxSync =
true;
87 double approxSyncMaxInterval = 0.0;
88 pnh.
param(
"approx_sync", approxSync, approxSync);
89 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
90 pnh.
param(
"topic_queue_size", queueSize, queueSize);
93 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
94 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
95 "to \"sync_queue_size\" and will be removed "
96 "in future versions! The value (%d) is still copied to "
97 "\"sync_queue_size\".", syncQueueSize);
101 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
127 if(approxSyncMaxInterval > 0.0)
150 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s",
152 approxSync?
"approx":
"exact",
153 approxSync&&approxSyncMaxInterval!=0.0?
uFormat(
", max interval=%fs", approxSyncMaxInterval).
c_str():
"",
161 uFormat(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "
162 "published (\"$ rostopic hz my_topic\") and the timestamps in their "
163 "header are set. %s%s",
165 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "
166 "topics should have all the exact timestamp for the callback to be called.",
167 subscribedTopicsMsg.c_str()));
171 const sensor_msgs::ImageConstPtr& image,
172 const sensor_msgs::ImageConstPtr& depth,
173 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
179 double rgbStamp = image->header.stamp.toSec();
180 double depthStamp = depth->header.stamp.toSec();
181 double infoStamp = cameraInfo->header.stamp.toSec();
183 double stampDiff =
fabs(rgbStamp - depthStamp);
184 if(stampDiff > 0.010)
186 NODELET_WARN(
"The time difference between rgb and depth frames is "
187 "high (diff=%fs, rgb=%fs, depth=%fs). You may want "
188 "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations or use "
189 "approx_sync=false if streams have all the exact same timestamp.",
195 rtabmap_msgs::RGBDImage
msg;
196 msg.header.frame_id = cameraInfo->header.frame_id;
197 msg.header.stamp = image->header.stamp>depth->header.stamp?image->header.stamp:depth->header.stamp;
200 ROS_WARN(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! "
201 "Images won't be resized.",
decimation_, depth->width, depth->height);
207 sensor_msgs::CameraInfo
info;
209 info.header = cameraInfo->header;
215 msg.rgb_camera_info = *cameraInfo;
216 msg.depth_camera_info = *cameraInfo;
223 rgbMat = imagePtr->image;
224 depthMat = imageDepthPtr->image;
239 bool publishCompressed =
true;
245 publishCompressed =
false;
249 if(publishCompressed)
253 rtabmap_msgs::RGBDImage msgCompressed;
254 msgCompressed.header =
msg.header;
255 msgCompressed.rgb_camera_info =
msg.rgb_camera_info;
256 msgCompressed.depth_camera_info =
msg.depth_camera_info;
259 cvImg.
header = image->header;
260 cvImg.
image = rgbMat;
264 msgCompressed.depth_compressed.header = imageDepthPtr->header;
267 msgCompressed.depth_compressed.format =
"png";
276 cvImg.
header = image->header;
277 cvImg.
image = rgbMat;
282 cvDepth.
header = depth->header;
283 cvDepth.
image = depthMat;
290 if( rgbStamp != image->header.stamp.toSec() ||
291 depthStamp != depth->header.stamp.toSec())
293 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make "
294 "sure the node publishing the topics doesn't override the same data after publishing them. A "
295 "solution is to use this node within another nodelet manager. Stamps: "
296 "rgb=%f->%f depth=%f->%f",
297 rgbStamp, image->header.stamp.toSec(),
298 depthStamp, depth->header.stamp.toSec());