00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00043 #include <ros/ros.h>
00044 #include "opencv_apps/nodelet.h"
00045 #include <image_transport/image_transport.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <sensor_msgs/image_encodings.h>
00048
00049 #include <opencv2/highgui/highgui.hpp>
00050 #include <opencv2/imgproc/imgproc.hpp>
00051
00052 #include <dynamic_reconfigure/server.h>
00053 #include "opencv_apps/HoughLinesConfig.h"
00054 #include "opencv_apps/Line.h"
00055 #include "opencv_apps/LineArray.h"
00056 #include "opencv_apps/LineArrayStamped.h"
00057
00058 namespace opencv_apps
00059 {
00060 class HoughLinesNodelet : public opencv_apps::Nodelet
00061 {
00062 image_transport::Publisher img_pub_;
00063 image_transport::Subscriber img_sub_;
00064 image_transport::CameraSubscriber cam_sub_;
00065 ros::Publisher msg_pub_;
00066
00067 boost::shared_ptr<image_transport::ImageTransport> it_;
00068
00069 typedef opencv_apps::HoughLinesConfig Config;
00070 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00071 Config config_;
00072 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00073
00074 int queue_size_;
00075 bool debug_view_;
00076 ros::Time prev_stamp_;
00077
00078 std::string window_name_;
00079 static bool need_config_update_;
00080
00081 int min_threshold_;
00082 int max_threshold_;
00083 int threshold_;
00084 double rho_;
00085 double theta_;
00086 double minLineLength_;
00087 double maxLineGap_;
00088
00089 void reconfigureCallback(Config& new_config, uint32_t level)
00090 {
00091 config_ = new_config;
00092 rho_ = config_.rho;
00093 theta_ = config_.theta;
00094 threshold_ = config_.threshold;
00095 minLineLength_ = config_.minLineLength;
00096 maxLineGap_ = config_.maxLineGap;
00097 }
00098
00099 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00100 {
00101 if (frame.empty())
00102 return image_frame;
00103 return frame;
00104 }
00105
00106 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00107 {
00108 doWork(msg, cam_info->header.frame_id);
00109 }
00110
00111 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00112 {
00113 doWork(msg, msg->header.frame_id);
00114 }
00115
00116 static void trackbarCallback(int , void* )
00117 {
00118 need_config_update_ = true;
00119 }
00120
00121 void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00122 {
00123
00124 try
00125 {
00126
00127 cv::Mat in_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00128 cv::Mat src_gray;
00129
00130 if (in_image.channels() > 1)
00131 {
00132 cv::cvtColor(in_image, src_gray, cv::COLOR_BGR2GRAY);
00134 Canny(src_gray, in_image, 50, 200, 3);
00135 }
00136 else
00137 {
00139 bool is_filtered = true;
00140 for (int y = 0; y < in_image.rows; ++y)
00141 {
00142 for (int x = 0; x < in_image.cols; ++x)
00143 {
00144 if (!(in_image.at<unsigned char>(y, x) == 0 || in_image.at<unsigned char>(y, x) == 255))
00145 {
00146 is_filtered = false;
00147 break;
00148 }
00149 if (!is_filtered)
00150 {
00151 break;
00152 }
00153 }
00154 }
00155
00156 if (!is_filtered)
00157 {
00158 Canny(in_image, in_image, 50, 200, 3);
00159 }
00160 }
00161
00162 cv::Mat out_image;
00163 cv::cvtColor(in_image, out_image, CV_GRAY2BGR);
00164
00165
00166 opencv_apps::LineArrayStamped lines_msg;
00167 lines_msg.header = msg->header;
00168
00169
00170 std::vector<cv::Rect> faces;
00171
00172 if (debug_view_)
00173 {
00175 char thresh_label[50];
00176 sprintf(thresh_label, "Thres: %d + input", min_threshold_);
00177
00178 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00179 cv::createTrackbar(thresh_label, window_name_, &threshold_, max_threshold_, trackbarCallback);
00180 if (need_config_update_)
00181 {
00182 config_.threshold = threshold_;
00183 reconfigure_server_->updateConfig(config_);
00184 need_config_update_ = false;
00185 }
00186 }
00187
00188 switch (config_.hough_type)
00189 {
00190 case opencv_apps::HoughLines_Standard_Hough_Transform:
00191 {
00192 std::vector<cv::Vec2f> s_lines;
00193
00195 cv::HoughLines(in_image, s_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
00196
00198 for (const cv::Vec2f& s_line : s_lines)
00199 {
00200 float r = s_line[0], t = s_line[1];
00201 double cos_t = cos(t), sin_t = sin(t);
00202 double x0 = r * cos_t, y0 = r * sin_t;
00203 double alpha = 1000;
00204
00205 cv::Point pt1(cvRound(x0 + alpha * (-sin_t)), cvRound(y0 + alpha * cos_t));
00206 cv::Point pt2(cvRound(x0 - alpha * (-sin_t)), cvRound(y0 - alpha * cos_t));
00207 #ifndef CV_VERSION_EPOCH
00208 cv::line(out_image, pt1, pt2, cv::Scalar(255, 0, 0), 3, cv::LINE_AA);
00209 #else
00210 cv::line(out_image, pt1, pt2, cv::Scalar(255, 0, 0), 3, CV_AA);
00211 #endif
00212 opencv_apps::Line line_msg;
00213 line_msg.pt1.x = pt1.x;
00214 line_msg.pt1.y = pt1.y;
00215 line_msg.pt2.x = pt2.x;
00216 line_msg.pt2.y = pt2.y;
00217 lines_msg.lines.push_back(line_msg);
00218 }
00219
00220 break;
00221 }
00222 case opencv_apps::HoughLines_Probabilistic_Hough_Transform:
00223 default:
00224 {
00225 std::vector<cv::Vec4i> p_lines;
00226
00228 cv::HoughLinesP(in_image, p_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_);
00229
00231 for (const cv::Vec4i& l : p_lines)
00232 {
00233 #ifndef CV_VERSION_EPOCH
00234 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);
00235 #else
00236 cv::line(out_image, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255, 0, 0), 3, CV_AA);
00237 #endif
00238 opencv_apps::Line line_msg;
00239 line_msg.pt1.x = l[0];
00240 line_msg.pt1.y = l[1];
00241 line_msg.pt2.x = l[2];
00242 line_msg.pt2.y = l[3];
00243 lines_msg.lines.push_back(line_msg);
00244 }
00245
00246 break;
00247 }
00248 }
00249
00250
00251 if (debug_view_)
00252 {
00253 cv::imshow(window_name_, out_image);
00254 int c = cv::waitKey(1);
00255 }
00256
00257
00258 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
00259 img_pub_.publish(out_img);
00260 msg_pub_.publish(lines_msg);
00261 }
00262 catch (cv::Exception& e)
00263 {
00264 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00265 }
00266
00267 prev_stamp_ = msg->header.stamp;
00268 }
00269
00270 void subscribe()
00271 {
00272 NODELET_DEBUG("Subscribing to image topic.");
00273 if (config_.use_camera_info)
00274 cam_sub_ = it_->subscribeCamera("image", queue_size_, &HoughLinesNodelet::imageCallbackWithInfo, this);
00275 else
00276 img_sub_ = it_->subscribe("image", queue_size_, &HoughLinesNodelet::imageCallback, this);
00277 }
00278
00279 void unsubscribe()
00280 {
00281 NODELET_DEBUG("Unsubscribing from image topic.");
00282 img_sub_.shutdown();
00283 cam_sub_.shutdown();
00284 }
00285
00286 public:
00287 virtual void onInit()
00288 {
00289 Nodelet::onInit();
00290 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00291
00292 pnh_->param("queue_size", queue_size_, 3);
00293 pnh_->param("debug_view", debug_view_, false);
00294 if (debug_view_)
00295 {
00296 always_subscribe_ = true;
00297 }
00298 prev_stamp_ = ros::Time(0, 0);
00299
00300 window_name_ = "Hough Lines Demo";
00301 min_threshold_ = 50;
00302 max_threshold_ = 150;
00303 threshold_ = max_threshold_;
00304
00305 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00306 dynamic_reconfigure::Server<Config>::CallbackType f =
00307 boost::bind(&HoughLinesNodelet::reconfigureCallback, this, _1, _2);
00308 reconfigure_server_->setCallback(f);
00309
00310 img_pub_ = advertiseImage(*pnh_, "image", 1);
00311 msg_pub_ = advertise<opencv_apps::LineArrayStamped>(*pnh_, "lines", 1);
00312
00313 onInitPostProcess();
00314 }
00315 };
00316 bool HoughLinesNodelet::need_config_update_ = false;
00317 }
00318
00319 namespace hough_lines
00320 {
00321 class HoughLinesNodelet : public opencv_apps::HoughLinesNodelet
00322 {
00323 public:
00324 virtual void onInit()
00325 {
00326 ROS_WARN("DeprecationWarning: Nodelet hough_lines/hough_lines is deprecated, "
00327 "and renamed to opencv_apps/hough_lines.");
00328 opencv_apps::HoughLinesNodelet::onInit();
00329 }
00330 };
00331 }
00332
00333 #include <pluginlib/class_list_macros.h>
00334 PLUGINLIB_EXPORT_CLASS(opencv_apps::HoughLinesNodelet, nodelet::Nodelet);
00335 PLUGINLIB_EXPORT_CLASS(hough_lines::HoughLinesNodelet, nodelet::Nodelet);