convex_hull_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/tutorial_code/ShapeDescriptors/hull_demo.cpp
42 #include <ros/ros.h>
43 #include "opencv_apps/nodelet.h"
46 #include <cv_bridge/cv_bridge.h>
48 
49 #include <opencv2/highgui/highgui.hpp>
50 #include <opencv2/imgproc/imgproc.hpp>
51 
52 #include <dynamic_reconfigure/server.h>
53 #include "opencv_apps/ConvexHullConfig.h"
54 #include "opencv_apps/Contour.h"
55 #include "opencv_apps/ContourArray.h"
56 #include "opencv_apps/ContourArrayStamped.h"
57 
58 namespace opencv_apps
59 {
61 {
66 
68 
69  typedef opencv_apps::ConvexHullConfig Config;
70  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
71  Config config_;
73 
77 
79 
80  std::string window_name_;
81  static bool need_config_update_;
82 
83  void reconfigureCallback(Config& new_config, uint32_t level)
84  {
85  config_ = new_config;
86  threshold_ = config_.threshold;
87  }
88 
89  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
90  {
91  if (frame.empty())
92  return image_frame;
93  return frame;
94  }
95 
96  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
97  {
98  doWork(msg, cam_info->header.frame_id);
99  }
100 
101  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
102  {
103  doWork(msg, msg->header.frame_id);
104  }
105 
106  static void trackbarCallback(int /*unused*/, void* /*unused*/)
107  {
108  need_config_update_ = true;
109  }
110 
111  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
112  {
113  // Work on the image.
114  try
115  {
116  // Convert the image into something opencv can handle.
117  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
118 
119  // Messages
120  opencv_apps::ContourArrayStamped contours_msg;
121  contours_msg.header = msg->header;
122 
123  // Do the work
124  cv::Mat src_gray;
125 
127  if (frame.channels() > 1)
128  {
129  cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
130  }
131  else
132  {
133  src_gray = frame;
134  }
135  cv::blur(src_gray, src_gray, cv::Size(3, 3));
136 
138  if (debug_view_)
139  {
140  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
141  }
142 
143  cv::Mat threshold_output;
144  int max_thresh = 255;
145  std::vector<std::vector<cv::Point> > contours;
146  std::vector<cv::Vec4i> hierarchy;
147  cv::RNG rng(12345);
148 
150  cv::threshold(src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY);
151 
153  cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
154 
156  std::vector<std::vector<cv::Point> > hull(contours.size());
157  for (size_t i = 0; i < contours.size(); i++)
158  {
159  cv::convexHull(cv::Mat(contours[i]), hull[i], false);
160  }
161 
163  cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
164  for (size_t i = 0; i < contours.size(); i++)
165  {
166  cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
167  cv::drawContours(drawing, contours, (int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
168  cv::drawContours(drawing, hull, (int)i, color, 4, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
169 
170  opencv_apps::Contour contour_msg;
171  for (const cv::Point& j : hull[i])
172  {
173  opencv_apps::Point2D point_msg;
174  point_msg.x = j.x;
175  point_msg.y = j.y;
176  contour_msg.points.push_back(point_msg);
177  }
178  contours_msg.contours.push_back(contour_msg);
179  }
180 
182  if (debug_view_)
183  {
184  if (need_config_update_)
185  {
186  config_.threshold = threshold_;
187  reconfigure_server_->updateConfig(config_);
188  need_config_update_ = false;
189  }
190  cv::createTrackbar("Threshold:", window_name_, &threshold_, max_thresh, trackbarCallback);
191 
192  cv::imshow(window_name_, drawing);
193  int c = cv::waitKey(1);
194  }
195 
196  // Publish the image.
197  sensor_msgs::Image::Ptr out_img =
199  img_pub_.publish(out_img);
200  msg_pub_.publish(contours_msg);
201  }
202  catch (cv::Exception& e)
203  {
204  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
205  }
206 
207  prev_stamp_ = msg->header.stamp;
208  }
209 
210  void subscribe() // NOLINT(modernize-use-override)
211  {
212  NODELET_DEBUG("Subscribing to image topic.");
213  if (config_.use_camera_info)
214  cam_sub_ = it_->subscribeCamera("image", queue_size_, &ConvexHullNodelet::imageCallbackWithInfo, this);
215  else
216  img_sub_ = it_->subscribe("image", queue_size_, &ConvexHullNodelet::imageCallback, this);
217  }
218 
219  void unsubscribe() // NOLINT(modernize-use-override)
220  {
221  NODELET_DEBUG("Unsubscribing from image topic.");
222  img_sub_.shutdown();
223  cam_sub_.shutdown();
224  }
225 
226 public:
227  virtual void onInit() // NOLINT(modernize-use-override)
228  {
229  Nodelet::onInit();
231 
232  pnh_->param("queue_size", queue_size_, 3);
233  pnh_->param("debug_view", debug_view_, false);
234  if (debug_view_)
235  {
236  always_subscribe_ = true;
237  }
238  prev_stamp_ = ros::Time(0, 0);
239 
240  window_name_ = "Hull Demo";
241  threshold_ = 100;
242 
243  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
244  dynamic_reconfigure::Server<Config>::CallbackType f =
245  boost::bind(&ConvexHullNodelet::reconfigureCallback, this, _1, _2);
246  reconfigure_server_->setCallback(f);
247 
248  img_pub_ = advertiseImage(*pnh_, "image", 1);
249  msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "hulls", 1);
251  }
252 };
254 } // namespace opencv_apps
255 
256 namespace convex_hull
257 {
259 {
260 public:
261  virtual void onInit() // NOLINT(modernize-use-override)
262  {
263  ROS_WARN("DeprecationWarning: Nodelet convex_hull/convex_hull is deprecated, "
264  "and renamed to opencv_apps/convex_hull.");
266  }
267 };
268 } // namespace convex_hull
269 
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
static void trackbarCallback(int, void *)
#define NODELET_ERROR(...)
opencv_apps::ConvexHullConfig Config
void publish(const boost::shared_ptr< M > &message) const
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Demo code to calculate moments.
Definition: nodelet.h:48
image_transport::CameraSubscriber cam_sub_
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(...)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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
image_transport::Publisher img_pub_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
dynamic_reconfigure::Server< Config > ReconfigureServer
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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...
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_DEBUG(...)
boost::shared_ptr< image_transport::ImageTransport > it_
PLUGINLIB_EXPORT_CLASS(opencv_apps::ConvexHullNodelet, nodelet::Nodelet)
sensor_msgs::ImagePtr toImageMsg() const
image_transport::Subscriber img_sub_


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