ellipses_draw.cpp
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 #include "opencv2/imgproc/imgproc.hpp"
00022 #include <opencv/cv.h>
00023 #include <tuw_ellipses/ellipses.h>
00024 #include <tuw_ellipses/ellipses_defaults.h>
00025 #include <boost/foreach.hpp>
00026 
00027 using namespace tuw;
00028 
00029 void EllipsesDetection::draw_ellipses(cv::Mat &img) {
00030     std::vector<cv::Point2f> vtx(4);
00031     std::vector<cv::Point2f> vtxDis;
00032     cv::Scalar colourContour(255,0,255);
00033     cv::Scalar colourEllipse(0,0,255);
00034     char text[0xFF];
00035     for(unsigned int i = 0; i < ellipses_.size(); i++) {
00036         Ellipse &ellipse = ellipses_[i];
00037         if(ellipse.detection != VALID) continue;
00038         //cv::drawContours(img, contours_, (int) i, colourContour, 1, 8);
00039         cv::RotatedRect box1, box2;
00040         camera_.distort(ellipse.boxEllipse, box1);
00041         cv::ellipse(img, box1, colourEllipse, 1, CV_AA);
00042         camera_.distort(ellipses_[ellipse.innerRing].boxEllipse, box2);
00043         if(ellipse.innerRing >= 0) cv::ellipse(img, box2, colourEllipse, 1, CV_AA);
00044         box1.points(&vtx[0]);
00045         for( int j = 0; j < 4; j++ ) {
00046             cv::line(img, vtx[j], vtx[(j+2)%4], cv::Scalar(0,255,0), 1, CV_AA);
00047             sprintf(text, "%i", j);
00048             //cv::putText(img, text, vtx[j], cv::FONT_HERSHEY_PLAIN, 1, cv::Scalar::all(0), 1, CV_AA);
00049         }
00050         camera_.distort(*ellipse.contourUndistort, vtxDis);
00051         BOOST_FOREACH(const cv::Point2f &p, vtxDis ) {
00052             img.at<cv::Vec3b>(p) = cv::Vec3b(0,255,255);
00053         }
00054 
00055         // draw normals into the image
00056         if(ellipse.cone.projections[0] != cv::Point2d(0,0)) {
00057             for(unsigned int k = 0; k < 2; k++) {
00058                 cv::Mat pi, pw(ellipse.cone.translations[k]);
00059                 cv::Mat pin , pn = pw + cv::Mat(ellipse.cone.normals[k])*param_->circle_diameter;
00060                 cv::projectPoints(pw.t(), cv::Mat_<double>::zeros(1,3), cv::Mat_<double>::zeros(1,3), camera_.cameraMatrix, camera_.distCoeffs, pi);
00061                 cv::projectPoints(pn.t(), cv::Mat_<double>::zeros(1,3), cv::Mat_<double>::zeros(1,3), camera_.cameraMatrix, camera_.distCoeffs, pin);
00062                 for(int j = 0; j < pi.rows; j++) {
00063                     cv::Point p0(pi.at<double>(j,0),pi.at<double>(j,1));
00064                     cv::circle(img, p0,2, cv::Scalar(125*j,125*j,255));
00065                     cv::Point p1(pin.at<double>(j,0),pin.at<double>(j,1));
00066                     cv::line(img, p0, p1, cv::Scalar(125*j,125*j,255), 1, CV_AA);
00067                 }
00068             }
00069         }
00070 
00072         if(param_->debug) {
00073             std::cout << "% === " << std::setw(4) <<  loop_count;
00074             std::cout << "  ===== ellipse " << std::setw(4) << i << " ===" << std::endl;
00075             std::cout << "ellipse.center     = " <<  ellipse.boxEllipse.center << "; " << std::endl;
00076             std::cout << "ellipse.size       = " <<  (cv::Point2f) ellipse.boxEllipse.size << "; " << std::endl;
00077             std::cout << "ellipse.angle      = " <<   M_PI/180.0 *ellipse.boxEllipse.angle << "; " << std::endl;
00078             std::cout << "ellipse.C          = " << ellipse.cone.C << "; " << "  % Ellipse Image" << std::endl;
00079             std::cout << "ellipse.radius     = " << param_->circle_diameter/2. << "; " << std::endl;
00080             std::cout << "ellipse.nr_of_edges=" <<  ellipse.contourUndistort->size() << "; " << std::endl;
00081             std::cout << "ellipse.contour    = " << cv::Mat(*ellipse.contourUndistort) << "; " << std::endl;
00082             std::cout << "camera.intrinsic   = " << camera_.cameraMatrix << "; " << std::endl;
00083             std::cout << "camera.distortions = " << camera_.distCoeffs << "; " << std::endl;
00084             std::cout << "camera.projectionMatrix = " << camera_.projectionMatrix << "; " << std::endl;
00085         }
00086     }
00087     if(param_->debug) {
00088         contour_detector_.Draw(img.data);
00089     }
00090 }


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