31 #include <opencv2/imgproc/imgproc.hpp> 32 #include <sensor_msgs/image_encodings.hpp> 38 subscribeDepth_(subscribeDepth),
42 qRegisterMetaType<rclcpp::Time>(
"ros::Time");
43 qRegisterMetaType<cv::Mat>(
"cv::Mat");
53 bool approxSync =
true;
54 queueSize = node->declare_parameter(
"queue_size", queueSize);
55 approxSync = node->declare_parameter(
"approx_sync", approxSync);
56 RCLCPP_INFO(node->get_logger(),
"find_object_ros: queue_size = %d", queueSize);
57 RCLCPP_INFO(node->get_logger(),
"find_object_ros: approx_sync = %s", approxSync?
"true":
"false");
61 rgbSub_.
subscribe(node,
"rgb/image_rect_color", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
62 depthSub_.
subscribe(node,
"depth_registered/image_raw", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
63 cameraInfoSub_.
subscribe(node,
"depth_registered/camera_info", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
138 Q_EMIT
imageReceived(image,
Header(msg->header.frame_id.c_str(), msg->header.stamp.sec, msg->header.stamp.nanosec), cv::Mat(), 0.0f);
142 RCLCPP_ERROR(
node_->get_logger(),
"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());
148 const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
149 const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
150 const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg)
155 RCLCPP_ERROR(
node_->get_logger(),
"find_object_ros: Depth image type must be 32FC1 or 16UC1");
159 if(rgbMsg->data.size())
163 float depthConstant = 1.0f/cameraInfoMsg->k[4];
179 Q_EMIT
imageReceived(image,
Header(rgbMsg->header.frame_id.c_str(), rgbMsg->header.stamp.sec, rgbMsg->header.stamp.nanosec), ptrDepth->image, depthConstant);
183 RCLCPP_ERROR(
node_->get_logger(),
"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())
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
std::string getTopic() const
const std::string & getTransport() 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_
void setupExecutor(std::shared_ptr< rclcpp::Node > node)
QStringList subscribedTopics() const
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
const ros::Subscriber & getSubscriber() const
const std::string TYPE_32FC1
CameraROS(bool subscribeDepth, QObject *parent=0)
const std::string TYPE_16UC1
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
rclcpp::executors::SingleThreadedExecutor executor_