ellipses.h
Go to the documentation of this file.
00001 /***************************************************************************
00002  *   Copyright (C) 2014 by Markus Bader                                    *
00003  *   markus.bader@tuwien.ac.at                                             *
00004  *                                                                         *
00005  *   This program is free software; you can redistribute it and/or modify  *
00006  *   it under the terms of the GNU General Public License as published by  *
00007  *   the Free Software Foundation; either version 2 of the License, or     *
00008  *   (at your option) any later version.                                   *
00009  *                                                                         *
00010  *   This program is distributed in the hope that it will be useful,       *
00011  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00012  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
00013  *   GNU General Public License for more details.                          *
00014  *                                                                         *
00015  *   You should have received a copy of the GNU General Public License     *
00016  *   along with this program; if not, write to the                         *
00017  *   Free Software Foundation, Inc.,                                       *
00018  *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
00019  ***************************************************************************/
00020 
00021 
00022 #include <iostream>
00023 #include <list>
00024 
00025 #ifndef TUW_ELLIPSES_H
00026 #define TUW_ELLIPSES_H
00027 
00028 #include "opencv/cxcore.h"
00029 #include "tuw_utils/contour.h"
00030 #include "tuw_utils/camera.h"
00031 #include "boost/shared_ptr.hpp"
00032 #include <boost/date_time/posix_time/posix_time.hpp>
00033 
00034 namespace tuw {
00035 
00036 class EllipsesDetection {
00037 public:
00038     enum DetectionState {
00039         VALID = 0,
00040         NA = 1,
00041         INVALID_CONTOUR_POINTS,
00042         INVALID_CONTOUR_CONVEX,
00043         INVALID_ROTATED_RECT_RATIO,
00044         INVALID_CONTOUR_MEAN,
00045         INVALID_MIN_RAIDUS,
00046         INVALID_MAX_RAIDUS,
00047         INVALID_NO_RING,
00048         INVALID_IS_INNER_RING,
00049         INVALID_ELLIPSE
00050     };
00051     enum PoseEstimation {
00052         POSE_ESTIMATION_OFF = 0,
00053         POSE_ESTIMATION_SOLVEPNP = 1,
00054         POSE_ESTIMATION_FROM_ELLIPSE = 2,
00055     };
00056     enum EdgeDetection {
00057         EDGE_DETECTION_THRESHOLD = 0,
00058         EDGE_DETECTION_CANNY = 1
00059     };
00060     enum EdgeLinking {
00061         EDGE_LINKING_OPENCV_APPROX_NONE = 0,
00062         EDGE_LINKING_OPENCV_APPROX_SIMPLE = 1,
00063         EDGE_LINKING_TUW_SIMPLE = 2,
00064         EDGE_LINKING_TUW_COMPLEX = 3,
00065         EDGE_LINKING_TUW_CONTOUR = 4
00066     };
00067     struct Parameters {
00068         Parameters();
00069         bool debug;
00070         bool distorted_input;
00071         EdgeDetection edge_detection;
00072         int threshold_edge_detection1;
00073         int threshold_edge_detection2;
00074         int kernel_size_edge_detection;
00075         EdgeLinking edge_linking;
00076         int threshold_contour_min_points;
00077         int threshold_polygon;
00078         bool filter_convex;
00079         double threshold_rotated_rect_ratio;
00080         bool ellipse_redefinement;
00081         bool filter_contour_mean;
00082         double threshold_contour_mean;
00083         double threshold_min_radius;
00084         double threshold_max_radius;
00085         bool filter_rings;
00086         double threshold_ring_center;
00087         double threshold_ring_ratio;
00088         PoseEstimation pose_estimation;
00089         double circle_diameter;
00090     };
00091     class ObliqueCone {
00092     public:
00093         ObliqueCone() {};
00094         ObliqueCone(const ObliqueCone& c) {
00095             set(c);
00096         };
00097         cv::Mat_<double> C;  
00098         cv::Point3d translations[2]; 
00099         cv::Vec3d normals[2];
00100         cv::Point2d projections[2]; 
00101         cv::Mat_<double> R[2]; 
00102         void set(const ObliqueCone& c) {
00103             C = c.C.clone();
00104             for(unsigned int i = 0; i < 2; i++) {
00105                 translations[i] = c.translations[i], normals[i] = c.normals[i], projections[i] = c.projections[i];
00106                 R[i] = c.R[i].clone();
00107             }
00108         }
00109         void pose(cv::Mat_<double> intrinsic, cv::Mat_<double> distCoeffs, double radius);
00110         void set(cv::RotatedRect box, cv::Mat_<double> intrinsic);
00111         double distance(const cv::Point2d p);
00112         void rotation2Normal(int i);
00113         void normal2Roation(int i);
00114     };
00115     class Ellipse {
00116     public:
00117         Ellipse(): id(-1), outerRing(-1), innerRing(-1), boxContour(), boxEllipse(), detection(VALID) {
00118         };
00119         void init() {
00120             contourUndistort = boost::shared_ptr<std::vector<cv::Point2f> > (new std::vector<cv::Point2f>);
00121             contourDistort = boost::shared_ptr<std::vector<cv::Point2f> > (new std::vector<cv::Point2f>);
00122             polygon = boost::shared_ptr<std::vector<cv::Point> > (new std::vector<cv::Point>);
00123             distances = boost::shared_ptr<std::vector<double> > (new std::vector<double>);
00124         }
00125         int id;
00126         int outerRing;
00127         int innerRing;
00128         DetectionState detection;
00129         cv::RotatedRect boxEllipse;
00130         cv::Rect boxContour;
00131         cv::Point2d centerContour;
00132         double radiusContour;
00133         double boxEllipseRatio;
00134         double radiusEllipseMax;
00135         double radiusEllipseMin;
00136         ObliqueCone cone;
00137         boost::shared_ptr<std::vector<cv::Point2f> > contourUndistort;
00138         boost::shared_ptr<std::vector<cv::Point2f> > contourDistort;
00139         boost::shared_ptr<std::vector<cv::Point> > polygon;
00140         boost::shared_ptr<std::vector<double> > distances;
00141     };
00142     class Marker : public ObliqueCone {
00143     public:
00144         Marker() {};
00145         Marker(const ObliqueCone &c)
00146             : ObliqueCone(c), id(-1), tstamp(), A(cv::Mat_<double>::eye(4,4)) {
00147         }
00148         Marker(const Marker &c)
00149             : ObliqueCone(c), id(c.id), tstamp(c.tstamp), A(c.A.clone()) {
00150         }
00151         int id;    
00152         boost::posix_time::ptime tstamp;
00153         cv::Mat_<double> A;
00154         void update(const boost::posix_time::ptime &t);
00155     };
00156     EllipsesDetection (Parameters *parm);
00157     ~EllipsesDetection();
00158 protected:
00159     Parameters *param_;
00160     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);
00161     void edge_detection(const cv::Mat &m);
00162     void contour_detection();
00163     void draw_ellipses(cv::Mat &m);
00164     void next();
00165     void createEllipseCanditates () ;
00166     DetectionState filterContour (Ellipse &ellipse);
00167     DetectionState filterEllipse (Ellipse &ellipse);
00168     DetectionState filterContourMean(Ellipse &ellipse);    
00169     DetectionState EllipseRedefinement(Ellipse &ellipse);
00170     void estimatePoses();
00171     void createRings();
00172     void filterShapes();
00173     std::vector< std::vector<cv::Point> > contours_;
00174     std::vector<Ellipse> ellipses_;
00175     cv::Mat imgGray_;
00176     cv::Mat imgBlured_;
00177     cv::Mat imgEdges_;
00178     cv::Mat imgGradient_;
00179     cv::Mat imgDirection_;
00180     cv::Mat imgSobelDx_;
00181     cv::Mat imgSobelDy_;
00182     cv::Mat_<cv::Point2f>  lookupUndistor_;
00183     std::list<Marker> markers_;
00184     unsigned long loop_count;
00185     tuw::Contour contour_detector_;
00186     tuw::Camera camera_;
00187     boost::posix_time::ptime tstamp_;
00188     boost::posix_time::ptime tstampLast_;
00189 };
00190 };
00191 #endif // TUW_ELLIPSES_H


tuw_ellipses
Author(s):
autogenerated on Sun May 29 2016 02:50:24