My Project
Draw.h
Go to the documentation of this file.
1 /*
2  * This file is part of ALVAR, A Library for Virtual and Augmented Reality.
3  *
4  * Copyright 2007-2012 VTT Technical Research Centre of Finland
5  *
6  * Contact: VTT Augmented Reality Team <alvar.info@vtt.fi>
7  * <http://www.vtt.fi/multimedia/alvar.html>
8  *
9  * ALVAR is free software; you can redistribute it and/or modify it under the
10  * terms of the GNU Lesser General Public License as published by the Free
11  * Software Foundation; either version 2.1 of the License, or (at your option)
12  * any later version.
13  *
14  * This library is distributed in the hope that it will be useful, but WITHOUT
15  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
16  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
17  * for more details.
18  *
19  * You should have received a copy of the GNU Lesser General Public License
20  * along with ALVAR; if not, see
21  * <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>.
22  */
23 
24 #ifndef DRAW_H
25 #define DRAW_H
26 
34 #include "Alvar.h"
35 #include "Camera.h"
36 #include "Line.h"
37 #include "Util.h"
38 
39 #include <opencv2/imgproc.hpp>
40 #include <sstream>
41 
42 namespace alvar {
43 
50 template <class PointType>
51 void inline DrawBB(cv::Mat & image,
52  const std::vector<PointType> &points,
53  const cv::Scalar & color,
54  const std::string & label = "")
55 {
56  if (points.size() < 2) {
57  return;
58  }
59  PointType minimum = PointType(image.cols, image.rows);
60  PointType maximum = PointType(0, 0);
61  for (int i = 0; i < (int)points.size(); ++i) {
62  PointType current = points.at(i);
63  if (current.x < minimum.x)
64  minimum.x = current.x;
65  if (current.x > maximum.x)
66  maximum.x = current.x;
67  if (current.y < minimum.y)
68  minimum.y = current.y;
69  if (current.y > maximum.y)
70  maximum.y = current.y;
71  }
72  cv::line(image,
73  cv::Point((int)minimum.x, (int)minimum.y),
74  cv::Point((int)maximum.x, (int)minimum.y),
75  color);
76  cv::line(image,
77  cv::Point((int)maximum.x, (int)minimum.y),
78  cv::Point((int)maximum.x, (int)maximum.y),
79  color);
80  cv::line(image,
81  cv::Point((int)maximum.x, (int)maximum.y),
82  cv::Point((int)minimum.x, (int)maximum.y),
83  color);
84  cv::line(image,
85  cv::Point((int)minimum.x, (int)maximum.y),
86  cv::Point((int)minimum.x, (int)minimum.y),
87  color);
88  if (!label.empty()) {
89  cv::putText(
90  image, label, cv::Point((int)minimum.x + 1, (int)minimum.y + 2), 0, 0.5, CV_RGB(255, 255, 0));
91  }
92 }
93 
100 template <class PointType>
101 void inline DrawLines(cv::Mat & image,
102  const std::vector<PointType> &points,
103  const cv::Scalar & color,
104  bool loop = true)
105 {
106  for (unsigned i = 1; i < points.size(); ++i)
107  cv::line(image,
108  cv::Point((int)points[i - 1].x, (int)points[i - 1].y),
109  cv::Point((int)points[i].x, (int)points[i].y),
110  color);
111  if (loop) {
112  cv::line(image,
113  cv::Point((int)points[points.size() - 1].x, (int)points[points.size() - 1].y),
114  cv::Point((int)points[0].x, (int)points[0].y),
115  color);
116  }
117 }
118 
124 void ALVAR_EXPORT DrawLine(cv::Mat & image,
125  const Line line,
126  const cv::Scalar &color = CV_RGB(0, 255, 0));
127 
133 void ALVAR_EXPORT DrawPoints(cv::Mat & image,
134  const std::vector<cv::Point> &contour,
135  const cv::Scalar & color = CV_RGB(255, 0, 0));
136 
143 void ALVAR_EXPORT DrawCircles(cv::Mat & image,
144  const std::vector<cv::Point> &contour,
145  int radius,
146  const cv::Scalar & color = CV_RGB(255, 0, 0));
152 void ALVAR_EXPORT DrawLines(cv::Mat & image,
153  const std::vector<cv::Point> &contour,
154  const cv::Scalar & color = CV_RGB(255, 0, 0));
161 template <class PointType>
162 void inline DrawPoints(cv::Mat & image,
163  const std::vector<PointType> &points,
164  const cv::Scalar & color,
165  int radius = 1)
166 {
167  for (unsigned i = 0; i < points.size(); ++i)
168  cv::circle(image, cv::Point((int)points[i].x, (int)points[i].y), radius, color);
169 }
170 
178 void ALVAR_EXPORT DrawCVEllipse(cv::Mat & image,
179  const cv::RotatedRect &ellipse,
180  const cv::Scalar & color,
181  bool fill = false,
182  double par = 0);
183 
192 void ALVAR_EXPORT BuildHideTexture(cv::Mat & image,
193  cv::Mat & hide_texture,
194  Camera * cam,
195  double gl_modelview[16],
196  PointDouble topleft,
197  PointDouble botright);
198 
207 void ALVAR_EXPORT DrawTexture(cv::Mat & image,
208  cv::Mat & texture,
209  Camera * cam,
210  double gl_modelview[16],
211  PointDouble topleft,
212  PointDouble botright);
213 
214 } // namespace alvar
215 
216 #endif
This file defines library export definitions, version numbers and build information.
This file implements a camera used for projecting points and computing homographies.
This file implements a parametrized line.
This file implements generic utility functions and a serialization interface.
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Definition: Camera.h:82
Main ALVAR namespace.
Definition: Alvar.h:174
void ALVAR_EXPORT BuildHideTexture(cv::Mat &image, cv::Mat &hide_texture, Camera *cam, double gl_modelview[16], PointDouble topleft, PointDouble botright)
This function is used to construct a texture image which is needed to hide a marker from the original...
void ALVAR_EXPORT DrawLine(cv::Mat &image, const Line line, const cv::Scalar &color=CV_RGB(0, 255, 0))
Draws a line.
void ALVAR_EXPORT DrawCVEllipse(cv::Mat &image, const cv::RotatedRect &ellipse, const cv::Scalar &color, bool fill=false, double par=0)
Draws OpenCV ellipse.
void DrawBB(cv::Mat &image, const std::vector< PointType > &points, const cv::Scalar &color, const std::string &label="")
Draws the bounding box of a connected component (Blob).
Definition: Draw.h:51
ALVAR_EXPORT Point< cv::Point2d > PointDouble
The default double point type.
Definition: Util.h:110
void ALVAR_EXPORT DrawCircles(cv::Mat &image, const std::vector< cv::Point > &contour, int radius, const cv::Scalar &color=CV_RGB(255, 0, 0))
Draws circles to the contour points that are obtained by Labeling class.
void ALVAR_EXPORT DrawTexture(cv::Mat &image, cv::Mat &texture, Camera *cam, double gl_modelview[16], PointDouble topleft, PointDouble botright)
Draws the texture generated by BuildHideTexture to given video frame. For better performance,...
void ALVAR_EXPORT DrawPoints(cv::Mat &image, const std::vector< cv::Point > &contour, const cv::Scalar &color=CV_RGB(255, 0, 0))
Draws points of the contour that is obtained by Labeling class.
void DrawLines(cv::Mat &image, const std::vector< PointType > &points, const cv::Scalar &color, bool loop=true)
Draws lines between consecutive points stored in vector (polyline).
Definition: Draw.h:101
Struct representing a line. The line is parametrized by its center and direction vector.
Definition: Line.h:44