camshift_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/camshiftdemo.cpp
42 #include <ros/ros.h>
43 #include "opencv_apps/nodelet.h"
46 #include <cv_bridge/cv_bridge.h>
48 
49 #include <iostream>
50 #include <ctype.h>
51 #include <opencv2/video/tracking.hpp>
52 #include <opencv2/highgui/highgui.hpp>
53 #include <opencv2/imgproc/imgproc.hpp>
54 
55 #include <dynamic_reconfigure/server.h>
56 #include "opencv_apps/CamShiftConfig.h"
57 #include "opencv_apps/RotatedRectStamped.h"
58 
59 namespace opencv_apps
60 {
62 {
67 
69 
70  typedef opencv_apps::CamShiftConfig Config;
71  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
72  Config config_;
74 
78 
80  static bool need_config_update_;
81  static bool on_mouse_update_;
82  static int on_mouse_event_;
83  static int on_mouse_x_;
84  static int on_mouse_y_;
85 
86  int vmin_, vmax_, smin_;
90  bool showHist;
91  cv::Point origin;
92  cv::Rect selection;
93  bool paused;
94 
95  cv::Rect trackWindow;
96  int hsize;
97  float hranges[2];
98  const float* phranges;
99  cv::Mat hist, histimg;
100  // cv::Mat hsv;
101 
102  static void onMouse(int event, int x, int y, int /*unused*/, void* /*unused*/)
103  {
104  on_mouse_update_ = true;
105  on_mouse_event_ = event;
106  on_mouse_x_ = x;
107  on_mouse_y_ = y;
108  }
109 
110  void reconfigureCallback(Config& new_config, uint32_t level)
111  {
112  config_ = new_config;
113  vmin_ = config_.vmin;
114  vmax_ = config_.vmax;
115  smin_ = config_.smin;
116  }
117 
118  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
119  {
120  if (frame.empty())
121  return image_frame;
122  return frame;
123  }
124 
125  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
126  {
127  doWork(msg, cam_info->header.frame_id);
128  }
129 
130  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
131  {
132  doWork(msg, msg->header.frame_id);
133  }
134 
135  static void trackbarCallback(int /*unused*/, void* /*unused*/)
136  {
137  need_config_update_ = true;
138  }
139 
140  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
141  {
142  // Work on the image.
143  try
144  {
145  // Convert the image into something opencv can handle.
146  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
147  cv::Mat backproj;
148 
149  // Messages
150  opencv_apps::RotatedRectStamped rect_msg;
151  rect_msg.header = msg->header;
152 
153  // Do the work
154 
155  if (debug_view_)
156  {
158 
159  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
160 
161  cv::setMouseCallback(window_name_, onMouse, nullptr);
162  cv::createTrackbar("Vmin", window_name_, &vmin_, 256, trackbarCallback);
163  cv::createTrackbar("Vmax", window_name_, &vmax_, 256, trackbarCallback);
164  cv::createTrackbar("Smin", window_name_, &smin_, 256, trackbarCallback);
165 
166  if (need_config_update_)
167  {
168  config_.vmin = vmin_;
169  config_.vmax = vmax_;
170  config_.smin = smin_;
171  reconfigure_server_->updateConfig(config_);
172  need_config_update_ = false;
173  }
174  }
175 
176  if (on_mouse_update_)
177  {
178  int event = on_mouse_event_;
179  int x = on_mouse_x_;
180  int y = on_mouse_y_;
181 
182  if (selectObject)
183  {
184  selection.x = MIN(x, origin.x);
185  selection.y = MIN(y, origin.y);
186  selection.width = std::abs(x - origin.x);
187  selection.height = std::abs(y - origin.y);
188 
189  selection &= cv::Rect(0, 0, frame.cols, frame.rows);
190  }
191 
192  switch (event)
193  {
194  case cv::EVENT_LBUTTONDOWN:
195  origin = cv::Point(x, y);
196  selection = cv::Rect(x, y, 0, 0);
197  selectObject = true;
198  break;
199  case cv::EVENT_LBUTTONUP:
200  selectObject = false;
201  if (selection.width > 0 && selection.height > 0)
202  trackObject = -1;
203  break;
204  }
205  on_mouse_update_ = false;
206  }
207 
208  if (!paused)
209  {
210  cv::Mat hsv, hue, mask;
211  cv::cvtColor(frame, hsv, cv::COLOR_BGR2HSV);
212 
213  if (trackObject)
214  {
215  int vmin = vmin_, vmax = vmax_;
216 
217  cv::inRange(hsv, cv::Scalar(0, smin_, MIN(vmin, vmax)), cv::Scalar(180, 256, MAX(vmin, vmax)), mask);
218  int ch[] = { 0, 0 };
219  hue.create(hsv.size(), hsv.depth());
220  cv::mixChannels(&hsv, 1, &hue, 1, ch, 1);
221 
222  if (trackObject < 0)
223  {
224  cv::Mat roi(hue, selection), maskroi(mask, selection);
225  cv::calcHist(&roi, 1, nullptr, maskroi, hist, 1, &hsize, &phranges);
226  cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX);
227  std::vector<float> hist_value;
228  hist_value.resize(hsize);
229  for (int i = 0; i < hsize; i++)
230  {
231  hist_value[i] = hist.at<float>(i);
232  }
233  pnh_->setParam("histogram", hist_value);
234 
235  trackWindow = selection;
236  trackObject = 1;
237 
238  histimg = cv::Scalar::all(0);
239  int bin_w = histimg.cols / hsize;
240  cv::Mat buf(1, hsize, CV_8UC3);
241  for (int i = 0; i < hsize; i++)
242  buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
243  cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
244 
245  for (int i = 0; i < hsize; i++)
246  {
247  int val = cv::saturate_cast<int>(hist.at<float>(i) * histimg.rows / 255);
248  cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
249  cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
250  }
251  }
252 
253  cv::calcBackProject(&hue, 1, nullptr, hist, backproj, &phranges);
254  backproj &= mask;
255  cv::RotatedRect track_box = cv::CamShift(
256  backproj, trackWindow, cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1));
257  if (trackWindow.area() <= 1)
258  {
259  int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5) / 6;
260  // trackWindow = cv::Rect(trackWindow.x - r, trackWindow.y - r,
261  // trackWindow.x + r, trackWindow.y + r) &
262  trackWindow = cv::Rect(cols / 2 - r, rows / 2 - r, cols / 2 + r, rows / 2 + r) & cv::Rect(0, 0, cols, rows);
263  }
264 
265  if (backprojMode)
266  cv::cvtColor(backproj, frame, cv::COLOR_GRAY2BGR);
267 #ifndef CV_VERSION_EPOCH
268  cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, cv::LINE_AA);
269 #else
270  cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, CV_AA);
271 #endif
272 
273  rect_msg.rect.angle = track_box.angle;
274  opencv_apps::Point2D point_msg;
275  opencv_apps::Size size_msg;
276  point_msg.x = track_box.center.x;
277  point_msg.y = track_box.center.y;
278  size_msg.width = track_box.size.width;
279  size_msg.height = track_box.size.height;
280  rect_msg.rect.center = point_msg;
281  rect_msg.rect.size = size_msg;
282  }
283  }
284  else if (trackObject < 0)
285  paused = false;
286 
287  if (selectObject && selection.width > 0 && selection.height > 0)
288  {
289  cv::Mat roi(frame, selection);
290  bitwise_not(roi, roi);
291  }
292 
293  if (debug_view_)
294  {
295  cv::imshow(window_name_, frame);
296  cv::imshow(histogram_name_, histimg);
297 
298  char c = (char)cv::waitKey(1);
299  // if( c == 27 )
300  // break;
301  switch (c)
302  {
303  case 'b':
304  backprojMode = !backprojMode;
305  break;
306  case 'c':
307  trackObject = 0;
308  histimg = cv::Scalar::all(0);
309  break;
310  case 'h':
311  showHist = !showHist;
312  if (!showHist)
313  cv::destroyWindow(histogram_name_);
314  else
315  cv::namedWindow(histogram_name_, 1);
316  break;
317  case 'p':
318  paused = !paused;
319  break;
320  default:;
321  }
322  }
323 
324  // Publish the image.
325  sensor_msgs::Image::Ptr out_img1 = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg();
326  sensor_msgs::Image::Ptr out_img2 =
328  img_pub_.publish(out_img1);
329  bproj_pub_.publish(out_img2);
330  if (trackObject)
331  msg_pub_.publish(rect_msg);
332  }
333  catch (cv::Exception& e)
334  {
335  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
336  }
337 
338  prev_stamp_ = msg->header.stamp;
339  }
340 
341  void subscribe() // NOLINT(modernize-use-override)
342  {
343  NODELET_DEBUG("Subscribing to image topic.");
344  if (config_.use_camera_info)
345  cam_sub_ = it_->subscribeCamera("image", queue_size_, &CamShiftNodelet::imageCallbackWithInfo, this);
346  else
347  img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this);
348  }
349 
350  void unsubscribe() // NOLINT(modernize-use-override)
351  {
352  NODELET_DEBUG("Unsubscribing from image topic.");
353  img_sub_.shutdown();
354  cam_sub_.shutdown();
355  }
356 
357 public:
358  virtual void onInit() // NOLINT(modernize-use-override)
359  {
360  Nodelet::onInit();
362 
363  pnh_->param("queue_size", queue_size_, 3);
364  pnh_->param("debug_view", debug_view_, false);
365  if (debug_view_)
366  {
367  always_subscribe_ = true;
368  }
369  prev_stamp_ = ros::Time(0, 0);
370 
371  window_name_ = "CamShift Demo";
372  histogram_name_ = "Histogram";
373 
374  vmin_ = 10;
375  vmax_ = 256;
376  smin_ = 30;
377  backprojMode = false;
378  selectObject = false;
379  trackObject = 0;
380  showHist = true;
381  paused = false;
382 
383  hsize = 16;
384  hranges[0] = 0;
385  hranges[1] = 180;
386  phranges = hranges;
387  histimg = cv::Mat::zeros(200, 320, CV_8UC3);
388 
389  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
390  dynamic_reconfigure::Server<Config>::CallbackType f =
391  boost::bind(&CamShiftNodelet::reconfigureCallback, this, _1, _2);
392  reconfigure_server_->setCallback(f);
393 
394  img_pub_ = advertiseImage(*pnh_, "image", 1);
395  bproj_pub_ = advertiseImage(*pnh_, "back_project", 1);
396  msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*pnh_, "track_box", 1);
397 
398  NODELET_INFO("Hot keys: ");
399  NODELET_INFO("\tESC - quit the program");
400  NODELET_INFO("\tc - stop the tracking");
401  NODELET_INFO("\tb - switch to/from backprojection view");
402  NODELET_INFO("\th - show/hide object histogram");
403  NODELET_INFO("\tp - pause video");
404  NODELET_INFO("To initialize tracking, select the object with mouse");
405 
406  std::vector<float> hist_value;
407  pnh_->getParam("histogram", hist_value);
408  if (hist_value.size() == hsize)
409  {
410  hist.create(hsize, 1, CV_32F);
411  for (int i = 0; i < hsize; i++)
412  {
413  hist.at<float>(i) = hist_value[i];
414  }
415  trackObject = 1;
416  trackWindow = cv::Rect(0, 0, 640, 480); //
417 
418  histimg = cv::Scalar::all(0);
419  int bin_w = histimg.cols / hsize;
420  cv::Mat buf(1, hsize, CV_8UC3);
421  for (int i = 0; i < hsize; i++)
422  buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
423  cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
424 
425  for (int i = 0; i < hsize; i++)
426  {
427  int val = cv::saturate_cast<int>(hist.at<float>(i) * histimg.rows / 255);
428  cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
429  cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
430  }
431  }
433  }
434 };
440 } // namespace opencv_apps
441 
442 namespace camshift
443 {
445 {
446 public:
447  virtual void onInit() // NOLINT(modernize-use-override)
448  {
449  ROS_WARN("DeprecationWarning: Nodelet camshift/camshift is deprecated, "
450  "and renamed to opencv_apps/camshift.");
452  }
453 };
454 } // namespace camshift
455 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
f
static void onMouse(int event, int x, int y, int, void *)
image_transport::Subscriber img_sub_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Demo code to calculate moments.
Definition: nodelet.h:48
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
static void trackbarCallback(int, void *)
#define ROS_WARN(...)
opencv_apps::CamShiftConfig Config
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
void reconfigureCallback(Config &new_config, uint32_t level)
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
PLUGINLIB_EXPORT_CLASS(opencv_apps::CamShiftNodelet, nodelet::Nodelet)
image_transport::Publisher img_pub_
void publish(const sensor_msgs::Image &message) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Publisher bproj_pub_
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
image_transport::CameraSubscriber cam_sub_
#define NODELET_INFO(...)
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const


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