aruco_test_markermap_gl.cpp
Go to the documentation of this file.
1 /*****************************
2 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without modification, are
5 permitted provided that the following conditions are met:
6 
7  1. Redistributions of source code must retain the above copyright notice, this list of
8  conditions and the following disclaimer.
9 
10  2. Redistributions in binary form must reproduce the above copyright notice, this list
11  of conditions and the following disclaimer in the documentation and/or other materials
12  provided with the distribution.
13 
14 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
15 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
16 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
17 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
19 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
20 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
21 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
22 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 
24 The views and conclusions contained in the software and documentation are those of the
25 authors and should not be interpreted as representing official policies, either expressed
26 or implied, of Rafael Muñoz Salinas.
27 ********************************/
28 #include <iostream>
29 #include <fstream>
30 #include <sstream>
31 #ifdef __APPLE__
32  #include <GLUT/glut.h>
33 #elif _MSC_VER
34  //http://social.msdn.microsoft.com/Forums/eu/vcgeneral/thread/7d6e6fa5-afc2-4370-9a1f-991a76ccb5b7
35  #include <windows.h>
36  #include <GL/gl.h>
37  #include <GL/glut.h>
38 #else
39  #include <GL/gl.h>
40  #include <GL/glut.h>
41 #endif
42 
43 #include <opencv2/highgui/highgui.hpp>
44 #include <opencv2/imgproc/imgproc.hpp>
45 #include <opencv2/calib3d/calib3d.hpp>
46 #include "aruco.h"
47 #include "markermap.h"
48 
49 
50 using namespace cv;
51 using namespace aruco;
52 void __glGetModelViewMatrix(double modelview_matrix[16],const cv::Mat &Rvec,const cv::Mat &Tvec) throw(cv::Exception) ;
53 
54 bool The3DInfoAvailable=false;
55 float TheMarkerSize=-1;
56 VideoCapture TheVideoCapturer;
57 vector<Marker> TheMarkers;
58 //board
65 bool TheCaptureFlag=true;
66 void vDrawScene();
67 void vIdle();
68 void vResize( GLsizei iWidth, GLsizei iHeight );
69 void vMouse(int b,int s,int x,int y);
70 
71 
72 /************************************
73  *
74  *
75  *
76  *
77  ************************************/
78 
79 int main(int argc,char **argv)
80 {
81  try
82  {
83  if (argc!=5) {
84  cerr<<"Invalid number of arguments"<<endl;
85  cerr<<"Usage: (in.avi|live) markermap_config.yml intrinsics.yml size "<<endl;
86  cerr<<"WARNING: this test creates a synthetic mask consisting of a single rectangle. "<<endl;
87  cerr<<"WARNING: The only purpose is to show how to create an AR application with mask in OpenGL "<<endl;
88  return false;
89  }
90  TheCameraParams.readFromXMLFile(argv[3]);
91  //read board configuration
92  TheMMConfig.readFromFile(argv[2]);
93  TheMarkerSize=atof(argv[4]);
94  if (TheMMConfig.isExpressedInPixels())
95  TheMMConfig=TheMMConfig.convertToMeters(TheMarkerSize);
96 
97  MMPoseTracker.setParams(TheCameraParams,TheMMConfig);
98  //Open video input source
99  if (string(argv[1])=="live") //read from camera
100  TheVideoCapturer.open(0);
101  else TheVideoCapturer.open(argv[1]);
102 
103  if (!TheVideoCapturer.isOpened()) throw std::runtime_error("could not open video");
104 
105  //read first image
106  TheVideoCapturer>>TheInputImage;
107  //read camera paramters if passed
108  TheCameraParams.readFromXMLFile(argv[3]);
109  TheCameraParams.resize( TheInputImage.size());
110 
111  TheMarkerDetector.setThresholdParams(25,7);
112 
113  MarkerDetector::Params params;
114  //play with this paramteres if the detection does not work correctly
115  params._borderDistThres=.01;//acept markers near the borders
116  params._thresParam1=5;
117  params._thresParam1_range=10;//search in wide range of values for param1
118  params._cornerMethod=MarkerDetector::SUBPIX;//use subpixel corner refinement
119  params._subpix_wsize= (15./2000.)*float(TheInputImage.cols) ;//search corner subpix in a 5x5 widow area
120  TheMarkerDetector.setParams(params);//set the params above
121  TheMarkerDetector.setDictionary(TheMMConfig.getDictionary());
122 
123 
124  glutInit(&argc, argv);
125  glutInitWindowPosition( 0, 0);
126  glutInitWindowSize(TheInputImage.size().width,TheInputImage.size().height);
127  glutInitDisplayMode( GLUT_RGB | GLUT_DEPTH | GLUT_DOUBLE );
128  glutCreateWindow( "AruCo" );
129  glutDisplayFunc( vDrawScene );
130  glutIdleFunc( vIdle );
131  glutReshapeFunc( vResize );
132  glutMouseFunc(vMouse);
133  glClearColor( 0.0, 0.0, 0.0, 1.0 );
134  glClearDepth( 1.0 );
135  TheGlWindowSize=TheInputImage.size();
136  vResize(TheGlWindowSize.width,TheGlWindowSize.height);
137  glutMainLoop();
138 
139  } catch (std::exception &ex)
140 
141  {
142  cout<<"Exception :"<<ex.what()<<endl;
143  }
144 
145 }
146 /************************************
147  *
148  *
149  *
150  *
151  ************************************/
152 
153 void vMouse(int b,int s,int x,int y)
154 {
155  if (b==GLUT_LEFT_BUTTON && s==GLUT_DOWN) {
156  TheCaptureFlag=!TheCaptureFlag;
157  }
158 
159 }
160 
161 /************************************
162  *
163  *
164  *
165  *
166  ************************************/
167 void axis(float size)
168 {
169  glColor3f (1,0,0 );
170  glBegin(GL_LINES);
171  glVertex3f(0.0f, 0.0f, 0.0f); // origin of the line
172  glVertex3f(size,0.0f, 0.0f); // ending point of the line
173  glEnd( );
174 
175  glColor3f ( 0,1,0 );
176  glBegin(GL_LINES);
177  glVertex3f(0.0f, 0.0f, 0.0f); // origin of the line
178  glVertex3f( 0.0f,size, 0.0f); // ending point of the line
179  glEnd( );
180 
181 
182  glColor3f (0,0,1 );
183  glBegin(GL_LINES);
184  glVertex3f(0.0f, 0.0f, 0.0f); // origin of the line
185  glVertex3f(0.0f, 0.0f, size); // ending point of the line
186  glEnd( );
187 
188 
189 }
190 
191 
192 /************************************
193  *
194  *
195  *
196  *
197  ************************************/
198 void vIdle()
199 {
200  if (TheCaptureFlag) {
201  //capture image
202  TheVideoCapturer.grab();
203  TheVideoCapturer.retrieve( TheInputImage);
204  TheUndInputImage.create(TheInputImage.size(),CV_8UC3);
205  //by deafult, opencv works in BGR, so we must convert to RGB because OpenGL in windows preffer
206  cv::cvtColor(TheInputImage,TheInputImage,CV_BGR2RGB);
207  //remove distorion in image
208  cv::undistort(TheInputImage,TheUndInputImage, TheCameraParams.CameraMatrix,TheCameraParams.Distorsion);
209  //detect markers
210  TheMarkers=TheMarkerDetector.detect(TheUndInputImage);
211  MMPoseTracker.estimatePose(TheMarkers);
212  //chekc the speed by calculating the mean speed of all iterations
213  //resize the image to the size of the GL window
214  cv::resize(TheUndInputImage,TheResizedImage,TheGlWindowSize);
215  }
216  glutPostRedisplay();
217 }
218 
219 /************************************
220  *
221  *
222  *
223  *
224  ************************************/
226 {
227 
228  if (TheResizedImage.rows==0) //prevent from going on until the image is initialized
229  return;
231  glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
233  glMatrixMode(GL_MODELVIEW);
234  glLoadIdentity();
235  glMatrixMode(GL_PROJECTION);
236  glLoadIdentity();
237  glOrtho(0, TheGlWindowSize.width, 0, TheGlWindowSize.height, -1.0, 1.0);
238  glViewport(0, 0, TheGlWindowSize.width , TheGlWindowSize.height);
239  glDisable(GL_TEXTURE_2D);
240  glPixelZoom( 1, -1);
241  glRasterPos3f( 0, TheGlWindowSize.height - 0.5, -1.0 );
242  glDrawPixels ( TheGlWindowSize.width , TheGlWindowSize.height , GL_RGB , GL_UNSIGNED_BYTE , TheResizedImage.ptr(0) );
244  //like the real camera (without distorsion)
245  glMatrixMode(GL_PROJECTION);
246  double proj_matrix[16];
247  TheCameraParams.glGetProjectionMatrix(TheInputImage.size(),TheGlWindowSize,proj_matrix,0.05,10);
248  glLoadIdentity();
249  glLoadMatrixd(proj_matrix);
250  glLineWidth(2);
251  //now, for each marker,
252  double modelview_matrix[16];
253 
254  /* for (unsigned int m=0;m<TheMarkers.size();m++)
255  {
256  TheMarkers[m].glGetModelViewMatrix(modelview_matrix);
257  glMatrixMode(GL_MODELVIEW);
258  glLoadIdentity();
259  glLoadMatrixd(modelview_matrix);
260  // axis(TheMarkerSize);
261  glColor3f(1,0.4,0.4);
262  glTranslatef(0, TheMarkerSize/2,0);
263  glPushMatrix();
264  glutWireCube( TheMarkerSize );
265 
266  glPopMatrix();
267  }*/
268  //If the board is detected with enough probability
269  if (!MMPoseTracker.getRTMatrix().empty()) {
270  __glGetModelViewMatrix(modelview_matrix,MMPoseTracker.getRvec(),MMPoseTracker.getTvec());
271  glMatrixMode(GL_MODELVIEW);
272  glLoadIdentity();
273  glLoadMatrixd(modelview_matrix);
274  glColor3f(0,1,0);
275  axis(TheMarkerSize);
276  glPushMatrix();
277  glutWireCube( TheMarkerSize );
278  glPopMatrix();
279  }
280 
281  glutSwapBuffers();
282 
283 }
284 
285 
286 
287 
288 /************************************
289  *
290  *
291  *
292  *
293  ************************************/
294 void vResize( GLsizei iWidth, GLsizei iHeight )
295 {
296 
297  TheGlWindowSize=Size(iWidth,iHeight);
298  //not all sizes are allowed. OpenCv images have padding at the end of each line in these that are not aligned to 4 bytes
299  if (iWidth*3%4!=0) {
300  iWidth+=iWidth*3%4;//resize to avoid padding
301  vResize(iWidth,TheGlWindowSize.height);
302  }
303  else {
304  //resize the image to the size of the GL window
305  if (TheUndInputImage.rows!=0)
306  cv::resize(TheUndInputImage,TheResizedImage,TheGlWindowSize);
307  }
308 
309 }
310 
311 void __glGetModelViewMatrix(double modelview_matrix[16],const cv::Mat &Rvec,const cv::Mat &Tvec) throw(cv::Exception) {
312  assert(Tvec.type()==CV_32F);
313  // check if paremeters are valid
314  Mat Rot(3, 3, CV_32FC1);
315  Rodrigues(Rvec, Rot);
316 
317  double para[3][4];
318  for (int i = 0; i < 3; i++)
319  for (int j = 0; j < 3; j++)
320  para[i][j] = Rot.at< float >(i, j);
321  // now, add the translation
322  para[0][3] = Tvec.ptr< float >(0)[0];
323  para[1][3] = Tvec.ptr< float >(0)[1];
324  para[2][3] = Tvec.ptr< float >(0)[2];
325  double scale = 1;
326 
327  modelview_matrix[0 + 0 * 4] = para[0][0];
328  // R1C2
329  modelview_matrix[0 + 1 * 4] = para[0][1];
330  modelview_matrix[0 + 2 * 4] = para[0][2];
331  modelview_matrix[0 + 3 * 4] = para[0][3];
332  // R2
333  modelview_matrix[1 + 0 * 4] = para[1][0];
334  modelview_matrix[1 + 1 * 4] = para[1][1];
335  modelview_matrix[1 + 2 * 4] = para[1][2];
336  modelview_matrix[1 + 3 * 4] = para[1][3];
337  // R3
338  modelview_matrix[2 + 0 * 4] = -para[2][0];
339  modelview_matrix[2 + 1 * 4] = -para[2][1];
340  modelview_matrix[2 + 2 * 4] = -para[2][2];
341  modelview_matrix[2 + 3 * 4] = -para[2][3];
342  modelview_matrix[3 + 0 * 4] = 0.0;
343  modelview_matrix[3 + 1 * 4] = 0.0;
344  modelview_matrix[3 + 2 * 4] = 0.0;
345  modelview_matrix[3 + 3 * 4] = 1.0;
346  if (scale != 0.0) {
347  modelview_matrix[12] *= scale;
348  modelview_matrix[13] *= scale;
349  modelview_matrix[14] *= scale;
350  }
351 
352 }
int main(int argc, char **argv)
void setThresholdParams(double param1, double param2)
void vIdle()
const cv::Mat getTvec() const
Definition: posetracker.h:104
void resize(cv::Size size)
void vDrawScene()
CameraParameters TheCameraParams
f
bool isExpressedInPixels() const
Definition: markermap.h:90
MarkerDetector TheMarkerDetector
cv::Mat TheInputImage
float TheMarkerSize
const cv::Mat getRvec() const
Definition: posetracker.h:102
void glGetProjectionMatrix(cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar, bool invert=false)
void setDictionary(std::string dict_type, float error_correction_rate=0)
std::vector< aruco::Marker > detect(const cv::Mat &input)
void readFromFile(string sfile)
Definition: markermap.cpp:89
void vMouse(int b, int s, int x, int y)
cv::Mat getRTMatrix() const
bool estimatePose(const vector< Marker > &v_m)
MarkerMap TheMMConfig
void readFromXMLFile(string filePath)
void setParams(const CameraParameters &cam_params, const MarkerMap &msconf, float markerSize=-1)
void setParams(Params p)
Size TheGlWindowSize
void __glGetModelViewMatrix(double modelview_matrix[16], const cv::Mat &Rvec, const cv::Mat &Tvec)
MarkerMap convertToMeters(float markerSize)
Definition: markermap.cpp:297
bool TheCaptureFlag
cv::Mat TheUndInputImage
MarkerMapPoseTracker MMPoseTracker
Main class for marker detection.
Parameters of the camera.
VideoCapture TheVideoCapturer
std::string getDictionary() const
Definition: markermap.h:132
cv::Mat TheResizedImage
bool The3DInfoAvailable
void vResize(GLsizei iWidth, GLsizei iHeight)
void axis(float size)
vector< Marker > TheMarkers
CornerRefinementMethod _cornerMethod
This class defines a set of markers whose locations are attached to a common reference system...
Definition: markermap.h:71


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:40:45