rectangle_detector.cpp
Go to the documentation of this file.
1 
6 // https://raw.github.com/bsdnoobz/opencv-code/master/quad-segmentation.cpp
7 
8 #include <ros/ros.h>
12 #include <jsk_recognition_msgs/LineArray.h>
13 #include <jsk_perception/RectangleDetectorConfig.h>
15 #include <cv_bridge/cv_bridge.h>
17 #include <opencv2/imgproc/imgproc.hpp>
18 #include "opencv2/highgui/highgui.hpp"
19 
20 #include <dynamic_reconfigure/server.h>
21 
23 
24 using namespace message_filters;
25 
27 {
28  jsk_perception::RectangleDetectorConfig config_;
29  dynamic_reconfigure::Server<jsk_perception::RectangleDetectorConfig> srv;
30 
31  //image_transport::Publisher image_pub_;
35  //int subscriber_count_;
36 
40 
41  double _threshold1;
42  double _threshold2;
45 
46  void reconfigureCallback(jsk_perception::RectangleDetectorConfig &new_config, uint32_t level)
47  {
48  config_ = new_config;
49  _threshold1 = config_.threshold1;
50  _threshold2 = config_.threshold2;
51  _apertureSize = config_.apertureSize;
52  _L2gradient = config_.L2gradient;
53  }
54 
55  cv::Point2f computeIntersect(cv::Vec4i a,
56  cv::Vec4i b)
57  {
58  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];
59  float denom;
60 
61  if (float d = ((float)(x1 - x2) * (y3 - y4)) - ((y1 - y2) * (x3 - x4)))
62  {
63  cv::Point2f pt;
64  pt.x = ((x1 * y2 - y1 * x2) * (x3 - x4) - (x1 - x2) * (x3 * y4 - y3 * x4)) / d;
65  pt.y = ((x1 * y2 - y1 * x2) * (y3 - y4) - (y1 - y2) * (x3 * y4 - y3 * x4)) / d;
66  return pt;
67  }
68  else
69  return cv::Point2f(-1, -1);
70  }
71 
72  void sortCorners(std::vector<cv::Point2f>& corners,
73  cv::Point2f center)
74  {
75  std::vector<cv::Point2f> top, bot;
76 
77  for (int i = 0; i < corners.size(); i++)
78  {
79  if (corners[i].y < center.y)
80  top.push_back(corners[i]);
81  else
82  bot.push_back(corners[i]);
83  }
84 
85  cv::Point2f tl = top[0].x > top[1].x ? top[1] : top[0];
86  cv::Point2f tr = top[0].x > top[1].x ? top[0] : top[1];
87  cv::Point2f bl = bot[0].x > bot[1].x ? bot[1] : bot[0];
88  cv::Point2f br = bot[0].x > bot[1].x ? bot[0] : bot[1];
89 
90  corners.clear();
91  corners.push_back(tl);
92  corners.push_back(tr);
93  corners.push_back(br);
94  corners.push_back(bl);
95  }
96 
97  void callback(const sensor_msgs::ImageConstPtr& image,
98  const jsk_recognition_msgs::LineArrayConstPtr& line)
99  {
100  // Transform the image.
101  try
102  {
103  if ( line->lines.size() < 4 ) return;
104 
105  // Convert the image into something opencv can handle.
106  cv::Mat src = cv_bridge::toCvShare(image, image->encoding)->image;
107  std::vector<cv::Vec4i> lines;
108  lines.resize(line->lines.size());
109 
110  // Expand the lines
111  for (int i = 0; i < lines.size(); i++)
112  {
113  cv::Vec4i v;
114  v[0] = line->lines[i].x1; v[1] = line->lines[i].y1;
115  v[2] = line->lines[i].x2; v[3] = line->lines[i].y2;
116  lines[i][0] = 0;
117  lines[i][1] = ((float)v[1] - v[3]) / (v[0] - v[2]) * -v[0] + v[1];
118  lines[i][2] = src.cols;
119  lines[i][3] = ((float)v[1] - v[3]) / (v[0] - v[2]) * (src.cols - v[2]) + v[3];
120  }
121 
122  std::vector<cv::Point2f> corners;
123  for (int i = 0; i < lines.size(); i++)
124  {
125  for (int j = i+1; j < lines.size(); j++)
126  {
127  cv::Point2f pt = computeIntersect(lines[i], lines[j]);
128  if (pt.x >= 0 && pt.y >= 0)
129  corners.push_back(pt);
130  }
131  }
132 
133  std::vector<cv::Point2f> approx;
134  cv::approxPolyDP(cv::Mat(corners), approx, cv::arcLength(cv::Mat(corners), true) * 0.02, true);
135 
136  if (approx.size() != 4)
137  {
138  ROS_ERROR("The object is not quadrilateral!");
139  return ;
140  }
141 
142  // Get mass center
143  cv::Point2f center(0,0);
144  for (int i = 0; i < corners.size(); i++)
145  center += corners[i];
146  center *= (1. / corners.size());
147 
148  sortCorners(corners, center);
149 
150  cv::Mat dst = src.clone();
151 
152  // Draw lines
153  for (int i = 0; i < lines.size(); i++)
154  {
155  cv::Vec4i v = lines[i];
156  cv::line(dst, cv::Point(v[0], v[1]), cv::Point(v[2], v[3]), CV_RGB(0,255,0));
157  }
158 
159  // Draw corner points
160  cv::circle(dst, corners[0], 3, CV_RGB(255,0,0), 2);
161  cv::circle(dst, corners[1], 3, CV_RGB(0,255,0), 2);
162  cv::circle(dst, corners[2], 3, CV_RGB(0,0,255), 2);
163  cv::circle(dst, corners[3], 3, CV_RGB(255,255,255), 2);
164 
165  // Draw mass center
166  cv::circle(dst, center, 3, CV_RGB(255,255,0), 2);
167 
168  cv::Mat quad = cv::Mat::zeros(300, 220, CV_8UC3);
169 
170  std::vector<cv::Point2f> quad_pts;
171  quad_pts.push_back(cv::Point2f(0, 0));
172  quad_pts.push_back(cv::Point2f(quad.cols, 0));
173  quad_pts.push_back(cv::Point2f(quad.cols, quad.rows));
174  quad_pts.push_back(cv::Point2f(0, quad.rows));
175 
176  cv::Mat transmtx = cv::getPerspectiveTransform(corners, quad_pts);
177  cv::warpPerspective(src, quad, transmtx, quad.size());
178 
179  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image->header, enc::RGB8, dst).toImageMsg();
180  //sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image->header, enc::RGB8, quad).toImageMsg();
181  image_pub_.publish(out_img);
182  }
183  catch (cv::Exception &e)
184  {
185  ROS_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
186  }
187  }
188 
189 public:
191  {
192 
193  image_sub = new message_filters::Subscriber<sensor_msgs::Image>(nh_, "image", 1);
194  line_sub = new message_filters::Subscriber<jsk_recognition_msgs::LineArray>(nh_, "lines", 1);
195  sync = new TimeSynchronizer<sensor_msgs::Image, jsk_recognition_msgs::LineArray>(*image_sub, *line_sub, 10);
196  sync->registerCallback(boost::bind(&RectangleDetector::callback, this, _1, _2));
197  image_pub_ = nh_.advertise<sensor_msgs::Image>("rectangle/image", 1);
198 
199  dynamic_reconfigure::Server<jsk_perception::RectangleDetectorConfig>::CallbackType f =
200  boost::bind(&RectangleDetector::reconfigureCallback, this, _1, _2);
201  srv.setCallback(f);
202  }
203 };
204 
205 int main(int argc, char **argv)
206 {
207  ros::init(argc, argv, "edge_detector", ros::init_options::AnonymousName);
208 
210  ros::spin();
211 }
d
Definition: setup.py:6
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
f
ros::Publisher image_pub_
cv::Point2f computeIntersect(cv::Vec4i a, cv::Vec4i b)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void sortCorners(std::vector< cv::Point2f > &corners, cv::Point2f center)
message_filters::Subscriber< jsk_recognition_msgs::LineArray > * line_sub
ROSCPP_DECL void spin(Spinner &spinner)
return(serverAddr)
void callback(const sensor_msgs::ImageConstPtr &image, const jsk_recognition_msgs::LineArrayConstPtr &line)
float
TimeSynchronizer< sensor_msgs::Image, jsk_recognition_msgs::LineArray > * sync
RectangleDetector(ros::NodeHandle nh=ros::NodeHandle())
y
image_transport::ImageTransport it_
int main(int argc, char **argv)
dynamic_reconfigure::Server< jsk_perception::RectangleDetectorConfig > srv
void reconfigureCallback(jsk_perception::RectangleDetectorConfig &new_config, uint32_t level)
jsk_perception::RectangleDetectorConfig config_
message_filters::Subscriber< sensor_msgs::Image > * image_sub
GLfloat v[8][3]
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
Connection registerCallback(const C &callback)


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27