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);
85 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
86 pnh.
param(
"topic_queue_size", queueSize, queueSize);
89 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
90 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
91 "to \"sync_queue_size\" and will be removed "
92 "in future versions! The value (%d) is copied to "
93 "\"sync_queue_size\".", syncQueueSize);
97 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
114 if(approxSyncMaxInterval > 0.0)
132 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s",
134 approxSync?
"approx":
"exact",
142 uFormat(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "
143 "published (\"$ rostopic hz my_topic\") and the timestamps in their "
144 "header are set. %s%s",
146 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "
147 "topics should have all the exact timestamp for the callback to be called.",
148 subscribedTopicsMsg.c_str()));
152 const sensor_msgs::ImageConstPtr& image,
153 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
159 double stamp = image->header.stamp.toSec();
161 rtabmap_msgs::RGBDImage
msg;
162 msg.header.frame_id = cameraInfo->header.frame_id;
163 msg.header.stamp = image->header.stamp;
164 msg.rgb_camera_info = *cameraInfo;
168 bool publishCompressed =
true;
174 publishCompressed =
false;
178 if(publishCompressed)
182 rtabmap_msgs::RGBDImage msgCompressed =
msg;
185 imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed,
cv_bridge::JPG);
197 if( stamp != image->header.stamp.toSec())
199 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make "
200 "sure the node publishing the topics doesn't override the same data after publishing them. A "
201 "solution is to use this node within another nodelet manager. Stamps: "
203 stamp, image->header.stamp.toSec());