rectangle_detector.cpp
Go to the documentation of this file.
00001 
00006 // https://raw.github.com/bsdnoobz/opencv-code/master/quad-segmentation.cpp
00007 
00008 #include <ros/ros.h>
00009 #include <message_filters/subscriber.h>
00010 #include <message_filters/time_synchronizer.h>
00011 #include <jsk_perception/LineArray.h>
00012 #include <jsk_perception/RectangleDetectorConfig.h>
00013 #include <image_transport/image_transport.h>
00014 #include <cv_bridge/cv_bridge.h>
00015 #include <sensor_msgs/image_encodings.h>
00016 #include <opencv2/imgproc/imgproc.hpp>
00017 #include "opencv2/highgui/highgui.hpp"
00018 
00019 #include <dynamic_reconfigure/server.h>
00020 
00021 namespace enc = sensor_msgs::image_encodings;
00022 
00023 using namespace message_filters;
00024 
00025 class RectangleDetector
00026 {
00027     jsk_perception::RectangleDetectorConfig config_;
00028     dynamic_reconfigure::Server<jsk_perception::RectangleDetectorConfig> srv;
00029 
00030     //image_transport::Publisher image_pub_;
00031     ros::Publisher image_pub_;
00032     image_transport::ImageTransport it_;
00033     ros::NodeHandle nh_;
00034     //int subscriber_count_;
00035 
00036     message_filters::Subscriber<sensor_msgs::Image> *image_sub;
00037     message_filters::Subscriber<jsk_perception::LineArray> *line_sub;
00038     TimeSynchronizer<sensor_msgs::Image, jsk_perception::LineArray> *sync;
00039 
00040     double _threshold1;
00041     double _threshold2;
00042     int _apertureSize;
00043     bool _L2gradient;
00044 
00045     void reconfigureCallback(jsk_perception::RectangleDetectorConfig &new_config, uint32_t level)
00046     {
00047         config_ = new_config;
00048         _threshold1 = config_.threshold1;
00049         _threshold2 = config_.threshold2;
00050         _apertureSize = config_.apertureSize;
00051         _L2gradient = config_.L2gradient;
00052     }
00053 
00054     cv::Point2f computeIntersect(cv::Vec4i a,
00055                                  cv::Vec4i b)
00056     {
00057         int x1 = a[0], y1 = a[1], x2 = a[2], y2 = a[3], x3 = b[0], y3 = b[1], x4 = b[2], y4 = b[3];
00058         float denom;
00059 
00060         if (float d = ((float)(x1 - x2) * (y3 - y4)) - ((y1 - y2) * (x3 - x4)))
00061             {
00062                 cv::Point2f pt;
00063                 pt.x = ((x1 * y2 - y1 * x2) * (x3 - x4) - (x1 - x2) * (x3 * y4 - y3 * x4)) / d;
00064                 pt.y = ((x1 * y2 - y1 * x2) * (y3 - y4) - (y1 - y2) * (x3 * y4 - y3 * x4)) / d;
00065                 return pt;
00066             }
00067         else
00068             return cv::Point2f(-1, -1);
00069     }
00070 
00071     void sortCorners(std::vector<cv::Point2f>& corners, 
00072                      cv::Point2f center)
00073     {
00074         std::vector<cv::Point2f> top, bot;
00075 
00076         for (int i = 0; i < corners.size(); i++)
00077             {
00078                 if (corners[i].y < center.y)
00079                     top.push_back(corners[i]);
00080                 else
00081                     bot.push_back(corners[i]);
00082             }
00083 
00084         cv::Point2f tl = top[0].x > top[1].x ? top[1] : top[0];
00085         cv::Point2f tr = top[0].x > top[1].x ? top[0] : top[1];
00086         cv::Point2f bl = bot[0].x > bot[1].x ? bot[1] : bot[0];
00087         cv::Point2f br = bot[0].x > bot[1].x ? bot[0] : bot[1];
00088 
00089         corners.clear();
00090         corners.push_back(tl);
00091         corners.push_back(tr);
00092         corners.push_back(br);
00093         corners.push_back(bl);
00094     }
00095 
00096     void callback(const sensor_msgs::ImageConstPtr& image,
00097                   const jsk_perception::LineArrayConstPtr& line)
00098     {
00099         // Transform the image.
00100         try
00101             {
00102                 if ( line->lines.size() < 4 ) return;
00103 
00104                 // Convert the image into something opencv can handle.
00105                 cv::Mat src = cv_bridge::toCvShare(image, image->encoding)->image;
00106                 std::vector<cv::Vec4i> lines;
00107                 lines.resize(line->lines.size());
00108 
00109                 // Expand the lines
00110                 for (int i = 0; i < lines.size(); i++)
00111                     {
00112                         cv::Vec4i v;
00113                         v[0] = line->lines[i].x1; v[1] = line->lines[i].y1;
00114                         v[2] = line->lines[i].x2; v[3] = line->lines[i].y2;
00115                         lines[i][0] = 0;
00116                         lines[i][1] = ((float)v[1] - v[3]) / (v[0] - v[2]) * -v[0] + v[1];
00117                         lines[i][2] = src.cols;
00118                         lines[i][3] = ((float)v[1] - v[3]) / (v[0] - v[2]) * (src.cols - v[2]) + v[3];
00119                     }
00120 
00121                 std::vector<cv::Point2f> corners;
00122                 for (int i = 0; i < lines.size(); i++)
00123                     {
00124                         for (int j = i+1; j < lines.size(); j++)
00125                             {
00126                                 cv::Point2f pt = computeIntersect(lines[i], lines[j]);
00127                                 if (pt.x >= 0 && pt.y >= 0)
00128                                     corners.push_back(pt);
00129                             }
00130                     }
00131 
00132                 std::vector<cv::Point2f> approx;
00133                 cv::approxPolyDP(cv::Mat(corners), approx, cv::arcLength(cv::Mat(corners), true) * 0.02, true);
00134 
00135                 if (approx.size() != 4)
00136                     {
00137                         ROS_ERROR("The object is not quadrilateral!");
00138                         return ;
00139                     }
00140 
00141                 // Get mass center
00142                 cv::Point2f center(0,0);
00143                 for (int i = 0; i < corners.size(); i++)
00144                     center += corners[i];
00145                 center *= (1. / corners.size());
00146 
00147                 sortCorners(corners, center);
00148 
00149                 cv::Mat dst = src.clone();
00150 
00151                 // Draw lines
00152                 for (int i = 0; i < lines.size(); i++)
00153                     {
00154                         cv::Vec4i v = lines[i];
00155                         cv::line(dst, cv::Point(v[0], v[1]), cv::Point(v[2], v[3]), CV_RGB(0,255,0));
00156                     }
00157 
00158                 // Draw corner points
00159                 cv::circle(dst, corners[0], 3, CV_RGB(255,0,0), 2);
00160                 cv::circle(dst, corners[1], 3, CV_RGB(0,255,0), 2);
00161                 cv::circle(dst, corners[2], 3, CV_RGB(0,0,255), 2);
00162                 cv::circle(dst, corners[3], 3, CV_RGB(255,255,255), 2);
00163 
00164                 // Draw mass center
00165                 cv::circle(dst, center, 3, CV_RGB(255,255,0), 2);
00166 
00167                 cv::Mat quad = cv::Mat::zeros(300, 220, CV_8UC3);
00168 
00169                 std::vector<cv::Point2f> quad_pts;
00170                 quad_pts.push_back(cv::Point2f(0, 0));
00171                 quad_pts.push_back(cv::Point2f(quad.cols, 0));
00172                 quad_pts.push_back(cv::Point2f(quad.cols, quad.rows));
00173                 quad_pts.push_back(cv::Point2f(0, quad.rows));
00174 
00175                 cv::Mat transmtx = cv::getPerspectiveTransform(corners, quad_pts);
00176                 cv::warpPerspective(src, quad, transmtx, quad.size());
00177 
00178                 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image->header, enc::RGB8, dst).toImageMsg();
00179                 //sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image->header, enc::RGB8, quad).toImageMsg();
00180                 image_pub_.publish(out_img);
00181             }
00182         catch (cv::Exception &e)
00183             {
00184                 ROS_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00185             }
00186     }
00187 
00188 public:
00189     RectangleDetector(ros::NodeHandle nh = ros::NodeHandle()) : it_(nh), nh_(nh)
00190     {
00191 
00192         image_sub = new message_filters::Subscriber<sensor_msgs::Image>(nh_, "image", 1);
00193         line_sub = new message_filters::Subscriber<jsk_perception::LineArray>(nh_, "lines", 1);
00194         sync = new TimeSynchronizer<sensor_msgs::Image, jsk_perception::LineArray>(*image_sub, *line_sub, 10);
00195         sync->registerCallback(boost::bind(&RectangleDetector::callback, this, _1, _2));
00196         image_pub_ = nh_.advertise<sensor_msgs::Image>("rectangle/image", 1);
00197 
00198         dynamic_reconfigure::Server<jsk_perception::RectangleDetectorConfig>::CallbackType f =
00199             boost::bind(&RectangleDetector::reconfigureCallback, this, _1, _2);
00200         srv.setCallback(f);
00201     }
00202 };
00203 
00204 int main(int argc, char **argv)
00205 {
00206     ros::init(argc, argv, "edge_detector", ros::init_options::AnonymousName);
00207 
00208     RectangleDetector rd;
00209     ros::spin();
00210 }


jsk_perception
Author(s): Manabu Saito
autogenerated on Mon Oct 6 2014 01:16:59