31 #include <opencv2/imgproc/imgproc.hpp> 38 subscribeDepth_(subscribeDepth)
43 qRegisterMetaType<ros::Time>(
"ros::Time");
44 qRegisterMetaType<cv::Mat>(
"cv::Mat");
54 pnh.
param(
"queue_size", queueSize, queueSize);
55 ROS_INFO(
"find_object_ros: queue_size = %d", queueSize);
114 cv::Mat cpy = ptr->image.clone();
115 Q_EMIT
rosDataReceived(msg->header.frame_id, msg->header.stamp, cv::Mat(), 0.0f);
121 cv::cvtColor(ptr->image, bgr, cv::COLOR_RGB2BGR);
122 Q_EMIT
rosDataReceived(msg->header.frame_id, msg->header.stamp, cv::Mat(), 0.0f);
127 ROS_ERROR(
"find_object_ros: Encoding \"%s\" detected. Supported image encodings are bgr8 and rgb8...", msg->encoding.c_str());
133 const sensor_msgs::ImageConstPtr& rgbMsg,
134 const sensor_msgs::ImageConstPtr& depthMsg,
135 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
143 ROS_ERROR(
"find_object_ros: Input type must be rgb=mono8,rgb8,bgr8 and depth=32FC1,16UC1");
147 if(rgbMsg->data.size())
151 float depthConstant = 1.0f/cameraInfoMsg->K[4];
154 cv::Mat cpy = ptr->image.clone();
155 Q_EMIT
rosDataReceived(rgbMsg->header.frame_id, rgbMsg->header.stamp, ptrDepth->image, depthConstant);
161 cv::cvtColor(ptr->image, bgr, cv::COLOR_RGB2BGR);
162 Q_EMIT
rosDataReceived(rgbMsg->header.frame_id, rgbMsg->header.stamp, ptrDepth->image, depthConstant);
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())
std::string getTopic() const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MySyncPolicy
void rosDataReceived(const std::string &frameId, const ros::Time &stamp, const cv::Mat &depth, float depthConstant)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
std::string resolveName(const std::string &name, bool remap=true) const
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_
std::string getTopic() const
message_filters::Synchronizer< MySyncPolicy > * sync_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
CameraROS(bool subscribeDepth, QObject *parent=0)
const std::string TYPE_16UC1
image_transport::Subscriber imageSub_
QStringList subscribedTopics() const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
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)
ROSCPP_DECL void spinOnce()
std::string getTopic() const