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" 89 bool approxSync =
false;
90 pnh.
param(
"approx_sync", approxSync, approxSync);
91 pnh.
param(
"queue_size", queueSize, queueSize);
124 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s,\n %s,\n %s,\n %s",
126 approxSync?
"approx":
"exact",
136 void warningLoop(
const std::string & subscribedTopicsMsg,
bool approxSync)
144 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 145 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 146 "header are set. %s%s",
148 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input " 149 "topics should have all the exact timestamp for the callback to be called.",
150 subscribedTopicsMsg.c_str());
156 const sensor_msgs::ImageConstPtr& imageLeft,
157 const sensor_msgs::ImageConstPtr& imageRight,
158 const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
159 const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
164 rtabmap_ros::RGBDImage msg;
165 msg.header.frame_id = cameraInfoLeft->header.frame_id;
166 msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
167 msg.rgbCameraInfo = *cameraInfoLeft;
168 msg.depthCameraInfo = *cameraInfoRight;
172 rtabmap_ros::RGBDImage msgCompressed = msg;
175 imagePtr->toCompressedImageMsg(msgCompressed.rgbCompressed,
cv_bridge::JPG);
178 imageDepthPtr->toCompressedImageMsg(msgCompressed.depthCompressed,
cv_bridge::JPG);
185 msg.rgb = *imageLeft;
186 msg.depth = *imageRight;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
std::string uFormat(const char *fmt,...)
void publish(const boost::shared_ptr< M > &message) const
std::string resolveName(const std::string &name, bool remap=true) const
image_transport::SubscriberFilter imageLeftSub_
const std::string & getName() const
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
ros::Publisher rgbdImageCompressedPub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
ros::NodeHandle & getNodeHandle() const
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(...)
uint32_t getNumSubscribers() const
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)
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_
std::string getTopic() const