hough_lines.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <jsk_topic_tools/log_utils.h>
00003 #include <jsk_perception/HoughLinesConfig.h>
00004 #include <jsk_recognition_msgs/LineArray.h>
00005 #include <image_transport/image_transport.h>
00006 #include <cv_bridge/cv_bridge.h>
00007 #include <sensor_msgs/image_encodings.h>
00008 #include <opencv2/imgproc/imgproc.hpp>
00009 #include "opencv2/highgui/highgui.hpp"
00010 
00011 #include <dynamic_reconfigure/server.h>
00012 
00013 namespace enc = sensor_msgs::image_encodings;
00014 
00015 class HoughLines
00016 {
00017     jsk_perception::HoughLinesConfig config_;
00018     dynamic_reconfigure::Server<jsk_perception::HoughLinesConfig> srv;
00019 
00020     image_transport::Publisher img_pub_;
00021     image_transport::Subscriber img_sub_;
00022     ros::Publisher out_pub_;
00023 
00024     image_transport::ImageTransport it_;
00025     ros::NodeHandle nh_;
00026     int subscriber_count_;
00027 
00028     double _rho;
00029     double _theta;
00030     int    _threshold;
00031     double _minLineLength;
00032     double _maxLineGap;
00033 
00034     void reconfigureCallback(jsk_perception::HoughLinesConfig &new_config, uint32_t level)
00035     {
00036         config_ = new_config;
00037         _rho            = config_.rho;
00038         _theta          = config_.theta;
00039         _threshold       = config_.threshold;
00040         _minLineLength  = config_.minLineLength;
00041         _maxLineGap     = config_.maxLineGap;
00042         if (subscriber_count_)
00043             { // @todo Could do this without an interruption at some point.
00044                 unsubscribe();
00045                 subscribe();
00046             }
00047     }
00048 
00049     void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00050     {
00051         do_work(msg, msg->header.frame_id);
00052     }
00053 
00054     void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00055     {
00056         // Transform the image.
00057         try
00058             {
00059                 // Convert the image into something opencv can handle.
00060                 cv::Mat in_image = cv_bridge::toCvShare(msg, msg->encoding)->image;
00061 
00062                 if (msg->encoding != enc::MONO8) {
00063                     JSK_ROS_ERROR("Hough Lines assume monochrome image for input");
00064                     return;
00065                 }
00066 
00067                 cv::Mat out_image;
00068                 cvtColor(in_image, out_image, CV_GRAY2BGR);
00069 
00070                 // Do the work
00071                 JSK_ROS_INFO_STREAM("Hough Lines : rho:" << _rho << ", tehta:" << _theta << ", threshold:" <<  _threshold << ", minLineLength:" <<  _minLineLength << ", maxLineGap" <<  _maxLineGap);
00072 #if 1
00073                 std::vector<cv::Vec4i> lines;
00074                 cv::HoughLinesP( in_image, lines, _rho, _theta*CV_PI/180 , _threshold, _minLineLength, _maxLineGap );
00075                 jsk_recognition_msgs::LineArray out_lines;
00076                 out_lines.header = msg->header;
00077                 out_lines.lines.resize(lines.size());
00078                 for( size_t i = 0; i < lines.size(); i++ )
00079                     {
00080                         out_lines.lines[i].x1 = lines[i][0];
00081                         out_lines.lines[i].y1 = lines[i][1];
00082                         out_lines.lines[i].x2 = lines[i][2];
00083                         out_lines.lines[i].y2 = lines[i][3];
00084                         cv::line( out_image, cv::Point(lines[i][0], lines[i][1]),
00085                                   cv::Point(lines[i][2], lines[i][3]), cv::Scalar(255,0,0), 3, 8 );
00086                     }
00087 #else
00088                 std::vector<cv::Vec2f> lines;
00089                 cv::HoughLines( in_image, lines, _rho, _theta, _threshold*CV_PI/180, _minLineLength, _maxLineGap );
00090                 jsk_recognition_msgs::LineArray out_lines;
00091                 out_lines.header = msg->header;
00092                 out_lines.lines.resize(lines.size());
00093                 for( size_t i = 0; i < lines.size(); i++ )
00094                     {
00095                         float rho = lines[i][0];
00096                         float theta = lines[i][1];
00097                         double a = cos(theta), b = sin(theta);
00098                         double x0 = a*rho, y0 = b*rho;
00099                         cv::Point pt1(cvRound(x0 + 1000*(-b)),
00100                                       cvRound(y0 + 1000*(a)));
00101                         cv::Point pt2(cvRound(x0 - 1000*(-b)),
00102                                       cvRound(y0 - 1000*(a)));
00103                         cv::line( out_image, pt1, pt2, cv::Scalar(0,0,255), 3, 8 );
00104                     }
00105 #endif
00106 
00107                 // Publish the image.
00108                 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, enc::RGB8, out_image).toImageMsg();
00109                 out_pub_.publish(out_lines);
00110                 img_pub_.publish(out_img);
00111             }
00112         catch (cv::Exception &e)
00113             {
00114                 JSK_ROS_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00115             }
00116     }
00117 
00118     void subscribe()
00119     {
00120         JSK_ROS_DEBUG("Subscribing to image topic.");
00121         img_sub_ = it_.subscribe("image", 3, &HoughLines::imageCallback, this);
00122     }
00123 
00124     void unsubscribe()
00125     {
00126         JSK_ROS_DEBUG("Unsubscribing from image topic.");
00127         img_sub_.shutdown();
00128     }
00129 
00130     void connectCb(const image_transport::SingleSubscriberPublisher& ssp)
00131     {
00132         if (subscriber_count_++ == 0) {
00133             subscribe();
00134         }
00135     }
00136 
00137     void disconnectCb(const image_transport::SingleSubscriberPublisher&)
00138     {
00139         subscriber_count_--;
00140         if (subscriber_count_ == 0) {
00141             unsubscribe();
00142         }
00143     }
00144 
00145 public:
00146     HoughLines(ros::NodeHandle nh = ros::NodeHandle()) : it_(nh), nh_(nh), subscriber_count_(0)
00147     {
00148         image_transport::SubscriberStatusCallback connect_cb    = boost::bind(&HoughLines::connectCb, this, _1);
00149         image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&HoughLines::disconnectCb, this, _1);
00150         img_pub_ = image_transport::ImageTransport(ros::NodeHandle(nh_, "hough")).advertise("image", 1, connect_cb, disconnect_cb);
00151 
00152         out_pub_ = nh.advertise<jsk_recognition_msgs::LineArray>(nh_.resolveName("lines"), 1);
00153 
00154 
00155         dynamic_reconfigure::Server<jsk_perception::HoughLinesConfig>::CallbackType f =
00156             boost::bind(&HoughLines::reconfigureCallback, this, _1, _2);
00157         srv.setCallback(f);
00158     }
00159 };
00160 
00161 int main(int argc, char **argv)
00162 {
00163     ros::init(argc, argv, "hough_lines", ros::init_options::AnonymousName);
00164 
00165     HoughLines hl;
00166     ros::spin();
00167 }


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15