ellipses_detection.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2014 by Markus Bader *
3  * markus.bader@tuwien.ac.at *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU General Public License as published by *
7  * the Free Software Foundation; either version 2 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the GNU General Public License *
16  * along with this program; if not, write to the *
17  * Free Software Foundation, Inc., *
18  * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
19  ***************************************************************************/
20 
21 #include <opencv2/imgproc/imgproc.hpp>
22 #include <opencv2/calib3d/calib3d.hpp>
23 #include <numeric> // std::inner_product
26 #include <boost/foreach.hpp>
27 #include "tuw_utils/canny.h"
29 
30 using namespace tuw;
31 
32 
34 {
35  if(param_ != NULL) delete param_;
36 }
37 
39  :param_(param), loop_count(0) {
40 }
41 
43  ellipses_.clear();
44  ellipses_.resize(contours_.size());
45  cv::Mat cameraMatrix, distCoeffs;
46  for(unsigned int i = 0; i < contours_.size(); i++) {
47  unsigned int count = contours_[i].size();
48  Ellipse &ellipse = ellipses_[i];
49  ellipse.init();
50  ellipse.id = i;
51  if(param_->filter_convex) {
52  cv::approxPolyDP( cv::Mat (contours_[i]), *ellipse.polygon, param_->threshold_polygon, true );
53  ellipse.boxContour = cv::boundingRect( cv::Mat(*ellipse.polygon) );
54  //cv::minEnclosingCircle( (cv::Mat)*ellipse.polygon, ellipse.centerContour, ellipse.radiusContour );
55  }
56  ellipse.contourDistort->resize(count);
57  ellipse.contourUndistort->resize(count);
58  for(unsigned int j = 0; j < count; j++) {
59  (*ellipse.contourDistort)[j] = contours_[i][j];
60  (*ellipse.contourUndistort)[j] = contours_[i][j];
61  }
62  if(param_->distorted_input) {
63  cv::undistortPoints(*ellipse.contourDistort, *ellipse.contourUndistort, camera_.cameraMatrix, camera_.distCoeffs, cv::Mat(), camera_.projectionMatrix);
64  }
65  }
66 }
67 
68 
70  if(ellipse.contourDistort->size() < param_->threshold_contour_min_points) {
72  return ellipse.detection;
73  }
74  if(param_->filter_convex && !cv::isContourConvex(*ellipse.polygon)) {
76  return ellipse.detection;
77  }
78  return ellipse.detection;
79 }
80 
81 void EllipsesDetection::edge_detection(const cv::Mat &m) {
82  imgGray_ = m;
83  switch(param_->edge_detection) {
86  break;
88  cv::blur(imgGray_, imgBlured_, cv::Size(3,3) );
90  break;
91  }
92 }
93 
95  switch(param_->edge_linking) {
97  cv::findContours ( imgEdges_, contours_, CV_RETR_LIST, CV_CHAIN_APPROX_NONE );
98  break;
100  cv::findContours( imgEdges_, contours_, CV_RETR_LIST, CV_CHAIN_APPROX_SIMPLE );
101  break;
107  break;
113  break;
119  break;
120  }
121 }
122 
123 void EllipsesDetection::fit_ellipses_opencv (const cv::Mat &m, const cv::Mat cameraMatrix, const cv::Mat distCoeffs, const cv::Mat projectionMatrix, const boost::posix_time::ptime &tstamp) {
124  loop_count++;
125  tstamp_ = tstamp;
126  if(param_->distorted_input) {
127  cameraMatrix.convertTo(camera_.cameraMatrix, CV_64F) ;
128  distCoeffs.convertTo(camera_.distCoeffs, CV_64F) ;
129  projectionMatrix(cv::Rect(0,0,3,3)).convertTo(camera_.projectionMatrix, CV_64F) ;
131  } else {
132  projectionMatrix(cv::Rect(0,0,3,3)).convertTo(camera_.cameraMatrix, CV_64F) ;
133  camera_.distCoeffs = (cv::Mat_<double>(1,5) << 0, 0, 0, 0, 0);
134  projectionMatrix(cv::Rect(0,0,3,3)).convertTo(camera_.projectionMatrix, CV_64F) ;
135  }
136 
137  edge_detection(m);
140 
141  double min_radius = m.rows * param_->threshold_min_radius;
142  double max_radius = m.rows * param_->threshold_max_radius;
143 
144  for(unsigned int i = 0; i < ellipses_.size(); i++) {
145  Ellipse &ellipse = ellipses_[i];
146  if(filterContour (ellipse) != VALID) continue;
147  cv::Mat pointsf(*ellipse.contourUndistort);
148  ellipse.boxEllipse = fitEllipse ( pointsf );
149  ellipse.radiusEllipseMax = MAX( ellipse.boxEllipse.size.width , ellipse.boxEllipse.size.height) / 2.0;
150  ellipse.radiusEllipseMin = MIN( ellipse.boxEllipse.size.width , ellipse.boxEllipse.size.height) / 2.0;
151  if(ellipse.radiusEllipseMax < min_radius) {
152  ellipse.detection = INVALID_MIN_RAIDUS;
153  }
154  if(ellipse.radiusEllipseMax > max_radius) {
155  ellipse.detection = INVALID_MAX_RAIDUS;
156  }
157  if(filterEllipse (ellipse) != VALID) continue;
158  if(filterContourMean(ellipse) != VALID) continue;
159  }
160  if(param_->ellipse_redefinement &&!imgSobelDx_.empty() && !imgSobelDy_.empty()) {
161  for(unsigned int i = 0; i < ellipses_.size(); i++) {
163  }
164  }
165 }
166 
168 
170  if(ellipse.detection != VALID) return ellipse.detection;
171 
173  e.setEllipse(ellipse.boxEllipse);
174  ellipseRefinementDual.refine(imgSobelDx_, imgSobelDy_, *ellipse.contourUndistort, e);
175  e.get(ellipse.boxEllipse);
176  return ellipse.detection;
177 }
178 
179 
181  if(ellipse.detection != VALID) return ellipse.detection;
182  double boxEllipseRatio = ellipse.radiusEllipseMin / ellipse.radiusEllipseMax;
183  if ( boxEllipseRatio < param_->threshold_ring_ratio ) {
185  return ellipse.detection;
186  }
187  return ellipse.detection;
188 }
189 
191  if(!param_->filter_rings) return;
192  for(std::vector<Ellipse>::iterator a = ellipses_.begin(); a != ellipses_.end(); a++) {
193  if((a->innerRing >= 0) || (a->outerRing >= 0) || (a->detection != VALID)) continue;
194  double threshold_center = a->radiusEllipseMax * param_->threshold_ring_center;
195  for(std::vector<Ellipse>::iterator b = ellipses_.begin(); b != ellipses_.end(); b++) {
196  if((a->id == b->id) || (b->innerRing != -1) || (b->outerRing != -1) || (b->detection != VALID) ) {
197  continue;
198  }
199  double d = cv::norm(a->boxEllipse.center - b->boxEllipse.center);
200  if(d < threshold_center) {
201  Ellipse *outer = &(*a), *inner = &(*b);
202  if(a->radiusEllipseMax < b->radiusEllipseMax) outer = &(*b), inner = &(*a);
203  double ratioRadiusRingMax = fabs(inner->radiusEllipseMax / outer->radiusEllipseMax-0.5);
204  double ratioRadiusRingMin = fabs(inner->radiusEllipseMax / outer->radiusEllipseMax-0.5);
205  if((ratioRadiusRingMax > param_->threshold_ring_ratio) || (ratioRadiusRingMin > param_->threshold_ring_ratio)) {
206  continue;
207  }
208  outer->innerRing = inner->id;
209  inner->outerRing = outer->id;
210  inner->detection = INVALID_IS_INNER_RING;
211  break;
212  }
213  }
214  if((a->innerRing == -1) && (a->outerRing == -1)) a->detection = INVALID_NO_RING;
215  }
216 }
217 
219  contours_.clear();
220  ellipses_.clear();
222 }
223 
225  if(!param_->filter_contour_mean || (ellipse.detection != VALID)) return ellipse.detection;
226  const std::vector<cv::Point2f> &contour = *(ellipse.contourUndistort.get());
227  ellipse.distances = boost::shared_ptr<std::vector<double> >(new std::vector<double> );
228  std::vector<double > &distances = *(ellipse.distances.get());
229  const cv::Point2f &pc = ellipse.boxEllipse.center;
230  double angle = M_PI/180.0 * (double) ellipse.boxEllipse.angle;
231  double ca = cos(angle), sa = sin(angle);
232  double a = ellipse.boxEllipse.size.width/2., b = ellipse.boxEllipse.size.height/2.;
233  double sum = 0;
234  distances.reserve(contour.size());
235  for(unsigned int i = 0; i < contour.size(); i++) {
236  double dx = contour[i].x - pc.x, dy = contour[i].y - pc.y;
237  double u = ca*dx + sa*dy, v = -sa*dx + ca*dy;
238  cv::Point2d p(contour[i].x - pc.x, contour[i].y - pc.y);
239  double d = (u*u)/(a*a) + (v*v)/(b*b);
240  distances.push_back(d);
241  sum += d;
242  // http://stackoverflow.com/questions/11041547/finding-the-distance-of-a-point-to-an-ellipse-wether-its-inside-or-outside-of-e
243  }
244  double mean = sum / distances.size();
245  double diff = fabs((mean - 1.));
246  if(diff > param_->threshold_contour_mean) {
248  }
249  return ellipse.detection;
250 }
251 
252 
255  cv::Point2f pi[4];
256  if(param_->circle_diameter <= 0) return;
257  cv::Mat_<double> rvec, tvec;
258  double radius = param_->circle_diameter / 2.0;
259  cv::Mat objectPoints = (cv::Mat_<double>(5,3) << 0, 0, 0, -radius, +radius, 0, +radius, +radius, 0, +radius, -radius, 0, -radius, -radius, 0);
260  for(std::vector<Ellipse>::iterator it = ellipses_.begin(); it != ellipses_.end(); it++) {
261  Ellipse &ellipse = *it;
262  if(ellipse.detection != VALID) continue;
263 
264  ellipse.boxEllipse.points(pi);
265  cv::Point2f& pc = ellipse.boxEllipse.center;
266  cv::Mat imagePoints = (cv::Mat_<double>(5,2) << pc.x, pc.y, pi[0].x, pi[0].y, pi[1].x, pi[1].y, pi[2].x, pi[2].y, pi[3].x, pi[3].y);
267  switch(param_->pose_estimation) {
269  cv::solvePnP(objectPoints, imagePoints, camera_.cameraMatrix, camera_.distCoeffs, rvec, tvec);
270  cv::Rodrigues(rvec, ellipse.cone.R[0]);
271  ellipse.cone.translations[0].x = tvec(0), ellipse.cone.translations[0].y = tvec(1), ellipse.cone.translations[0].z = tvec(2);
272  ellipse.cone.rotation2Normal(0);
273  ellipse.cone.R[1] = ellipse.cone.R[0].clone();
274  ellipse.cone.rotation2Normal(1);
275  break;
277  ellipse.cone.set(ellipse.boxEllipse, camera_.projectionMatrix);
279  ellipse.cone.normal2Roation(0);
280  ellipse.cone.normal2Roation(1);
281  break;
282  default:
283  continue;
284  }
285  }
286  markers_.clear();
287  for(std::vector<Ellipse>::iterator ellipse = ellipses_.begin(); ellipse != ellipses_.end(); ellipse++) {
288  if(ellipse->detection != VALID) continue;
289  markers_.push_back(ellipse->cone);
290  markers_.back().id = markers_.size()-1;
291  markers_.back().tstamp = tstamp_;
292  }
293 
294 }
295 
296 
298  cv::Mat_<double> tvec(translations[i]);
299  cv::Mat_<double> nvec = R[i] * (cv::Mat_<double>(3,1) << 0, 0, 1);
300  double d0 = cv::norm(tvec - nvec);
301  double d1 = cv::norm(tvec + nvec);
302  if(d1 < d0) {
303  nvec = -nvec;
304  }
305  normals[i][0] = nvec(0), normals[i][1] = nvec(1), normals[i][2] = nvec(2);
306 }
308  cv::Mat_<double> unitZ = (cv::Mat_<double>(3,1) << 0, 0, 1);
309  cv::Mat_<double> nvec(normals[i]);
310  nvec = nvec/cv::norm(nvec);
311  cv::Mat_<double> c2 = nvec;
312  cv::Mat_<double> c1 = unitZ.cross(c2);
313  cv::Mat_<double> c0 = c1.cross(c2);
314  c1 = c1/cv::norm(c1);
315  c0 = c0/cv::norm(c0);
316  R[i] = (cv::Mat_<double>(3,3) << c0(0), c1(0), c2(0), c0(1), c1(1), c2(1), c0(2), c1(2), c2(2));
317 }
318 
319 
320 double EllipsesDetection::ObliqueCone::distance(const cv::Point2d p) {
321  cv::Mat_<double> P = (cv::Mat_<double>(3,1) << p.x, p.y, 1);
322  cv::Mat_<double> D = P.t() * C * P;
323  double d = D(0,0);
324  return d;
325 }
326 void EllipsesDetection::ObliqueCone::set(cv::RotatedRect box, cv::Mat_<double> intrinsic) {
327  double a = box.size.width/2., b = box.size.height/2.;
328  double angle = M_PI/180.0 * (float) box.angle;
329  double ca = cos(angle), sa = sin(angle);
330  double cx = intrinsic(0,2), cy = intrinsic(1,2);
331  cv::Mat_<double> Re = (cv::Mat_<double>(2,2) << ca, -sa, sa, ca);
332  cv::Mat_<double> ABInvTAB = (cv::Mat_<double>(2,2) << 1./(a*a), 0., 0., 1./(b*b));
333  cv::Mat_<double> X0 = (cv::Mat_<double>(2,1) << box.center.x-cx, box.center.y-cy);
334  cv::Mat_<double> M = Re * ABInvTAB * Re.t();
335  cv::Mat_<double> Mf = X0.t() * M * X0;
336  double A = M(0,0);
337  double B = M(0,1);
338  double C = M(1,1);
339  double D = - A * X0(0) - B * X0(1);
340  double E = - B * X0(0) - C * X0(1);
341  double F = Mf(0,0) - 1.0;
342  this->C = (cv::Mat_<double>(3,3) << A, B, D,
343  B, C, E,
344  D, E, F);
345 }
346 
347 
348 
349 
350 void EllipsesDetection::ObliqueCone::pose(cv::Mat_<double> intrinsic, cv::Mat_<double> distCoeffs, double radius) {
351  cv::Mat_<double> Q, V, E;
352 
353  double fx = intrinsic(0,0), fy = intrinsic(1,1);
354  double focalLength = (fx+fy)/2.0;
355  if(focalLength == 0) return;
356  Q = this->C.clone();
357  Q(0,0) = this->C(0,0);
358  Q(0,1) = this->C(0,1);
359  Q(0,2) = this->C(0,2) / (focalLength);
360  Q(1,0) = this->C(1,0);
361  Q(1,1) = this->C(1,1);
362  Q(1,2) = this->C(1,2) / (focalLength);
363  Q(2,0) = this->C(2,0) / (focalLength);
364  Q(2,1) = this->C(2,1) / (focalLength);
365  Q(2,2) = this->C(2,2) / (focalLength*focalLength);
366 
367  cv::eigen(Q, E, V);
368  V = V.t();
369  double e1 = E.at<double>(0);
370  double e2 = E.at<double>(1);
371  double e3 = E.at<double>(2);
372  double S1[] = {+1,+1,+1,+1,-1,-1,-1,-1};
373  double S2[] = {+1,+1,-1,-1,+1,+1,-1,-1};
374  double S3[] = {+1,-1,+1,-1,+1,-1,+1,-1};
375 
376  double g = sqrt((e2-e3)/(e1-e3));
377  double h = sqrt((e1-e2)/(e1-e3));
378  translations[0] = translations[1] = cv::Point3d(0,0,0);
379  normals[0] = normals[1] = cv::Vec3d(0,0,0);
380  projections[0] = projections[1] = cv::Point2d(0,0);
381  unsigned int k = 0;
382  for(int i = 0; i < 8; i++) {
383 
384  double z0 = S3[i] * (e2 * radius) / sqrt(-e1*e3);
385  double Tx = S2[i] * e3/e2 * h;
386  double Ty = 0.;
387  double Tz = -S1[i] * e1/e2 * g;
388  double Nx = S2[i] * h;
389  double Ny = 0.;
390  double Nz = -S1[i] * g;
391 
392  cv::Mat_<double> t = (z0 * V * (cv::Mat_<double>(3,1) << Tx, Ty, Tz));
393  cv::Mat_<double> n = (V * (cv::Mat_<double>(3,1) << Nx, Ny, Nz));
394 
395  // identify the two possible solutions
396  if((t(2) > 0) && (n(2)<0)) {
397  if(k > 1) continue;
398  translations[k] = cv::Point3d(t(0), t(1), t(2));
399  normals[k] = cv::Vec3d(n(0), n(1), n(2));
400  // Projection
401  cv::Mat_<double> Pc = intrinsic * t;
402  projections[k].x = Pc(0)/Pc(2);
403  projections[k].y = Pc(1)/Pc(2);
404  k++;
405  }
406  }
407 }
408 
d
cv::Mat_< double > distCoeffs
Definition: camera.h:35
std::list< Marker > markers_
boost::shared_ptr< std::vector< cv::Point2f > > contourUndistort
boost::posix_time::ptime tstampLast_
double distance(const cv::Point2d p)
cv::Mat_< double > projectionMatrix
Definition: camera.h:36
void Perform(unsigned char *pImgEdgeStrength, int defEdgeLinkMode=MODE_CONTOUR, void *pImgEdgeDirection=NULL, int defImgEdgeDirectionType=ANGLE_8U)
Starts the edge linking with a certain mode.
Definition: contour.cpp:235
void edge_detection(const cv::Mat &m)
tuw::EllipseRefinement ellipseRefinementDual
DetectionState filterContourMean(Ellipse &ellipse)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void Init(unsigned int iImgWidth, unsigned int iImgHeight, bool bAllowToModifyTheSources=false, unsigned char iEdgeToProcess=0xFF, unsigned char iEdgeInProcess=0xFF-1, unsigned char iEdgeProcessed=0xFF-2, unsigned char iEdgeStrengthRemoved=0)
Inititalized the class and reserves the momory needed.
Definition: contour.cpp:178
boost::shared_ptr< std::vector< cv::Point2f > > contourDistort
std::vector< std::vector< cv::Point > > contours_
bool refine(const cv::Mat_< short > &im_dx, const cv::Mat_< short > &im_dy, const std::vector< cv::Point2f > &points, Ellipse &ellipse)
std::vector< Ellipse > ellipses_
int getContours(std::vector< std::vector< cv::Point > > &contours, unsigned min_length=0)
Returns the contour as vector of vector points.
Definition: contour.cpp:147
void Canny(const cv::Mat &image, cv::Mat &edges, cv::Mat &gradient, cv::Mat &direction, cv::Mat &sobel_dx, cv::Mat &sobel_dy, double threshold1, double threshold2, int apertureSize=3, bool L2gradient=false)
Definition: canny.cpp:363
static const int MODE_COMPLEX
Static const variable used to define the methode used to find the contour (linked edges) ...
Definition: contour.h:60
cv::Mat_< double > cameraMatrix
Definition: camera.h:34
DetectionState EllipseRedefinement(Ellipse &ellipse)
boost::posix_time::ptime tstamp_
TFSIMD_FORCE_INLINE const tfScalar & x() const
cv::Mat_< double > R[2]
two plausible translations solutions
boost::shared_ptr< std::vector< cv::Point > > polygon
void setEllipse(const double &_x, const double &_y, const double &_a, const double &_b, const double &_phi)
boost::shared_ptr< std::vector< double > > distances
void set(const ObliqueCone &c)
two plausible roations
static const int MODE_CONTOUR
Static const variable used to define the methode used to find the contour (linked edges) ...
Definition: contour.h:52
void pose(cv::Mat_< double > intrinsic, cv::Mat_< double > distCoeffs, double radius)
void fit_ellipses_opencv(const cv::Mat &m, const cv::Mat cameraMatrix, const cv::Mat distCoeffs, const cv::Mat projectionMatrix, const boost::posix_time::ptime &tstamp)
static const int MODE_SIMPLE
Static const variable used to define the methode used to find the contour (linked edges) ...
Definition: contour.h:48
EllipsesDetection(Parameters *parm)
DetectionState filterContour(Ellipse &ellipse)
cv::Point3d translations[2]
ellipse equation
DetectionState filterEllipse(Ellipse &ellipse)


tuw_ellipses
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:42:10