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 pnh.
param(
"approx_sync", approxSync, approxSync);
96 pnh.
param(
"queue_size", queueSize, queueSize);
139 std::string subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s",
141 approxSync?
"approx":
"exact",
150 void warningLoop(
const std::string & subscribedTopicsMsg,
bool approxSync)
158 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 159 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 160 "header are set. %s%s",
162 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input " 163 "topics should have all the exact timestamp for the callback to be called.",
164 subscribedTopicsMsg.c_str());
170 const sensor_msgs::ImageConstPtr& image,
171 const sensor_msgs::ImageConstPtr& depth,
172 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
177 double rgbStamp = image->header.stamp.toSec();
178 double depthStamp = depth->header.stamp.toSec();
179 double infoStamp = cameraInfo->header.stamp.toSec();
181 rtabmap_ros::RGBDImage msg;
182 msg.header.frame_id = cameraInfo->header.frame_id;
183 msg.header.stamp = image->header.stamp>depth->header.stamp?image->header.stamp:depth->header.stamp;
186 ROS_WARN(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! " 187 "Images won't be resized.",
decimation_, depth->width, depth->height);
193 sensor_msgs::CameraInfo info;
195 info.header = cameraInfo->header;
196 msg.rgb_camera_info = info;
197 msg.depth_camera_info = info;
201 msg.rgb_camera_info = *cameraInfo;
202 msg.depth_camera_info = *cameraInfo;
209 rgbMat = imagePtr->image;
210 depthMat = imageDepthPtr->image;
225 bool publishCompressed =
true;
231 publishCompressed =
false;
235 if(publishCompressed)
239 rtabmap_ros::RGBDImage msgCompressed;
240 msgCompressed.header = msg.header;
241 msgCompressed.rgb_camera_info = msg.rgb_camera_info;
242 msgCompressed.depth_camera_info = msg.depth_camera_info;
245 cvImg.
header = image->header;
246 cvImg.
image = rgbMat;
250 msgCompressed.depth_compressed.header = imageDepthPtr->header;
253 msgCompressed.depth_compressed.format =
"png";
262 cvImg.
header = image->header;
263 cvImg.
image = rgbMat;
268 cvDepth.
header = depth->header;
269 cvDepth.
image = depthMat;
276 if( rgbStamp != image->header.stamp.toSec() ||
277 depthStamp != depth->header.stamp.toSec())
279 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make " 280 "sure the node publishing the topics doesn't override the same data after publishing them. A " 281 "solution is to use this node within another nodelet manager. Stamps: " 282 "rgb=%f->%f depth=%f->%f",
283 rgbStamp, image->header.stamp.toSec(),
284 depthStamp, depth->header.stamp.toSec());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
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
void publish(const boost::shared_ptr< M > &message) const
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
const std::string & getName() 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_
ros::NodeHandle & getPrivateNodeHandle() const
std::vector< unsigned char > RTABMAP_EXP compressImage(const cv::Mat &image, const std::string &format=".png")
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
sensor_msgs::CompressedImagePtr toCompressedImageMsg(const Format dst_format=JPG) const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#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)
ros::Time lastCompressedPublished_
image_transport::SubscriberFilter imageDepthSub_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
boost::thread * warningThread_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
#define NODELET_DEBUG(...)
std::string getTopic() const
sensor_msgs::ImagePtr toImageMsg() const
CameraModel scaled(double scale) const
ros::Publisher rgbdImageCompressedPub_