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