ros2/CameraROS.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "CameraROS.h"
29 #include "find_object/Settings.h"
30 
31 #include <opencv2/imgproc/imgproc.hpp>
32 #include <sensor_msgs/image_encodings.hpp>
33 
34 using namespace find_object;
35 
36 CameraROS::CameraROS(bool subscribeDepth, rclcpp::Node * node) :
37  node_(node),
38  subscribeDepth_(subscribeDepth),
39  approxSync_(0),
40  exactSync_(0)
41 {
42  qRegisterMetaType<rclcpp::Time>("ros::Time");
43  qRegisterMetaType<cv::Mat>("cv::Mat");
44 
45  if(!subscribeDepth_)
46  {
48  imageSub_ = image_transport::create_subscription(node, "image", std::bind(&CameraROS::imgReceivedCallback, this, std::placeholders::_1), hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
49  }
50  else
51  {
52  int queueSize = 10;
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");
58 
59 
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());
64 
65  if(approxSync)
66  {
68  approxSync_->registerCallback(std::bind(&CameraROS::imgDepthReceivedCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
69  }
70  else
71  {
73  exactSync_->registerCallback(std::bind(&CameraROS::imgDepthReceivedCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
74  }
75  }
76 }
78 {
79  delete approxSync_;
80  delete exactSync_;
81 }
82 
83 void CameraROS::setupExecutor(std::shared_ptr<rclcpp::Node> node)
84 {
85  executor_.add_node(node);
86 }
87 
88 QStringList CameraROS::subscribedTopics() const
89 {
90  QStringList topics;
91  if(subscribeDepth_)
92  {
93  topics.append(rgbSub_.getTopic().c_str());
94  topics.append(depthSub_.getTopic().c_str());
95  topics.append(cameraInfoSub_.getSubscriber()->get_topic_name());
96  }
97  else
98  {
99  topics.append(imageSub_.getTopic().c_str());
100  }
101  return topics;
102 }
103 
104 bool CameraROS::start()
105 {
106  this->startTimer();
107  return true;
108 }
109 
110 void CameraROS::stop()
111 {
112  this->stopTimer();
113 }
114 
116 {
117  executor_.spin_some();
118 }
119 
120 void CameraROS::imgReceivedCallback(const sensor_msgs::msg::Image::ConstSharedPtr msg)
121 {
122  if(msg->data.size())
123  {
124  cv::Mat image;
126  try
127  {
128  if(msg->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
129  msg->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
130  {
131  image = cv_bridge::cvtColor(imgPtr, "mono8")->image;
132  }
133  else
134  {
135  image = cv_bridge::cvtColor(imgPtr, "bgr8")->image;
136  }
137 
138  Q_EMIT imageReceived(image, Header(msg->header.frame_id.c_str(), msg->header.stamp.sec, msg->header.stamp.nanosec), cv::Mat(), 0.0f);
139  }
140  catch(const cv_bridge::Exception & e)
141  {
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());
143  }
144  }
145 }
146 
148  const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
149  const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
150  const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg)
151 {
152  if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
153  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0)
154  {
155  RCLCPP_ERROR(node_->get_logger(), "find_object_ros: Depth image type must be 32FC1 or 16UC1");
156  return;
157  }
158 
159  if(rgbMsg->data.size())
160  {
163  float depthConstant = 1.0f/cameraInfoMsg->k[4];
164 
165  cv::Mat image;
167  try
168  {
169  if(rgbMsg->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
170  rgbMsg->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
171  {
172  image = cv_bridge::cvtColor(imgPtr, "mono8")->image;
173  }
174  else
175  {
176  image = cv_bridge::cvtColor(imgPtr, "bgr8")->image;
177  }
178 
179  Q_EMIT imageReceived(image, Header(rgbMsg->header.frame_id.c_str(), rgbMsg->header.stamp.sec, rgbMsg->header.stamp.nanosec), ptrDepth->image, depthConstant);
180  }
181  catch(const cv_bridge::Exception & e)
182  {
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());
184  }
185  }
186 
187 
188 }
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_
virtual ~CameraROS()
virtual void takeImage()
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)
virtual bool start()
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)
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
const std::string MONO16
image_transport::Subscriber imageSub_
bool subscribeDepth_
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)
virtual void stop()
rclcpp::executors::SingleThreadedExecutor executor_


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09