49 #include <opencv2/highgui/highgui.hpp>
50 #include <opencv2/imgproc/imgproc.hpp>
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"
69 typedef opencv_apps::HoughLinesConfig
Config;
99 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
108 doWork(msg, cam_info->header.frame_id);
113 doWork(msg, msg->header.frame_id);
121 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
130 if (in_image.channels() > 1)
132 cv::cvtColor(in_image, src_gray, cv::COLOR_BGR2GRAY);
134 Canny(src_gray, in_image, 50, 200, 3);
139 bool is_filtered =
true;
140 for (
int y = 0; y < in_image.rows; ++y)
142 for (
int x = 0; x < in_image.cols; ++x)
144 if (!(in_image.at<
unsigned char>(y, x) == 0 || in_image.at<
unsigned char>(y, x) == 255))
158 Canny(in_image, in_image, 50, 200, 3);
163 cv::cvtColor(in_image, out_image, CV_GRAY2BGR);
166 opencv_apps::LineArrayStamped lines_msg;
167 lines_msg.header = msg->header;
170 std::vector<cv::Rect> faces;
175 char thresh_label[50];
190 case opencv_apps::HoughLines_Standard_Hough_Transform:
192 std::vector<cv::Vec2f> s_lines;
198 for (
const cv::Vec2f& s_line : s_lines)
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;
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);
210 cv::line(out_image, pt1, pt2, cv::Scalar(255, 0, 0), 3, CV_AA);
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);
222 case opencv_apps::HoughLines_Probabilistic_Hough_Transform:
225 std::vector<cv::Vec4i> p_lines;
231 for (
const cv::Vec4i& l : p_lines)
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);
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);
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);
254 int c = cv::waitKey(1);
262 catch (cv::Exception& e)
264 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
306 dynamic_reconfigure::Server<Config>::CallbackType
f =
311 msg_pub_ = advertise<opencv_apps::LineArrayStamped>(*
pnh_,
"lines", 1);
326 ROS_WARN(
"DeprecationWarning: Nodelet hough_lines/hough_lines is deprecated, "
327 "and renamed to opencv_apps/hough_lines.");
333 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H