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"
81 int syncQueueSize = 10;
82 bool approxSync =
false;
83 double approxSyncMaxInterval = 0.0;
84 pnh.
param(
"approx_sync", approxSync, approxSync);
86 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
87 pnh.
param(
"topic_queue_size", queueSize, queueSize);
90 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
91 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
92 "to \"sync_queue_size\" and will be removed "
93 "in future versions! The value (%d) is still copied to "
94 "\"sync_queue_size\".", syncQueueSize);
98 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
114 if(approxSyncMaxInterval>0.0)
116 approxSync_->registerCallback(boost::bind(&
StereoSync::callback,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
121 exactSync_->registerCallback(boost::bind(&
StereoSync::callback,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
138 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
140 approxSync?
"approx":
"exact",
141 approxSync&&approxSyncMaxInterval!=0.0?
uFormat(
", max interval=%fs", approxSyncMaxInterval).
c_str():
"",
150 uFormat(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "
151 "published (\"$ rostopic hz my_topic\") and the timestamps in their "
152 "header are set. %s%s",
154 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "
155 "topics should have all the exact timestamp for the callback to be called.",
156 subscribedTopicsMsg.c_str()));
161 const sensor_msgs::ImageConstPtr& imageLeft,
162 const sensor_msgs::ImageConstPtr& imageRight,
163 const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
164 const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
170 double leftStamp = imageLeft->header.stamp.toSec();
171 double rightStamp = imageRight->header.stamp.toSec();
172 double leftInfoStamp = cameraInfoLeft->header.stamp.toSec();
173 double rightInfoStamp = cameraInfoRight->header.stamp.toSec();
175 double stampDiff =
fabs(leftStamp - rightStamp);
176 if(stampDiff > 0.010)
178 NODELET_WARN(
"The time difference between left and right frames is "
179 "high (diff=%fs, left=%fs, right=%fs). If your left and right cameras are hardware "
180 "synchronized, use approx_sync:=false. Otherwise, you may want "
181 "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations.",
187 rtabmap_msgs::RGBDImage
msg;
188 msg.header.frame_id = cameraInfoLeft->header.frame_id;
189 msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
190 msg.rgb_camera_info = *cameraInfoLeft;
191 msg.depth_camera_info = *cameraInfoRight;
195 bool publishCompressed =
true;
201 publishCompressed =
false;
205 if(publishCompressed)
209 rtabmap_msgs::RGBDImage msgCompressed =
msg;
212 imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed,
cv_bridge::JPG);
215 imageDepthPtr->toCompressedImageMsg(msgCompressed.depth_compressed,
cv_bridge::JPG);
223 msg.rgb = *imageLeft;
224 msg.depth = *imageRight;
228 if( leftStamp != imageLeft->header.stamp.toSec() ||
229 rightStamp != imageRight->header.stamp.toSec())
231 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make "
232 "sure the node publishing the topics doesn't override the same data after publishing them. A "
233 "solution is to use this node within another nodelet manager. Stamps: "
234 "left%f->%f right=%f->%f",
235 leftStamp, imageLeft->header.stamp.toSec(),
236 rightStamp, imageRight->header.stamp.toSec());