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 "Util.h"
36 #include "Camera.h"
37 #include "Line.h"
38 #include <sstream>
39 
40 namespace alvar {
41 
48 template<class PointType>
49 void inline DrawBB(IplImage *image, const std::vector<PointType>& points, CvScalar color, std::string label="")
50 {
51  if (points.size() < 2) {
52  return;
53  }
54  PointType minimum = PointType(image->width, image->height);
55  PointType maximum = PointType(0, 0);
56  for (int i = 0; i < (int)points.size(); ++i) {
57  PointType current = points.at(i);
58  if (current.x < minimum.x) minimum.x = current.x;
59  if (current.x > maximum.x) maximum.x = current.x;
60  if (current.y < minimum.y) minimum.y = current.y;
61  if (current.y > maximum.y) maximum.y = current.y;
62  }
63  cvLine(image, cvPoint((int)minimum.x,(int)minimum.y), cvPoint((int)maximum.x,(int)minimum.y), color);
64  cvLine(image, cvPoint((int)maximum.x,(int)minimum.y), cvPoint((int)maximum.x,(int)maximum.y), color);
65  cvLine(image, cvPoint((int)maximum.x,(int)maximum.y), cvPoint((int)minimum.x,(int)maximum.y), color);
66  cvLine(image, cvPoint((int)minimum.x,(int)maximum.y), cvPoint((int)minimum.x,(int)minimum.y), color);
67  if (!label.empty()) {
68  CvFont font;
69  cvInitFont(&font, 0, 0.5, 0.5, 0);
70  cvPutText(image, label.c_str(), cvPoint((int)minimum.x+1,(int)minimum.y+2), &font, CV_RGB(255,255,0));
71  }
72 }
73 
79 void ALVAR_EXPORT DrawPoints(IplImage *image, const std::vector<CvPoint>& points, CvScalar color);
80 
87 template<class PointType>
88 void inline DrawLines(IplImage *image, const std::vector<PointType>& points, CvScalar color, bool loop=true)
89 {
90  for(unsigned i = 1; i < points.size(); ++i)
91  cvLine(image, cvPoint((int)points[i-1].x,(int)points[i-1].y), cvPoint((int)points[i].x,(int)points[i].y), color);
92  if (loop) {
93  cvLine(image, cvPoint((int)points[points.size()-1].x,(int)points[points.size()-1].y), cvPoint((int)points[0].x,(int)points[0].y), color);
94  }
95 }
96 
102 void ALVAR_EXPORT DrawLine(IplImage* image, const Line line, CvScalar color = CV_RGB(0,255,0));
103 
109 void ALVAR_EXPORT DrawPoints(IplImage* image, const CvSeq* contour, CvScalar color = CV_RGB(255,0,0));
110 
111 
118 void ALVAR_EXPORT DrawCircles(IplImage* image, const CvSeq* contour, int radius, CvScalar color = CV_RGB(255,0,0));
119 
125 void ALVAR_EXPORT DrawLines(IplImage* image, const CvSeq* contour, CvScalar color = CV_RGB(255,0,0));
126 
133 template<class PointType>
134 void inline DrawPoints(IplImage *image, const std::vector<PointType>& points, CvScalar color, int radius=1)
135 {
136  for(unsigned i = 0; i < points.size(); ++i)
137  cvCircle(image, cvPoint((int)points[i].x,(int)points[i].y), radius, color);
138 }
139 
147 void ALVAR_EXPORT DrawCVEllipse(IplImage* image, CvBox2D& ellipse, CvScalar color, bool fill=false, double par=0);
148 
157 void ALVAR_EXPORT BuildHideTexture(IplImage *image, IplImage *hide_texture,
158  Camera *cam, double gl_modelview[16],
159  PointDouble topleft, PointDouble botright);
160 
169 void ALVAR_EXPORT DrawTexture(IplImage *image, IplImage *texture,
170  Camera *cam, double gl_modelview[16],
171  PointDouble topleft, PointDouble botright);
172 
173 } // namespace alvar
174 
175 #endif
Main ALVAR namespace.
Definition: Alvar.h:174
void ALVAR_EXPORT DrawCircles(IplImage *image, const CvSeq *contour, int radius, CvScalar color=CV_RGB(255, 0, 0))
Draws circles to the contour points that are obtained by Labeling class.
Definition: Draw.cpp:60
This file implements a parametrized line.
This file implements a camera used for projecting points and computing homographies.
void ALVAR_EXPORT DrawTexture(IplImage *image, IplImage *texture, Camera *cam, double gl_modelview[16], PointDouble topleft, PointDouble botright)
Draws the texture generated by BuildHideTexture to given video frame. For better performance, use OpenGL instead. See SampleMarkerHide.cpp for example implementation.
Definition: Draw.cpp:213
unsigned char * image
Definition: GlutViewer.cpp:155
void ALVAR_EXPORT DrawPoints(IplImage *image, const std::vector< CvPoint > &points, CvScalar color)
Draws a set of points.
CvFont font
Definition: SampleTrack.cpp:12
TFSIMD_FORCE_INLINE const tfScalar & y() const
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Definition: Camera.h:82
void DrawBB(IplImage *image, const std::vector< PointType > &points, CvScalar color, std::string label="")
Draws the bounding box of a connected component (Blob).
Definition: Draw.h:49
Struct representing a line. The line is parametrized by its center and direction vector.
Definition: Line.h:41
void ALVAR_EXPORT DrawLine(IplImage *image, const Line line, CvScalar color=CV_RGB(0, 255, 0))
Draws a line.
Definition: Draw.cpp:38
TFSIMD_FORCE_INLINE const tfScalar & x() const
This file implements generic utility functions and a serialization interface.
#define ALVAR_EXPORT
Definition: Alvar.h:168
ALVAR_EXPORT Point< CvPoint2D64f > PointDouble
The default double point type.
Definition: Util.h:108
void ALVAR_EXPORT BuildHideTexture(IplImage *image, IplImage *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...
Definition: Draw.cpp:95
Camera * cam
void DrawLines(IplImage *image, const std::vector< PointType > &points, CvScalar color, bool loop=true)
Draws lines between consecutive points stored in vector (polyline).
Definition: Draw.h:88
void ALVAR_EXPORT DrawCVEllipse(IplImage *image, CvBox2D &ellipse, CvScalar color, bool fill=false, double par=0)
Draws OpenCV ellipse.
Definition: Draw.cpp:82
This file defines library export definitions, version numbers and build information.


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04