hough_lines_nodelet.cpp
Go to the documentation of this file.
1 // -*- coding:utf-8-unix; mode: c++; indent-tabs-mode: nil; c-basic-offset: 2; -*-
2 /*********************************************************************
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2014, Kei Okada.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Kei Okada nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ImgTrans/HoughLines_Demo.cpp
43 #include <ros/ros.h>
44 #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/HoughLinesConfig.h"
54 #include "opencv_apps/Line.h"
55 #include "opencv_apps/LineArray.h"
56 #include "opencv_apps/LineArrayStamped.h"
57 
58 namespace opencv_apps
59 {
61 {
66 
68 
69  typedef opencv_apps::HoughLinesConfig Config;
70  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
73 
77 
78  std::string window_name_;
79  static bool need_config_update_;
80 
84  double rho_;
85  double theta_;
87  double maxLineGap_;
88 
89  void reconfigureCallback(Config& new_config, uint32_t level)
90  {
91  config_ = new_config;
92  rho_ = config_.rho;
93  theta_ = config_.theta;
94  threshold_ = config_.threshold;
95  minLineLength_ = config_.minLineLength;
96  maxLineGap_ = config_.maxLineGap;
97  }
98 
99  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
100  {
101  if (frame.empty())
102  return image_frame;
103  return frame;
104  }
105 
106  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
107  {
108  doWork(msg, cam_info->header.frame_id);
109  }
110 
111  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
112  {
113  doWork(msg, msg->header.frame_id);
114  }
115 
116  static void trackbarCallback(int /*unused*/, void* /*unused*/)
117  {
118  need_config_update_ = true;
119  }
120 
121  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
122  {
123  // Work on the image.
124  try
125  {
126  // Convert the image into something opencv can handle.
127  cv::Mat in_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
128  cv::Mat src_gray;
129 
130  if (in_image.channels() > 1)
131  {
132  cv::cvtColor(in_image, src_gray, cv::COLOR_BGR2GRAY);
134  Canny(src_gray, in_image, 50, 200, 3);
135  }
136  else
137  {
139  bool is_filtered = true;
140  for (int y = 0; y < in_image.rows; ++y)
141  {
142  for (int x = 0; x < in_image.cols; ++x)
143  {
144  if (!(in_image.at<unsigned char>(y, x) == 0 || in_image.at<unsigned char>(y, x) == 255))
145  {
146  is_filtered = false;
147  break;
148  }
149  if (!is_filtered)
150  {
151  break;
152  }
153  }
154  }
155 
156  if (!is_filtered)
157  {
158  Canny(in_image, in_image, 50, 200, 3);
159  }
160  }
161 
162  cv::Mat out_image;
163  cv::cvtColor(in_image, out_image, CV_GRAY2BGR);
164 
165  // Messages
166  opencv_apps::LineArrayStamped lines_msg;
167  lines_msg.header = msg->header;
168 
169  // Do the work
170  std::vector<cv::Rect> faces;
171 
172  if (debug_view_)
173  {
175  char thresh_label[50];
176  sprintf(thresh_label, "Thres: %d + input", min_threshold_);
177 
178  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
179  cv::createTrackbar(thresh_label, window_name_, &threshold_, max_threshold_, trackbarCallback);
181  {
182  config_.threshold = threshold_;
183  reconfigure_server_->updateConfig(config_);
184  need_config_update_ = false;
185  }
186  }
187 
188  switch (config_.hough_type)
189  {
190  case opencv_apps::HoughLines_Standard_Hough_Transform:
191  {
192  std::vector<cv::Vec2f> s_lines;
193 
195  cv::HoughLines(in_image, s_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
196 
198  for (const cv::Vec2f& s_line : s_lines)
199  {
200  float r = s_line[0], t = s_line[1];
201  double cos_t = cos(t), sin_t = sin(t);
202  double x0 = r * cos_t, y0 = r * sin_t;
203  double alpha = 1000;
204 
205  cv::Point pt1(cvRound(x0 + alpha * (-sin_t)), cvRound(y0 + alpha * cos_t));
206  cv::Point pt2(cvRound(x0 - alpha * (-sin_t)), cvRound(y0 - alpha * cos_t));
207 #ifndef CV_VERSION_EPOCH
208  cv::line(out_image, pt1, pt2, cv::Scalar(255, 0, 0), 3, cv::LINE_AA);
209 #else
210  cv::line(out_image, pt1, pt2, cv::Scalar(255, 0, 0), 3, CV_AA);
211 #endif
212  opencv_apps::Line line_msg;
213  line_msg.pt1.x = pt1.x;
214  line_msg.pt1.y = pt1.y;
215  line_msg.pt2.x = pt2.x;
216  line_msg.pt2.y = pt2.y;
217  lines_msg.lines.push_back(line_msg);
218  }
219 
220  break;
221  }
222  case opencv_apps::HoughLines_Probabilistic_Hough_Transform:
223  default:
224  {
225  std::vector<cv::Vec4i> p_lines;
226 
228  cv::HoughLinesP(in_image, p_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
229 
231  for (const cv::Vec4i& l : p_lines)
232  {
233 #ifndef CV_VERSION_EPOCH
234  cv::line(out_image, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255, 0, 0), 3, cv::LINE_AA);
235 #else
236  cv::line(out_image, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255, 0, 0), 3, CV_AA);
237 #endif
238  opencv_apps::Line line_msg;
239  line_msg.pt1.x = l[0];
240  line_msg.pt1.y = l[1];
241  line_msg.pt2.x = l[2];
242  line_msg.pt2.y = l[3];
243  lines_msg.lines.push_back(line_msg);
244  }
245 
246  break;
247  }
248  }
249 
250  //-- Show what you got
251  if (debug_view_)
252  {
253  cv::imshow(window_name_, out_image);
254  int c = cv::waitKey(1);
255  }
256 
257  // Publish the image.
258  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
259  img_pub_.publish(out_img);
260  msg_pub_.publish(lines_msg);
261  }
262  catch (cv::Exception& e)
263  {
264  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
265  }
266 
267  prev_stamp_ = msg->header.stamp;
268  }
269 
270  void subscribe() // NOLINT(modernize-use-override)
271  {
272  NODELET_DEBUG("Subscribing to image topic.");
273  if (config_.use_camera_info)
274  cam_sub_ = it_->subscribeCamera("image", queue_size_, &HoughLinesNodelet::imageCallbackWithInfo, this);
275  else
276  img_sub_ = it_->subscribe("image", queue_size_, &HoughLinesNodelet::imageCallback, this);
277  }
278 
279  void unsubscribe() // NOLINT(modernize-use-override)
280  {
281  NODELET_DEBUG("Unsubscribing from image topic.");
282  img_sub_.shutdown();
283  cam_sub_.shutdown();
284  }
285 
286 public:
287  virtual void onInit() // NOLINT(modernize-use-override)
288  {
289  Nodelet::onInit();
291 
292  pnh_->param("queue_size", queue_size_, 3);
293  pnh_->param("debug_view", debug_view_, false);
294  if (debug_view_)
295  {
296  always_subscribe_ = true;
297  }
298  prev_stamp_ = ros::Time(0, 0);
299 
300  window_name_ = "Hough Lines Demo";
301  min_threshold_ = 50;
302  max_threshold_ = 150;
304 
305  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
306  dynamic_reconfigure::Server<Config>::CallbackType f =
308  reconfigure_server_->setCallback(f);
309 
310  img_pub_ = advertiseImage(*pnh_, "image", 1);
311  msg_pub_ = advertise<opencv_apps::LineArrayStamped>(*pnh_, "lines", 1);
312 
314  }
315 };
317 } // namespace opencv_apps
318 
319 namespace hough_lines
320 {
322 {
323 public:
324  virtual void onInit() // NOLINT(modernize-use-override)
325  {
326  ROS_WARN("DeprecationWarning: Nodelet hough_lines/hough_lines is deprecated, "
327  "and renamed to opencv_apps/hough_lines.");
329  }
330 };
331 } // namespace hough_lines
332 
333 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
335 #else
337 #endif
nodelet.h
NODELET_ERROR
#define NODELET_ERROR(...)
opencv_apps::HoughLinesNodelet::debug_view_
bool debug_view_
Definition: hough_lines_nodelet.cpp:75
opencv_apps::HoughLinesNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: hough_lines_nodelet.cpp:287
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
opencv_apps::HoughLinesNodelet::need_config_update_
static bool need_config_update_
Definition: hough_lines_nodelet.cpp:79
boost::shared_ptr< image_transport::ImageTransport >
opencv_apps::HoughLinesNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: hough_lines_nodelet.cpp:111
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
opencv_apps::HoughLinesNodelet::window_name_
std::string window_name_
Definition: hough_lines_nodelet.cpp:78
ros.h
boost::placeholders::_1
boost::arg< 1 > _1
Definition: nodelet.cpp:44
opencv_apps::HoughLinesNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: hough_lines_nodelet.cpp:70
opencv_apps::Nodelet
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
Definition: nodelet.h:90
opencv_apps::HoughLinesNodelet::theta_
double theta_
Definition: hough_lines_nodelet.cpp:85
opencv_apps::HoughLinesNodelet::threshold_
int threshold_
Definition: hough_lines_nodelet.cpp:83
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(opencv_apps::HoughLinesNodelet, nodelet::Nodelet)
hough_lines
Definition: hough_lines_nodelet.cpp:319
opencv_apps::HoughLinesNodelet::Config
opencv_apps::HoughLinesConfig Config
Definition: hough_lines_nodelet.cpp:69
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
f
f
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::HoughLinesNodelet::msg_pub_
ros::Publisher msg_pub_
Definition: hough_lines_nodelet.cpp:65
opencv_apps::HoughLinesNodelet::queue_size_
int queue_size_
Definition: hough_lines_nodelet.cpp:74
image_transport::CameraSubscriber
opencv_apps::HoughLinesNodelet::max_threshold_
int max_threshold_
Definition: hough_lines_nodelet.cpp:82
image_transport::CameraSubscriber::shutdown
void shutdown()
opencv_apps::HoughLinesNodelet::subscribe
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Definition: hough_lines_nodelet.cpp:270
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
opencv_apps::HoughLinesNodelet::doWork
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Definition: hough_lines_nodelet.cpp:121
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(...)
opencv_apps::HoughLinesNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: hough_lines_nodelet.cpp:72
opencv_apps::HoughLinesNodelet
Definition: hough_lines_nodelet.cpp:60
opencv_apps::HoughLinesNodelet::imageCallbackWithInfo
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: hough_lines_nodelet.cpp:106
opencv_apps::HoughLinesNodelet::cam_sub_
image_transport::CameraSubscriber cam_sub_
Definition: hough_lines_nodelet.cpp:64
opencv_apps::HoughLinesNodelet::minLineLength_
double minLineLength_
Definition: hough_lines_nodelet.cpp:86
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
image_transport.h
opencv_apps::HoughLinesNodelet::config_
Config config_
Definition: hough_lines_nodelet.cpp:71
opencv_apps::HoughLinesNodelet::maxLineGap_
double maxLineGap_
Definition: hough_lines_nodelet.cpp:87
face_recognition_trainer.t
t
Definition: face_recognition_trainer.py:96
nodelet::Nodelet
ros::Time
opencv_apps::HoughLinesNodelet::min_threshold_
int min_threshold_
Definition: hough_lines_nodelet.cpp:81
opencv_apps::HoughLinesNodelet::prev_stamp_
ros::Time prev_stamp_
Definition: hough_lines_nodelet.cpp:76
opencv_apps::HoughLinesNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: hough_lines_nodelet.cpp:67
image_transport::Publisher
cv_bridge.h
cv_bridge::CvImage
class_list_macros.hpp
opencv_apps::HoughLinesNodelet::img_pub_
image_transport::Publisher img_pub_
Definition: hough_lines_nodelet.cpp:62
sensor_msgs::image_encodings::BGR8
const std::string BGR8
hough_lines::HoughLinesNodelet
Definition: hough_lines_nodelet.cpp:321
opencv_apps::HoughLinesNodelet::trackbarCallback
static void trackbarCallback(int, void *)
Definition: hough_lines_nodelet.cpp:116
hough_lines::HoughLinesNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: hough_lines_nodelet.cpp:324
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::HoughLinesNodelet::unsubscribe
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Definition: hough_lines_nodelet.cpp:279
opencv_apps::HoughLinesNodelet::frameWithDefault
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Definition: hough_lines_nodelet.cpp:99
opencv_apps::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
opencv_apps::HoughLinesNodelet::reconfigureCallback
void reconfigureCallback(Config &new_config, uint32_t level)
Definition: hough_lines_nodelet.cpp:89
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(...)
opencv_apps::HoughLinesNodelet::rho_
double rho_
Definition: hough_lines_nodelet.cpp:84
image_transport::Subscriber::shutdown
void shutdown()
opencv_apps::HoughLinesNodelet::img_sub_
image_transport::Subscriber img_sub_
Definition: hough_lines_nodelet.cpp:63


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