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"    90                 bool approxSync = 
false;
    91                 double approxSyncMaxInterval = 0.0;
    92                 pnh.
param(
"approx_sync", approxSync, approxSync);
    94                         pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
    95                 pnh.
param(
"queue_size", queueSize, queueSize);
    99                 NODELET_INFO(
"%s: approx_sync_max_interval = %f", 
getName().c_str(), approxSyncMaxInterval);
   109                         if(approxSyncMaxInterval>0.0)
   111                         approxSync_->registerCallback(boost::bind(&
StereoSync::callback, 
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   116                         exactSync_->registerCallback(boost::bind(&
StereoSync::callback, 
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   133                 std::string subscribedTopicsMsg = 
uFormat(
"\n%s subscribed to (%s sync%s):\n   %s \\\n   %s \\\n   %s \\\n   %s",
   135                                                         approxSync?
"approx":
"exact",
   136                                                         approxSync&&approxSyncMaxInterval!=0.0?
uFormat(
", max interval=%fs", approxSyncMaxInterval).c_str():
"",
   146         void warningLoop(
const std::string & subscribedTopicsMsg, 
bool approxSync)
   154                                 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "   155                                                 "published (\"$ rostopic hz my_topic\") and the timestamps in their "   156                                                 "header are set. %s%s",
   158                                                 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "   159                                                         "topics should have all the exact timestamp for the callback to be called.",
   160                                                 subscribedTopicsMsg.c_str());
   166                           const sensor_msgs::ImageConstPtr& imageLeft,
   167                           const sensor_msgs::ImageConstPtr& imageRight,
   168                           const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
   169                           const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
   174                         double leftStamp = imageLeft->header.stamp.toSec();
   175                         double rightStamp = imageRight->header.stamp.toSec();
   176                         double leftInfoStamp = cameraInfoLeft->header.stamp.toSec();
   177                         double rightInfoStamp = cameraInfoRight->header.stamp.toSec();
   179                         double stampDiff = fabs(leftStamp - rightStamp);
   180                         if(stampDiff > 0.010)
   182                                 NODELET_WARN(
"The time difference between left and right frames is "   183                                                 "high (diff=%fs, left=%fs, right=%fs). If your left and right cameras are hardware "   184                                                 "synchronized, use approx_sync:=false. Otherwise, you may want "   185                                                 "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations.",
   191                         rtabmap_ros::RGBDImage msg;
   192                         msg.header.frame_id = cameraInfoLeft->header.frame_id;
   193                         msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
   194                         msg.rgb_camera_info = *cameraInfoLeft;
   195                         msg.depth_camera_info = *cameraInfoRight;
   199                                 bool publishCompressed = 
true;
   205                                                 publishCompressed = 
false;
   209                                 if(publishCompressed)
   213                                         rtabmap_ros::RGBDImage msgCompressed = msg;
   216                                         imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, 
cv_bridge::JPG);
   219                                         imageDepthPtr->toCompressedImageMsg(msgCompressed.depth_compressed, 
cv_bridge::JPG);
   227                                 msg.rgb = *imageLeft;
   228                                 msg.depth = *imageRight;
   232                         if( leftStamp != imageLeft->header.stamp.toSec() ||
   233                                 rightStamp != imageRight->header.stamp.toSec())
   235                                 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make "   236                                                 "sure the node publishing the topics doesn't override the same data after publishing them. A "   237                                                 "solution is to use this node within another nodelet manager. Stamps: "   238                                                 "left%f->%f right=%f->%f",
   239                                                 leftStamp, imageLeft->header.stamp.toSec(),
   240                                                 rightStamp, imageRight->header.stamp.toSec());
 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
std::string getTopic() const
ros::NodeHandle & getNodeHandle() const
image_transport::SubscriberFilter imageLeftSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeftSub_
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
const std::string & getName() 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
ros::Publisher rgbdImageCompressedPub_
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRightSub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
#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)
boost::thread * warningThread_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
std::string getTopic() const
uint32_t getNumSubscribers() const
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &cameraInfoLeft, const sensor_msgs::CameraInfoConstPtr &cameraInfoRight)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
image_transport::SubscriberFilter imageRightSub_
#define NODELET_DEBUG(...)
ros::Time lastCompressedPublished_