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());
 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
std::string getTopic() const
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
image_transport::SubscriberFilter rgbSub_
void imgDepthReceivedCallback(const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
void imgReceivedCallback(const sensor_msgs::ImageConstPtr &msg)
void imageReceived(const cv::Mat &image)
image_transport::SubscriberFilter depthSub_
QStringList subscribedTopics() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
const std::string TYPE_32FC1
CameraROS(bool subscribeDepth, QObject *parent=0)
const std::string TYPE_16UC1
std::string resolveName(const std::string &name, bool remap=true) const
image_transport::Subscriber imageSub_
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 > MyApproxSyncPolicy
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)
std::string getTopic() const
ROSCPP_DECL void spinOnce()