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_ros/RGBDImage.h" 94 bool approxSync =
true;
95 double approxSyncMaxInterval = 0.0;
96 pnh.
param(
"approx_sync", approxSync, approxSync);
97 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
98 pnh.
param(
"queue_size", queueSize, queueSize);
110 NODELET_INFO(
"%s: approx_sync_max_interval = %f",
getName().c_str(), approxSyncMaxInterval);
122 if(approxSyncMaxInterval > 0.0)
145 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s",
147 approxSync?
"approx":
"exact",
148 approxSync&&approxSyncMaxInterval!=0.0?
uFormat(
", max interval=%fs", approxSyncMaxInterval).c_str():
"",
157 void warningLoop(
const std::string & subscribedTopicsMsg,
bool approxSync)
165 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 166 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 167 "header are set. %s%s",
169 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input " 170 "topics should have all the exact timestamp for the callback to be called.",
171 subscribedTopicsMsg.c_str());
177 const sensor_msgs::ImageConstPtr& image,
178 const sensor_msgs::ImageConstPtr& depth,
179 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
184 double rgbStamp = image->header.stamp.toSec();
185 double depthStamp = depth->header.stamp.toSec();
186 double infoStamp = cameraInfo->header.stamp.toSec();
188 double stampDiff = fabs(rgbStamp - depthStamp);
189 if(stampDiff > 0.010)
191 NODELET_WARN(
"The time difference between rgb and depth frames is " 192 "high (diff=%fs, rgb=%fs, depth=%fs). You may want " 193 "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations or use " 194 "approx_sync=false if streams have all the exact same timestamp.",
200 rtabmap_ros::RGBDImage msg;
201 msg.header.frame_id = cameraInfo->header.frame_id;
202 msg.header.stamp = image->header.stamp>depth->header.stamp?image->header.stamp:depth->header.stamp;
205 ROS_WARN(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! " 206 "Images won't be resized.",
decimation_, depth->width, depth->height);
212 sensor_msgs::CameraInfo info;
214 info.header = cameraInfo->header;
215 msg.rgb_camera_info = info;
216 msg.depth_camera_info = info;
220 msg.rgb_camera_info = *cameraInfo;
221 msg.depth_camera_info = *cameraInfo;
228 rgbMat = imagePtr->image;
229 depthMat = imageDepthPtr->image;
244 bool publishCompressed =
true;
250 publishCompressed =
false;
254 if(publishCompressed)
258 rtabmap_ros::RGBDImage msgCompressed;
259 msgCompressed.header = msg.header;
260 msgCompressed.rgb_camera_info = msg.rgb_camera_info;
261 msgCompressed.depth_camera_info = msg.depth_camera_info;
264 cvImg.
header = image->header;
265 cvImg.
image = rgbMat;
269 msgCompressed.depth_compressed.header = imageDepthPtr->header;
272 msgCompressed.depth_compressed.format =
"png";
281 cvImg.
header = image->header;
282 cvImg.
image = rgbMat;
287 cvDepth.
header = depth->header;
288 cvDepth.
image = depthMat;
295 if( rgbStamp != image->header.stamp.toSec() ||
296 depthStamp != depth->header.stamp.toSec())
298 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make " 299 "sure the node publishing the topics doesn't override the same data after publishing them. A " 300 "solution is to use this node within another nodelet manager. Stamps: " 301 "rgb=%f->%f depth=%f->%f",
302 rgbStamp, image->header.stamp.toSec(),
303 depthStamp, depth->header.stamp.toSec());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string uFormat(const char *fmt,...)
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
#define NODELET_ERROR(...)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
CameraModel scaled(double scale) const
#define NODELET_WARN(...)
std::string getTopic() const
ros::NodeHandle & getNodeHandle() const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
sensor_msgs::CompressedImagePtr toCompressedImageMsg(const Format dst_format=JPG) const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
image_transport::SubscriberFilter imageSub_
ros::Publisher rgbdImagePub_
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
std::vector< unsigned char > RTABMAP_EXP compressImage(const cv::Mat &image, const std::string &format=".png")
const std::string & getName() const
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
std::string resolveName(const std::string &name, bool remap=true) const
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define NODELET_INFO(...)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
ros::Time lastCompressedPublished_
image_transport::SubscriberFilter imageDepthSub_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
std::string getTopic() const
boost::thread * warningThread_
uint32_t getNumSubscribers() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
#define NODELET_DEBUG(...)
ros::Publisher rgbdImageCompressedPub_