watershed_segmentation_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Kei Okada.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/watershed.cpp
40 #include <ros/ros.h>
41 #include "opencv_apps/nodelet.h"
43 #include <cv_bridge/cv_bridge.h>
45 
46 #include <opencv2/highgui/highgui.hpp>
47 #include <opencv2/imgproc/imgproc.hpp>
48 
49 #include <dynamic_reconfigure/server.h>
50 #include "opencv_apps/WatershedSegmentationConfig.h"
51 #include "opencv_apps/Contour.h"
52 #include "opencv_apps/ContourArray.h"
53 #include "opencv_apps/ContourArrayStamped.h"
54 #include "opencv_apps/Point2DArray.h"
55 
56 namespace opencv_apps
57 {
59 {
65 
67 
68  typedef opencv_apps::WatershedSegmentationConfig Config;
69  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
70  Config config_;
72 
76 
78  static bool need_config_update_;
79  static bool on_mouse_update_;
80  static int on_mouse_event_;
81  static int on_mouse_x_;
82  static int on_mouse_y_;
83  static int on_mouse_flags_;
84 
85  cv::Mat markerMask, img_gray;
86  cv::Point prevPt;
87 
88  static void onMouse(int event, int x, int y, int flags, void* /*unused*/)
89  {
90  on_mouse_update_ = true;
91  on_mouse_event_ = event;
92  on_mouse_x_ = x;
93  on_mouse_y_ = y;
94  on_mouse_flags_ = flags;
95  }
96 
97  void reconfigureCallback(opencv_apps::WatershedSegmentationConfig& new_config, uint32_t level)
98  {
99  config_ = new_config;
100  }
101 
102  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
103  {
104  if (frame.empty())
105  return image_frame;
106  return frame;
107  }
108 
109  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
110  {
111  doWork(msg, cam_info->header.frame_id);
112  }
113 
114  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
115  {
116  doWork(msg, msg->header.frame_id);
117  }
118 
119  static void trackbarCallback(int /*unused*/, void* /*unused*/)
120  {
121  need_config_update_ = true;
122  }
123 
124  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
125  {
126  // Work on the image.
127  try
128  {
129  // Convert the image into something opencv can handle.
130  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
131 
132  // Messages
133  opencv_apps::ContourArrayStamped contours_msg;
134  contours_msg.header = msg->header;
135 
136  // Do the work
137  // std::vector<cv::Rect> faces;
138 
140  if (markerMask.empty())
141  {
142  cv::cvtColor(frame, markerMask, cv::COLOR_BGR2GRAY);
143  markerMask = cv::Scalar::all(0);
144  }
145  cv::Mat tmp;
146  cv::cvtColor(frame, tmp, cv::COLOR_BGR2GRAY);
147  cv::cvtColor(tmp, img_gray, cv::COLOR_GRAY2BGR);
148 
149  if (debug_view_)
150  {
151  cv::imshow(window_name_, frame);
152  cv::setMouseCallback(window_name_, onMouse, nullptr);
153  if (need_config_update_)
154  {
155  reconfigure_server_->updateConfig(config_);
156  need_config_update_ = false;
157  }
158 
159  if (on_mouse_update_)
160  {
161  int event = on_mouse_event_;
162  int x = on_mouse_x_;
163  int y = on_mouse_y_;
164  int flags = on_mouse_flags_;
165 
166  if (x < 0 || x >= frame.cols || y < 0 || y >= frame.rows)
167  return;
168  if (event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON))
169  prevPt = cv::Point(-1, -1);
170  else if (event == cv::EVENT_LBUTTONDOWN)
171  prevPt = cv::Point(x, y);
172  else if (event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON))
173  {
174  cv::Point pt(x, y);
175  if (prevPt.x < 0)
176  prevPt = pt;
177  cv::line(markerMask, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
178  cv::line(frame, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
179  prevPt = pt;
180  cv::imshow(window_name_, markerMask);
181  }
182  }
183  cv::waitKey(1);
184  }
185 
186  int i, j, comp_count = 0;
187  std::vector<std::vector<cv::Point> > contours;
188  std::vector<cv::Vec4i> hierarchy;
189 
190  cv::findContours(markerMask, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
191 
192  if (contours.empty())
193  {
194  NODELET_WARN("contours are empty");
195  return; // continue;
196  }
197  cv::Mat markers(markerMask.size(), CV_32S);
198  markers = cv::Scalar::all(0);
199  int idx = 0;
200  for (; idx >= 0; idx = hierarchy[idx][0], comp_count++)
201  cv::drawContours(markers, contours, idx, cv::Scalar::all(comp_count + 1), -1, 8, hierarchy, INT_MAX);
202 
203  if (comp_count == 0)
204  {
205  NODELET_WARN("compCount is 0");
206  return; // continue;
207  }
208  for (const std::vector<cv::Point>& contour : contours)
209  {
210  opencv_apps::Contour contour_msg;
211  for (const cv::Point& j : contour)
212  {
213  opencv_apps::Point2D point_msg;
214  point_msg.x = j.x;
215  point_msg.y = j.y;
216  contour_msg.points.push_back(point_msg);
217  }
218  contours_msg.contours.push_back(contour_msg);
219  }
220 
221  std::vector<cv::Vec3b> color_tab;
222  for (i = 0; i < comp_count; i++)
223  {
224  int b = cv::theRNG().uniform(0, 255);
225  int g = cv::theRNG().uniform(0, 255);
226  int r = cv::theRNG().uniform(0, 255);
227 
228  color_tab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r));
229  }
230 
231  double t = (double)cv::getTickCount();
232  cv::watershed(frame, markers);
233  t = (double)cv::getTickCount() - t;
234  NODELET_INFO("execution time = %gms", t * 1000. / cv::getTickFrequency());
235 
236  cv::Mat wshed(markers.size(), CV_8UC3);
237 
238  // paint the watershed image
239  for (i = 0; i < markers.rows; i++)
240  for (j = 0; j < markers.cols; j++)
241  {
242  int index = markers.at<int>(i, j);
243  if (index == -1)
244  wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(255, 255, 255);
245  else if (index <= 0 || index > comp_count)
246  wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(0, 0, 0);
247  else
248  wshed.at<cv::Vec3b>(i, j) = color_tab[index - 1];
249  }
250 
251  wshed = wshed * 0.5 + img_gray * 0.5;
252 
253  //-- Show what you got
254  if (debug_view_)
255  {
256  cv::imshow(segment_name_, wshed);
257 
258  int c = cv::waitKey(1);
259  // if( (char)c == 27 )
260  // break;
261  if ((char)c == 'r')
262  {
263  markerMask = cv::Scalar::all(0);
264  }
265  }
266 
267  // Publish the image.
268  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, wshed).toImageMsg();
269  img_pub_.publish(out_img);
270  msg_pub_.publish(contours_msg);
271  }
272  catch (cv::Exception& e)
273  {
274  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
275  }
276 
277  prev_stamp_ = msg->header.stamp;
278  }
279 
280  void addSeedPointCb(const opencv_apps::Point2DArray& msg)
281  {
282  if (msg.points.empty())
283  {
284  markerMask = cv::Scalar::all(0);
285  }
286  else
287  {
288  for (const opencv_apps::Point2D& point : msg.points)
289  {
290  cv::Point pt0(point.x, point.y);
291  cv::Point pt1(pt0.x + 1, pt0.y + 1);
292  cv::line(markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0);
293  }
294  }
295  }
296 
297  void subscribe() // NOLINT(modernize-use-override)
298  {
299  NODELET_DEBUG("Subscribing to image topic.");
300  if (config_.use_camera_info)
301  cam_sub_ = it_->subscribeCamera("image", queue_size_, &WatershedSegmentationNodelet::imageCallbackWithInfo, this);
302  else
303  img_sub_ = it_->subscribe("image", queue_size_, &WatershedSegmentationNodelet::imageCallback, this);
304  }
305 
306  void unsubscribe() // NOLINT(modernize-use-override)
307  {
308  NODELET_DEBUG("Unsubscribing from image topic.");
309  img_sub_.shutdown();
310  cam_sub_.shutdown();
311  }
312 
313 public:
314  virtual void onInit() // NOLINT(modernize-use-override)
315  {
316  Nodelet::onInit();
318 
319  pnh_->param("queue_size", queue_size_, 3);
320  pnh_->param("debug_view", debug_view_, false);
321  if (debug_view_)
322  {
323  always_subscribe_ = true;
324  }
325  prev_stamp_ = ros::Time(0, 0);
326 
327  window_name_ = "roughly mark the areas to segment on the image";
328  segment_name_ = "watershed transform";
329  prevPt.x = -1;
330  prevPt.y = -1;
331 
332  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
333  dynamic_reconfigure::Server<Config>::CallbackType f =
334  boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2);
335  reconfigure_server_->setCallback(f);
336 
337  add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::addSeedPointCb, this);
338  img_pub_ = advertiseImage(*pnh_, "image", 1);
339  msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
340 
341  NODELET_INFO("This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
342  NODELET_INFO("Hot keys: ");
343  NODELET_INFO("\tESC - quit the program");
344  NODELET_INFO("\tr - restore the original image");
345  NODELET_INFO("\tw or SPACE - run watershed segmentation algorithm");
346  NODELET_INFO("\t\t(before running it, *roughly* mark the areas to segment on the image)");
347  NODELET_INFO("\t (before that, roughly outline several markers on the image)");
348 
350  }
351 };
358 } // namespace opencv_apps
359 
361 {
363 {
364 public:
365  virtual void onInit() // NOLINT(modernize-use-override)
366  {
367  ROS_WARN("DeprecationWarning: Nodelet watershed_segmentation/watershed_segmentation is deprecated, "
368  "and renamed to opencv_apps/watershed_segmentation.");
370  }
371 };
372 } // namespace watershed_segmentation
373 
static void onMouse(int event, int x, int y, int flags, void *)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
f
opencv_apps::WatershedSegmentationConfig Config
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
Demo code to calculate moments.
Definition: nodelet.h:48
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
#define ROS_WARN(...)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
void publish(const sensor_msgs::Image &message) const
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(opencv_apps::WatershedSegmentationConfig &new_config, uint32_t level)
void addSeedPointCb(const opencv_apps::Point2DArray &msg)
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
Definition: nodelet.h:180
#define NODELET_INFO(...)
PLUGINLIB_EXPORT_CLASS(opencv_apps::WatershedSegmentationNodelet, nodelet::Nodelet)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define NODELET_DEBUG(...)
dynamic_reconfigure::Server< Config > ReconfigureServer
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< image_transport::ImageTransport > it_


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08