30 #include <opencv2/imgproc/imgproc.hpp>
38 subscribeDepth_(subscribeDepth),
45 qRegisterMetaType<ros::Time>(
"ros::Time");
46 qRegisterMetaType<cv::Mat>(
"cv::Mat");
56 bool approxSync =
true;
57 pnh.
param(
"queue_size", queueSize, queueSize);
58 pnh.
param(
"approx_sync", approxSync, approxSync);
59 ROS_INFO(
"find_object_ros: queue_size = %d", queueSize);
60 ROS_INFO(
"find_object_ros: approx_sync = %s", approxSync?
"true":
"false");
78 boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
84 boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
144 Q_EMIT
imageReceived(image,
Header(msg->header.frame_id.c_str(), msg->header.stamp.sec, msg->header.stamp.nsec), cv::Mat(), 0.0f);
148 ROS_ERROR(
"find_object_ros: Could not convert input image to mono8 or bgr8 format, encoding detected is %s... cv_bridge exception: %s", msg->encoding.c_str(), e.what());
154 const sensor_msgs::ImageConstPtr& rgbMsg,
155 const sensor_msgs::ImageConstPtr& depthMsg,
156 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
161 ROS_ERROR(
"find_object_ros: Depth image type must be 32FC1 or 16UC1");
165 if(rgbMsg->data.size())
169 float depthConstant = 1.0f/cameraInfoMsg->K[4];
185 Q_EMIT
imageReceived(image,
Header(rgbMsg->header.frame_id.c_str(), rgbMsg->header.stamp.sec, rgbMsg->header.stamp.nsec), ptrDepth->image, depthConstant);
189 ROS_ERROR(
"find_object_ros: Could not convert input image to mono8 or bgr8 format, encoding detected is %s... cv_bridge exception: %s", rgbMsg->encoding.c_str(), e.what());