ros1/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 "find_object/Settings.h"
29 
30 #include <opencv2/imgproc/imgproc.hpp>
31 #include "CameraROS.h"
33 
34 using namespace find_object;
35 
36 CameraROS::CameraROS(bool subscribeDepth, QObject * parent) :
37  Camera(parent),
38  subscribeDepth_(subscribeDepth),
39  approxSync_(0),
40  exactSync_(0)
41 {
42  ros::NodeHandle nh; // public
43  ros::NodeHandle pnh("~"); // private
44 
45  qRegisterMetaType<ros::Time>("ros::Time");
46  qRegisterMetaType<cv::Mat>("cv::Mat");
47 
48  if(!subscribeDepth_)
49  {
52  }
53  else
54  {
55  int queueSize = 10;
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");
61 
62  ros::NodeHandle rgb_nh(nh, "rgb");
63  ros::NodeHandle rgb_pnh(pnh, "rgb");
64  ros::NodeHandle depth_nh(nh, "depth_registered");
65  ros::NodeHandle depth_pnh(pnh, "depth_registered");
66  image_transport::ImageTransport rgb_it(rgb_nh);
67  image_transport::ImageTransport depth_it(depth_nh);
68  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
69  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
70 
71  rgbSub_.subscribe(rgb_it, rgb_nh.resolveName("image_rect_color"), 1, hintsRgb);
72  depthSub_.subscribe(depth_it, depth_nh.resolveName("image_raw"), 1, hintsDepth);
73  cameraInfoSub_.subscribe(depth_nh, "camera_info", 1);
74  if(approxSync)
75  {
77  approxSync_->registerCallback(boost::bind(&CameraROS::imgDepthReceivedCallback, this,
78  boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
79  }
80  else
81  {
83  exactSync_->registerCallback(boost::bind(&CameraROS::imgDepthReceivedCallback, this,
84  boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
85  }
86  }
87 }
89 {
90  delete approxSync_;
91  delete exactSync_;
92 }
93 
94 QStringList CameraROS::subscribedTopics() const
95 {
96  QStringList topics;
97  if(subscribeDepth_)
98  {
99  topics.append(rgbSub_.getTopic().c_str());
100  topics.append(depthSub_.getTopic().c_str());
101  topics.append(cameraInfoSub_.getTopic().c_str());
102  }
103  else
104  {
105  topics.append(imageSub_.getTopic().c_str());
106  }
107  return topics;
108 }
109 
111 {
112  this->startTimer();
113  return true;
114 }
115 
117 {
118  this->stopTimer();
119 }
120 
122 {
123  ros::spinOnce();
124 }
125 
126 void CameraROS::imgReceivedCallback(const sensor_msgs::ImageConstPtr & msg)
127 {
128  if(msg->data.size())
129  {
130  cv::Mat image;
132  try
133  {
134  if(msg->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
135  msg->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
136  {
137  image = cv_bridge::cvtColor(imgPtr, "mono8")->image;
138  }
139  else
140  {
141  image = cv_bridge::cvtColor(imgPtr, "bgr8")->image;
142  }
143 
144  Q_EMIT imageReceived(image, Header(msg->header.frame_id.c_str(), msg->header.stamp.sec, msg->header.stamp.nsec), cv::Mat(), 0.0f);
145  }
146  catch(const cv_bridge::Exception & e)
147  {
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());
149  }
150  }
151 }
152 
154  const sensor_msgs::ImageConstPtr& rgbMsg,
155  const sensor_msgs::ImageConstPtr& depthMsg,
156  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
157 {
158  if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
159  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0)
160  {
161  ROS_ERROR("find_object_ros: Depth image type must be 32FC1 or 16UC1");
162  return;
163  }
164 
165  if(rgbMsg->data.size())
166  {
169  float depthConstant = 1.0f/cameraInfoMsg->K[4];
170 
171  cv::Mat image;
173  try
174  {
175  if(rgbMsg->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
176  rgbMsg->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
177  {
178  image = cv_bridge::cvtColor(imgPtr, "mono8")->image;
179  }
180  else
181  {
182  image = cv_bridge::cvtColor(imgPtr, "bgr8")->image;
183  }
184 
185  Q_EMIT imageReceived(image, Header(rgbMsg->header.frame_id.c_str(), rgbMsg->header.stamp.sec, rgbMsg->header.stamp.nsec), ptrDepth->image, depthConstant);
186  }
187  catch(const cv_bridge::Exception & e)
188  {
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());
190  }
191  }
192 
193 
194 }
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_
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_
QStringList subscribedTopics() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
#define ROS_INFO(...)
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
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()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)


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