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;
93 theta_ = config_.theta;
94 threshold_ = config_.threshold;
95 minLineLength_ = config_.minLineLength;
96 maxLineGap_ = config_.maxLineGap;
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);
118 need_config_update_ =
true;
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];
176 sprintf(thresh_label,
"Thres: %d + input", min_threshold_);
178 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
179 cv::createTrackbar(thresh_label, window_name_, &threshold_, max_threshold_,
trackbarCallback);
180 if (need_config_update_)
183 reconfigure_server_->updateConfig(config_);
184 need_config_update_ =
false;
188 switch (config_.hough_type)
190 case opencv_apps::HoughLines_Standard_Hough_Transform:
192 std::vector<cv::Vec2f> s_lines;
195 cv::HoughLines(in_image, s_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
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;
228 cv::HoughLinesP(in_image, p_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
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);
253 cv::imshow(window_name_, out_image);
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);
267 prev_stamp_ = msg->header.stamp;
273 if (config_.use_camera_info)
292 pnh_->param(
"queue_size", queue_size_, 3);
293 pnh_->param(
"debug_view", debug_view_,
false);
300 window_name_ =
"Hough Lines Demo";
302 max_threshold_ = 150;
305 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
306 dynamic_reconfigure::Server<Config>::CallbackType
f =
308 reconfigure_server_->setCallback(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.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
static bool need_config_update_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
opencv_apps::HoughLinesConfig Config
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
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)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
boost::shared_ptr< image_transport::ImageTransport > it_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
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...
dynamic_reconfigure::Server< Config > ReconfigureServer
image_transport::CameraSubscriber cam_sub_
image_transport::Subscriber img_sub_
image_transport::Publisher img_pub_
PLUGINLIB_EXPORT_CLASS(opencv_apps::HoughLinesNodelet, nodelet::Nodelet)
static void trackbarCallback(int, void *)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(Config &new_config, uint32_t level)
boost::shared_ptr< ReconfigureServer > reconfigure_server_