ellipses_detection.h
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 
22 #include <iostream>
23 #include <list>
24 
25 #ifndef TUW_ELLIPSES_H
26 #define TUW_ELLIPSES_H
27 
28 #include "opencv2/core/core.hpp"
29 #include "tuw_utils/contour.h"
30 #include "tuw_utils/camera.h"
31 #include "boost/shared_ptr.hpp"
32 #include <boost/date_time/posix_time/posix_time.hpp>
33 
34 namespace tuw {
35 
37 public:
39  VALID = 0,
40  NA = 1,
50  };
55  };
59  };
60  enum EdgeLinking {
66  };
67  struct Parameters {
68  Parameters();
69  bool debug;
90  };
91  class ObliqueCone {
92  public:
95  set(c);
96  };
97  cv::Mat_<double> C;
98  cv::Point3d translations[2];
99  cv::Vec3d normals[2];
100  cv::Point2d projections[2];
101  cv::Mat_<double> R[2];
102  void set(const ObliqueCone& c) {
103  C = c.C.clone();
104  for(unsigned int i = 0; i < 2; i++) {
105  translations[i] = c.translations[i], normals[i] = c.normals[i], projections[i] = c.projections[i];
106  R[i] = c.R[i].clone();
107  }
108  }
109  void pose(cv::Mat_<double> intrinsic, cv::Mat_<double> distCoeffs, double radius);
110  void set(cv::RotatedRect box, cv::Mat_<double> intrinsic);
111  double distance(const cv::Point2d p);
112  void rotation2Normal(int i);
113  void normal2Roation(int i);
114  };
115  class Ellipse {
116  public:
117  Ellipse(): id(-1), outerRing(-1), innerRing(-1), boxContour(), boxEllipse(), detection(VALID) {
118  };
119  void init() {
120  contourUndistort = boost::shared_ptr<std::vector<cv::Point2f> > (new std::vector<cv::Point2f>);
121  contourDistort = boost::shared_ptr<std::vector<cv::Point2f> > (new std::vector<cv::Point2f>);
122  polygon = boost::shared_ptr<std::vector<cv::Point> > (new std::vector<cv::Point>);
123  distances = boost::shared_ptr<std::vector<double> > (new std::vector<double>);
124  }
125  int id;
129  cv::RotatedRect boxEllipse;
130  cv::Rect boxContour;
131  cv::Point2d centerContour;
141  };
142  class Marker : public ObliqueCone {
143  public:
144  Marker() {};
145  Marker(const ObliqueCone &c)
146  : ObliqueCone(c), id(-1), tstamp(), A(cv::Mat_<double>::eye(4,4)) {
147  }
148  Marker(const Marker &c)
149  : ObliqueCone(c), id(c.id), tstamp(c.tstamp), A(c.A.clone()) {
150  }
151  int id;
152  boost::posix_time::ptime tstamp;
153  cv::Mat_<double> A;
154  void update(const boost::posix_time::ptime &t);
155  };
158 protected:
160  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);
161  void edge_detection(const cv::Mat &m);
162  void contour_detection();
163  void draw_ellipses(cv::Mat &m);
164  void next();
165  void createEllipseCanditates () ;
170  void estimatePoses();
171  void createRings();
172  void filterShapes();
173  std::vector< std::vector<cv::Point> > contours_;
174  std::vector<Ellipse> ellipses_;
175  cv::Mat imgGray_;
176  cv::Mat imgBlured_;
177  cv::Mat imgEdges_;
178  cv::Mat imgGradient_;
179  cv::Mat imgDirection_;
180  cv::Mat imgSobelDx_;
181  cv::Mat imgSobelDy_;
182  cv::Mat_<cv::Point2f> lookupUndistor_;
183  std::list<Marker> markers_;
184  unsigned long loop_count;
187  boost::posix_time::ptime tstamp_;
188  boost::posix_time::ptime tstampLast_;
189 };
190 };
191 #endif // TUW_ELLIPSES_H
std::list< Marker > markers_
boost::shared_ptr< std::vector< cv::Point2f > > contourUndistort
boost::posix_time::ptime tstampLast_
void draw_ellipses(cv::Mat &m)
bool update(const T &new_val, T &my_val)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
DetectionState filterContourMean(Ellipse &ellipse)
boost::shared_ptr< std::vector< cv::Point2f > > contourDistort
std::vector< std::vector< cv::Point > > contours_
std::vector< Ellipse > ellipses_
DetectionState EllipseRedefinement(Ellipse &ellipse)
boost::posix_time::ptime tstamp_
boost::shared_ptr< std::vector< cv::Point > > polygon
boost::shared_ptr< std::vector< double > > distances
boost::posix_time::ptime tstamp
Class to link detected images edges a typical source can be a cvCanny image.
Definition: contour.h:24
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)
cv::Mat_< cv::Point2f > lookupUndistor_
EllipsesDetection(Parameters *parm)
DetectionState filterContour(Ellipse &ellipse)
DetectionState filterEllipse(Ellipse &ellipse)


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