general_contours_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/generalContours_demo2.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/GeneralContoursConfig.h"
54 #include "opencv_apps/RotatedRect.h"
55 #include "opencv_apps/RotatedRectArray.h"
56 #include "opencv_apps/RotatedRectArrayStamped.h"
57 
58 namespace opencv_apps
59 {
60 class GeneralContoursNodelet : public opencv_apps::Nodelet
61 {
66 
68 
69  typedef opencv_apps::GeneralContoursConfig Config;
70  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
73 
74  int queue_size_;
75  bool debug_view_;
77 
78  int threshold_;
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::RotatedRectArrayStamped rects_msg, ellipses_msg;
121  rects_msg.header = msg->header;
122  ellipses_msg.header = msg->header;
123 
124  // Do the work
125  cv::Mat src_gray;
126 
128  if (frame.channels() > 1)
129  {
130  cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
131  }
132  else
133  {
134  src_gray = frame;
135  }
136  cv::blur(src_gray, src_gray, cv::Size(3, 3));
137 
140  {
141  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
142  }
143 
144  cv::Mat threshold_output;
145  int max_thresh = 255;
146  std::vector<std::vector<cv::Point> > contours;
147  std::vector<cv::Vec4i> hierarchy;
148  cv::RNG rng(12345);
149 
151  cv::threshold(src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY);
152 
154  cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
155 
157  std::vector<cv::RotatedRect> min_rect(contours.size());
158  std::vector<cv::RotatedRect> min_ellipse(contours.size());
159 
160  for (size_t i = 0; i < contours.size(); i++)
161  {
162  min_rect[i] = cv::minAreaRect(cv::Mat(contours[i]));
163  if (contours[i].size() > 5)
164  {
165  min_ellipse[i] = cv::fitEllipse(cv::Mat(contours[i]));
166  }
167  }
168 
170  cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
171  for (size_t i = 0; i < contours.size(); i++)
172  {
173  cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
174  // contour
175  cv::drawContours(drawing, contours, (int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
176  // ellipse
177  cv::ellipse(drawing, min_ellipse[i], color, 2, 8);
178  // rotated rectangle
179  cv::Point2f rect_points[4];
180  min_rect[i].points(rect_points);
181  for (int j = 0; j < 4; j++)
182  cv::line(drawing, rect_points[j], rect_points[(j + 1) % 4], color, 1, 8);
183 
184  opencv_apps::RotatedRect rect_msg;
185  opencv_apps::Point2D rect_center;
186  opencv_apps::Size rect_size;
187  rect_center.x = min_rect[i].center.x;
188  rect_center.y = min_rect[i].center.y;
189  rect_size.width = min_rect[i].size.width;
190  rect_size.height = min_rect[i].size.height;
191  rect_msg.center = rect_center;
192  rect_msg.size = rect_size;
193  rect_msg.angle = min_rect[i].angle;
194  opencv_apps::RotatedRect ellipse_msg;
195  opencv_apps::Point2D ellipse_center;
196  opencv_apps::Size ellipse_size;
197  ellipse_center.x = min_ellipse[i].center.x;
198  ellipse_center.y = min_ellipse[i].center.y;
199  ellipse_size.width = min_ellipse[i].size.width;
200  ellipse_size.height = min_ellipse[i].size.height;
201  ellipse_msg.center = ellipse_center;
202  ellipse_msg.size = ellipse_size;
203  ellipse_msg.angle = min_ellipse[i].angle;
204 
205  rects_msg.rects.push_back(rect_msg);
206  ellipses_msg.rects.push_back(ellipse_msg);
207  }
208 
210  if (debug_view_)
211  {
213  {
214  config_.threshold = threshold_;
215  reconfigure_server_->updateConfig(config_);
216  need_config_update_ = false;
217  }
218  cv::createTrackbar("Threshold:", window_name_, &threshold_, max_thresh, trackbarCallback);
219 
220  cv::imshow(window_name_, drawing);
221  int c = cv::waitKey(1);
222  }
223 
224  // Publish the image.
225  sensor_msgs::Image::Ptr out_img =
227  img_pub_.publish(out_img);
228  rects_pub_.publish(rects_msg);
229  ellipses_pub_.publish(ellipses_msg);
230  }
231  catch (cv::Exception& e)
232  {
233  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
234  }
235 
236  prev_stamp_ = msg->header.stamp;
237  }
238 
239  void subscribe() // NOLINT(modernize-use-override)
240  {
241  NODELET_DEBUG("Subscribing to image topic.");
242  if (config_.use_camera_info)
243  cam_sub_ = it_->subscribeCamera("image", queue_size_, &GeneralContoursNodelet::imageCallbackWithInfo, this);
244  else
245  img_sub_ = it_->subscribe("image", queue_size_, &GeneralContoursNodelet::imageCallback, this);
246  }
247 
248  void unsubscribe() // NOLINT(modernize-use-override)
249  {
250  NODELET_DEBUG("Unsubscribing from image topic.");
251  img_sub_.shutdown();
252  cam_sub_.shutdown();
253  }
254 
255 public:
256  virtual void onInit() // NOLINT(modernize-use-override)
257  {
258  Nodelet::onInit();
260 
261  pnh_->param("queue_size", queue_size_, 3);
262  pnh_->param("debug_view", debug_view_, false);
263  if (debug_view_)
264  {
265  always_subscribe_ = true;
266  }
267  prev_stamp_ = ros::Time(0, 0);
268 
269  window_name_ = "Contours";
270  threshold_ = 100;
271 
272  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
273  dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(
275  reconfigure_server_->setCallback(f);
276 
277  img_pub_ = advertiseImage(*pnh_, "image", 1);
278  rects_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "rectangles", 1);
279  ellipses_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "ellipses", 1);
280 
282  }
283 };
285 } // namespace opencv_apps
286 
288 {
290 {
291 public:
292  virtual void onInit() // NOLINT(modernize-use-override)
293  {
294  ROS_WARN("DeprecationWarning: Nodelet general_contours/general_contours is deprecated, "
295  "and renamed to opencv_apps/general_contours.");
297  }
298 };
299 } // namespace general_contours
300 
301 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
303 #else
305 #endif
opencv_apps::GeneralContoursNodelet::doWork
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Definition: general_contours_nodelet.cpp:175
opencv_apps::GeneralContoursNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: general_contours_nodelet.cpp:136
nodelet.h
NODELET_ERROR
#define NODELET_ERROR(...)
opencv_apps::GeneralContoursNodelet
Definition: general_contours_nodelet.cpp:92
opencv_apps::Nodelet::onInitPostProcess
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:77
ros::Publisher
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
opencv_apps::GeneralContoursNodelet::prev_stamp_
ros::Time prev_stamp_
Definition: general_contours_nodelet.cpp:140
opencv_apps::GeneralContoursNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: general_contours_nodelet.cpp:134
opencv_apps::GeneralContoursNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: general_contours_nodelet.cpp:131
general_contours::GeneralContoursNodelet
Definition: general_contours_nodelet.cpp:289
opencv_apps::GeneralContoursNodelet::rects_pub_
ros::Publisher rects_pub_
Definition: general_contours_nodelet.cpp:129
ros.h
opencv_apps::GeneralContoursNodelet::frameWithDefault
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Definition: general_contours_nodelet.cpp:153
boost::placeholders::_1
boost::arg< 1 > _1
Definition: nodelet.cpp:44
opencv_apps::Nodelet
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
Definition: nodelet.h:90
opencv_apps::GeneralContoursNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: general_contours_nodelet.cpp:165
opencv_apps::GeneralContoursNodelet::unsubscribe
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Definition: general_contours_nodelet.cpp:312
opencv_apps::GeneralContoursNodelet::trackbarCallback
static void trackbarCallback(int, void *)
Definition: general_contours_nodelet.cpp:170
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
opencv_apps::GeneralContoursNodelet::threshold_
int threshold_
Definition: general_contours_nodelet.cpp:142
opencv_apps::GeneralContoursNodelet::ellipses_pub_
ros::Publisher ellipses_pub_
Definition: general_contours_nodelet.cpp:129
f
f
opencv_apps::GeneralContoursNodelet::imageCallbackWithInfo
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: general_contours_nodelet.cpp:160
image_transport::Subscriber
opencv_apps::Nodelet::advertiseImage
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:201
class_list_macros.h
opencv_apps::GeneralContoursNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: general_contours_nodelet.cpp:320
opencv_apps::GeneralContoursNodelet::window_name_
std::string window_name_
Definition: general_contours_nodelet.cpp:144
image_transport::CameraSubscriber
image_transport::CameraSubscriber::shutdown
void shutdown()
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
opencv_apps::Nodelet::always_subscribe_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
ROS_WARN
#define ROS_WARN(...)
general_contours::GeneralContoursNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: general_contours_nodelet.cpp:292
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
opencv_apps::GeneralContoursNodelet::reconfigureCallback
void reconfigureCallback(Config &new_config, uint32_t level)
Definition: general_contours_nodelet.cpp:147
image_transport.h
nodelet::Nodelet
ros::Time
image_transport::Publisher
opencv_apps::GeneralContoursNodelet::Config
opencv_apps::GeneralContoursConfig Config
Definition: general_contours_nodelet.cpp:133
cv_bridge.h
cv_bridge::CvImage
class_list_macros.hpp
opencv_apps::GeneralContoursNodelet::debug_view_
bool debug_view_
Definition: general_contours_nodelet.cpp:139
sensor_msgs::image_encodings::BGR8
const std::string BGR8
opencv_apps::GeneralContoursNodelet::img_sub_
image_transport::Subscriber img_sub_
Definition: general_contours_nodelet.cpp:127
opencv_apps::GeneralContoursNodelet::img_pub_
image_transport::Publisher img_pub_
Definition: general_contours_nodelet.cpp:126
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
opencv_apps::GeneralContoursNodelet::subscribe
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Definition: general_contours_nodelet.cpp:303
general_contours
Definition: general_contours_nodelet.cpp:287
opencv_apps::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
opencv_apps::GeneralContoursNodelet::queue_size_
int queue_size_
Definition: general_contours_nodelet.cpp:138
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(opencv_apps::GeneralContoursNodelet, nodelet::Nodelet)
opencv_apps::GeneralContoursNodelet::need_config_update_
static bool need_config_update_
Definition: general_contours_nodelet.cpp:145
opencv_apps::GeneralContoursNodelet::cam_sub_
image_transport::CameraSubscriber cam_sub_
Definition: general_contours_nodelet.cpp:128
opencv_apps::Nodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: nodelet.cpp:60
opencv_apps::Nodelet::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
NODELET_DEBUG
#define NODELET_DEBUG(...)
image_transport::Subscriber::shutdown
void shutdown()
opencv_apps::GeneralContoursNodelet::config_
Config config_
Definition: general_contours_nodelet.cpp:135


opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49