opencv_calibration.cpp
Go to the documentation of this file.
1 #include <opencv2/core/core.hpp>
2 #include <opencv2/imgproc/imgproc.hpp>
3 #include <opencv2/calib3d/calib3d.hpp>
4 #include <opencv2/highgui/highgui.hpp>
5 #include <cctype>
6 #include <stdio.h>
7 #include <string.h>
8 #include <time.h>
9 #include <iostream>
10 #include <fstream>
11 using namespace cv;
12 using namespace std;
13 
14 const char * usage =
15 " \nexample command line for calibration from a live feed.\n"
16 " calibration -w 4 -h 5 -s 0.025 -o camera.yml -op -oe\n"
17 " \n"
18 " example command line for calibration from a list of stored images:\n"
19 " imagelist_creator image_list.xml *.png\n"
20 " calibration -w 4 -h 5 -s 0.025 -o camera.yml -op -oe image_list.xml\n"
21 " where image_list.xml is the standard OpenCV XML/YAML\n"
22 " use imagelist_creator to create the xml or yaml list\n"
23 " file consisting of the list of strings, e.g.:\n"
24 " \n"
25 "<?xml version=\"1.0\"?>\n"
26 "<opencv_storage>\n"
27 "<images>\n"
28 "view000.png\n"
29 "view001.png\n"
30 "<!-- view002.png -->\n"
31 "view003.png\n"
32 "view010.png\n"
33 "one_extra_view.jpg\n"
34 "</images>\n"
35 "</opencv_storage>\n";
36 
37 
38 
39 
40 const char* liveCaptureHelp =
41  "When the live video from camera is used as input, the following hot-keys may be used:\n"
42  " <ESC>, 'q' - quit the program\n"
43  " 'g' - start capturing images\n"
44  " 'u' - switch undistortion on/off\n";
45 
46 static void help()
47 {
48  printf( "This is a camera calibration sample.\n"
49  "Usage: calibration\n"
50  " -w <board_width> # the number of inner corners per one of board dimension\n"
51  " -h <board_height> # the number of inner corners per another board dimension\n"
52  " [-pt <pattern>] # the type of pattern: chessboard or circles' grid\n"
53  " [-n <number_of_frames>] # the number of frames to use for calibration\n"
54  " # (if not specified, it will be set to the number\n"
55  " # of board views actually available)\n"
56  " [-d <delay>] # a minimum delay in ms between subsequent attempts to capture a next view\n"
57  " # (used only for video capturing)\n"
58  " [-s <squareSize>] # square size in some user-defined units (1 by default)\n"
59  " [-o <out_camera_params>] # the output filename for intrinsic [and extrinsic] parameters\n"
60  " [-op] # write detected feature points\n"
61  " [-oe] # write extrinsic parameters\n"
62  " [-zt] # assume zero tangential distortion\n"
63  " [-a <aspectRatio>] # fix aspect ratio (fx/fy)\n"
64  " [-p] # fix the principal point at the center\n"
65  " [-v] # flip the captured images around the horizontal axis\n"
66  " [-V] # use a video file, and not an image list, uses\n"
67  " # [input_data] string for the video file name\n"
68  " [-su] # show undistorted images after calibration\n"
69  " [input_data] # input data, one of the following:\n"
70  " # - text file with a list of the images of the board\n"
71  " # the text file can be generated with imagelist_creator\n"
72  " # - name of video file with a video of the board\n"
73  " # if input_data not specified, a live view from the camera is used\n"
74  "\n" );
75  printf("\n%s",usage);
76  printf( "\n%s", liveCaptureHelp );
77 }
78 
79 enum { DETECTION = 0, CAPTURING = 1, CALIBRATED = 2 };
81 
83  const vector<vector<Point3f> >& objectPoints,
84  const vector<vector<Point2f> >& imagePoints,
85  const vector<Mat>& rvecs, const vector<Mat>& tvecs,
86  const Mat& cameraMatrix, const Mat& distCoeffs,
87  vector<float>& perViewErrors )
88 {
89  vector<Point2f> imagePoints2;
90  int i, totalPoints = 0;
91  double totalErr = 0, err;
92  perViewErrors.resize(objectPoints.size());
93 
94  for( i = 0; i < (int)objectPoints.size(); i++ )
95  {
96  projectPoints(Mat(objectPoints[i]), rvecs[i], tvecs[i],
97  cameraMatrix, distCoeffs, imagePoints2);
98  err = norm(Mat(imagePoints[i]), Mat(imagePoints2), NORM_L2);
99  int n = (int)objectPoints[i].size();
100  perViewErrors[i] = (float)std::sqrt(err*err/n);
101  totalErr += err*err;
102  totalPoints += n;
103  }
104 
105  return std::sqrt(totalErr/totalPoints);
106 }
107 
108 static void calcChessboardCorners(Size boardSize, float squareSize, vector<Point3f>& corners, Pattern patternType = CHESSBOARD)
109 {
110  corners.resize(0);
111 
112  switch(patternType)
113  {
114  case CHESSBOARD:
115  case CIRCLES_GRID:
116  for( int i = 0; i < boardSize.height; i++ )
117  for( int j = 0; j < boardSize.width; j++ )
118  corners.push_back(Point3f(float(j*squareSize),
119  float(i*squareSize), 0));
120  break;
121 
123  for( int i = 0; i < boardSize.height; i++ )
124  for( int j = 0; j < boardSize.width; j++ )
125  corners.push_back(Point3f(float((2*j + i % 2)*squareSize),
126  float(i*squareSize), 0));
127  break;
128 
129  default:
130  std::cerr<< "Unknown pattern type\n";
131  }
132 }
133 
134 static bool runCalibration( vector<vector<Point2f> > imagePoints,
135  Size imageSize, Size boardSize, Pattern patternType,
136  float squareSize, float aspectRatio,
137  int flags, Mat& cameraMatrix, Mat& distCoeffs,
138  vector<Mat>& rvecs, vector<Mat>& tvecs,
139  vector<float>& reprojErrs,
140  double& totalAvgErr)
141 {
142  cameraMatrix = Mat::eye(3, 3, CV_64F);
143  if( flags & CALIB_FIX_ASPECT_RATIO )
144  cameraMatrix.at<double>(0,0) = aspectRatio;
145 
146  distCoeffs = Mat::zeros(8, 1, CV_64F);
147 
148  vector<vector<Point3f> > objectPoints(1);
149  calcChessboardCorners(boardSize, squareSize, objectPoints[0], patternType);
150 
151  objectPoints.resize(imagePoints.size(),objectPoints[0]);
152 
153  double rms = calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix,
154  distCoeffs, rvecs, tvecs, flags|CALIB_FIX_K4|CALIB_FIX_K5);
156  printf("RMS error reported by calibrateCamera: %g\n", rms);
157 
158  bool ok = checkRange(cameraMatrix) && checkRange(distCoeffs);
159 
160  totalAvgErr = computeReprojectionErrors(objectPoints, imagePoints,
161  rvecs, tvecs, cameraMatrix, distCoeffs, reprojErrs);
162 
163  return ok;
164 }
165 
166 
167 static void saveCameraParams( const string& filename,
168  Size imageSize, Size boardSize,
169  float squareSize, float aspectRatio, int flags,
170  const Mat& cameraMatrix, const Mat& distCoeffs,
171  const vector<Mat>& rvecs, const vector<Mat>& tvecs,
172  const vector<float>& reprojErrs,
173  const vector<vector<Point2f> >& imagePoints,
174  double totalAvgErr )
175 {
176  FileStorage fs( filename, FileStorage::WRITE );
177 
178  time_t tt;
179  time( &tt );
180  struct tm *t2 = localtime( &tt );
181  char buf[1024];
182  strftime( buf, sizeof(buf)-1, "%c", t2 );
183 
184  fs << "calibration_time" << buf;
185 
186  if( !rvecs.empty() || !reprojErrs.empty() )
187  fs << "nframes" << (int)std::max(rvecs.size(), reprojErrs.size());
188  fs << "image_width" << imageSize.width;
189  fs << "image_height" << imageSize.height;
190  fs << "board_width" << boardSize.width;
191  fs << "board_height" << boardSize.height;
192  fs << "square_size" << squareSize;
193 
194  if( flags & CALIB_FIX_ASPECT_RATIO )
195  fs << "aspectRatio" << aspectRatio;
196 
197  if( flags != 0 )
198  {
199  sprintf( buf, "flags: %s%s%s%s",
200  flags & CALIB_USE_INTRINSIC_GUESS ? "+use_intrinsic_guess" : "",
201  flags & CALIB_FIX_ASPECT_RATIO ? "+fix_aspectRatio" : "",
202  flags & CALIB_FIX_PRINCIPAL_POINT ? "+fix_principal_point" : "",
203  flags & CALIB_ZERO_TANGENT_DIST ? "+zero_tangent_dist" : "" );
204  //cvWriteComment( *fs, buf, 0 );
205  }
206 
207  fs << "flags" << flags;
208 
209  fs << "camera_matrix" << cameraMatrix;
210  fs << "distortion_coefficients" << distCoeffs;
211 
212  fs << "avg_reprojection_error" << totalAvgErr;
213  if( !reprojErrs.empty() )
214  fs << "per_view_reprojection_errors" << Mat(reprojErrs);
215 
216  if( !rvecs.empty() && !tvecs.empty() )
217  {
218  CV_Assert(rvecs[0].type() == tvecs[0].type());
219  Mat bigmat((int)rvecs.size(), 6, rvecs[0].type());
220  for( int i = 0; i < (int)rvecs.size(); i++ )
221  {
222  Mat r = bigmat(Range(i, i+1), Range(0,3));
223  Mat t = bigmat(Range(i, i+1), Range(3,6));
224 
225  CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1);
226  CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1);
227  //*.t() is MatExpr (not Mat) so we can use assignment operator
228  r = rvecs[i].t();
229  t = tvecs[i].t();
230  }
231  //cvWriteComment( *fs, "a set of 6-tuples (rotation vector + translation vector) for each view", 0 );
232  fs << "extrinsic_parameters" << bigmat;
233  }
234 
235  if( !imagePoints.empty() )
236  {
237  Mat imagePtMat((int)imagePoints.size(), (int)imagePoints[0].size(), CV_32FC2);
238  for( int i = 0; i < (int)imagePoints.size(); i++ )
239  {
240  Mat r = imagePtMat.row(i).reshape(2, imagePtMat.cols);
241  Mat imgpti(imagePoints[i]);
242  imgpti.copyTo(r);
243  }
244  fs << "image_points" << imagePtMat;
245  }
246 }
247 
248 static bool readStringList( const string& filename, vector<string>& l )
249 {
250  try{
251  FileStorage fs(filename, FileStorage::READ);
252  if( !fs.isOpened() )
253  return false;
254  FileNode n = fs.getFirstTopLevelNode();
255  if( n.type() != FileNode::SEQ )
256  return false;
257  FileNodeIterator it = n.begin(), it_end = n.end();
258  for( ; it != it_end; ++it )
259  l.push_back((string)*it);
260  }catch(std::exception &ex){
261  cerr<<"ex:"<<ex.what()<<endl;
262  return false;
263  }
264  return true;
265 }
266 static bool readInputFile( const string& filename, vector<string>& l )throw(std::exception)
267 {
268 
269  l.resize(0);
270 if( !readStringList(filename,l)){
271  cout<<"read txt file"<<endl;
272  //read as txt file
273  std::ifstream file(filename.c_str());
274  std::string str;
275  file>>str;
276  while(!file.eof()){
277  l.push_back(str);
278  file>>str;
279 
280  }
281  return true;
282 
283 }
284 else return true;
285 }
286 
287 
288 static bool runAndSave(const string& outputFilename,
289  const vector<vector<Point2f> >& imagePoints,
290  Size imageSize, Size boardSize, Pattern patternType, float squareSize,
291  float aspectRatio, int flags, Mat& cameraMatrix,
292  Mat& distCoeffs, bool writeExtrinsics, bool writePoints )
293 {
294  vector<Mat> rvecs, tvecs;
295  vector<float> reprojErrs;
296  double totalAvgErr = 0;
297 
298  bool ok = runCalibration(imagePoints, imageSize, boardSize, patternType, squareSize,
299  aspectRatio, flags, cameraMatrix, distCoeffs,
300  rvecs, tvecs, reprojErrs, totalAvgErr);
301  printf("%s. avg reprojection error = %.2f\n",
302  ok ? "Calibration succeeded" : "Calibration failed",
303  totalAvgErr);
304 
305  if( ok )
306  saveCameraParams( outputFilename, imageSize,
307  boardSize, squareSize, aspectRatio,
308  flags, cameraMatrix, distCoeffs,
309  writeExtrinsics ? rvecs : vector<Mat>(),
310  writeExtrinsics ? tvecs : vector<Mat>(),
311  writeExtrinsics ? reprojErrs : vector<float>(),
312  writePoints ? imagePoints : vector<vector<Point2f> >(),
313  totalAvgErr );
314  return ok;
315 }
316 
317 
318 int main( int argc, char** argv )
319 {
320  Size boardSize, imageSize;
321  float squareSize = 1.f, aspectRatio = 1.f;
322  Mat cameraMatrix, distCoeffs;
323  const char* outputFilename = "out_camera_data.yml";
324  const char* inputFilename = 0;
325 
326  int i, nframes = 10;
327  bool writeExtrinsics = false, writePoints = false;
328  bool undistortImage = false;
329  int flags = 0;
330  cv::VideoCapture capture;
331  bool flipVertical = false;
332  bool showUndistorted = false;
333  bool videofile = false;
334  int delay = 1000;
335  clock_t prevTimestamp = 0;
336  int mode = DETECTION;
337  int cameraId = 0;
338  vector<vector<Point2f> > imagePoints;
339  vector<string> imageList;
340  Pattern pattern = CHESSBOARD;
341 
342  if( argc < 2 )
343  {
344  help();
345  return 0;
346  }
347 
348  for( i = 1; i < argc; i++ )
349  {
350  const char* s = argv[i];
351  if( strcmp( s, "-w" ) == 0 )
352  {
353  if( sscanf( argv[++i], "%u", &boardSize.width ) != 1 || boardSize.width <= 0 )
354  return fprintf( stderr, "Invalid board width\n" ), -1;
355  }
356  else if( strcmp( s, "-h" ) == 0 )
357  {
358  if( sscanf( argv[++i], "%u", &boardSize.height ) != 1 || boardSize.height <= 0 )
359  return fprintf( stderr, "Invalid board height\n" ), -1;
360  }
361  else if( strcmp( s, "-pt" ) == 0 )
362  {
363  i++;
364  if( !strcmp( argv[i], "circles" ) )
365  pattern = CIRCLES_GRID;
366  else if( !strcmp( argv[i], "acircles" ) )
367  pattern = ASYMMETRIC_CIRCLES_GRID;
368  else if( !strcmp( argv[i], "chessboard" ) )
369  pattern = CHESSBOARD;
370  else
371  return fprintf( stderr, "Invalid pattern type: must be chessboard or circles\n" ), -1;
372  }
373  else if( strcmp( s, "-s" ) == 0 )
374  {
375  if( sscanf( argv[++i], "%f", &squareSize ) != 1 || squareSize <= 0 )
376  return fprintf( stderr, "Invalid board square width\n" ), -1;
377  }
378  else if( strcmp( s, "-n" ) == 0 )
379  {
380  if( sscanf( argv[++i], "%u", &nframes ) != 1 || nframes <= 3 )
381  return printf("Invalid number of images\n" ), -1;
382  }
383  else if( strcmp( s, "-a" ) == 0 )
384  {
385  if( sscanf( argv[++i], "%f", &aspectRatio ) != 1 || aspectRatio <= 0 )
386  return printf("Invalid aspect ratio\n" ), -1;
387  flags |= CALIB_FIX_ASPECT_RATIO;
388  }
389  else if( strcmp( s, "-d" ) == 0 )
390  {
391  if( sscanf( argv[++i], "%u", &delay ) != 1 || delay <= 0 )
392  return printf("Invalid delay\n" ), -1;
393  }
394  else if( strcmp( s, "-op" ) == 0 )
395  {
396  writePoints = true;
397  }
398  else if( strcmp( s, "-oe" ) == 0 )
399  {
400  writeExtrinsics = true;
401  }
402  else if( strcmp( s, "-zt" ) == 0 )
403  {
404  flags |= CALIB_ZERO_TANGENT_DIST;
405  }
406  else if( strcmp( s, "-p" ) == 0 )
407  {
408  flags |= CALIB_FIX_PRINCIPAL_POINT;
409  }
410  else if( strcmp( s, "-v" ) == 0 )
411  {
412  flipVertical = true;
413  }
414  else if( strcmp( s, "-V" ) == 0 )
415  {
416  videofile = true;
417  }
418  else if( strcmp( s, "-o" ) == 0 )
419  {
420  outputFilename = argv[++i];
421  }
422  else if( strcmp( s, "-su" ) == 0 )
423  {
424  showUndistorted = true;
425  }
426  else if( s[0] != '-' )
427  {
428  if( isdigit(s[0]) )
429  sscanf(s, "%d", &cameraId);
430  else
431  inputFilename = s;
432  }
433  else
434  return fprintf( stderr, "Unknown option %s", s ), -1;
435  }
436 
437  if( inputFilename )
438  {
439  if( !videofile && readInputFile(inputFilename, imageList) )
440  mode = CAPTURING;
441  else
442  capture.open(inputFilename);
443  }
444  else
445  capture.open(cameraId);
446 
447  if( !capture.isOpened() && imageList.empty() )
448  return fprintf( stderr, "Could not initialize video (%d) capture\n",cameraId ), -2;
449 
450  if( !imageList.empty() )
451  nframes = (int)imageList.size();
452 
453  if( capture.isOpened() )
454  printf( "%s", liveCaptureHelp );
455 
456  namedWindow( "Image View", 1 );
457 
458  for(i = 0;;i++)
459  {
460  Mat view, viewGray;
461  bool blink = false;
462 
463  if( capture.isOpened() )
464  {
465  Mat view0;
466  capture >> view0;
467  view0.copyTo(view);
468  }
469  else if( i < (int)imageList.size() )
470  view = imread(imageList[i], 1);
471 
472  if(view.empty())
473  {
474  if( imagePoints.size() > 0 )
475  runAndSave(outputFilename, imagePoints, imageSize,
476  boardSize, pattern, squareSize, aspectRatio,
477  flags, cameraMatrix, distCoeffs,
478  writeExtrinsics, writePoints);
479  break;
480  }
481 
482  imageSize = view.size();
483 
484  if( flipVertical )
485  flip( view, view, 0 );
486 
487  vector<Point2f> pointbuf;
488  cvtColor(view, viewGray, COLOR_BGR2GRAY);
489 
490  bool found;
491  switch( pattern )
492  {
493  case CHESSBOARD:
494  found = findChessboardCorners( view, boardSize, pointbuf,
495  CALIB_CB_ADAPTIVE_THRESH | CALIB_CB_FAST_CHECK | CALIB_CB_NORMALIZE_IMAGE);
496  break;
497  case CIRCLES_GRID:
498  found = findCirclesGrid( view, boardSize, pointbuf );
499  break;
501  found = findCirclesGrid( view, boardSize, pointbuf, CALIB_CB_ASYMMETRIC_GRID );
502  break;
503  default:
504  return fprintf( stderr, "Unknown pattern type\n" ), -1;
505  }
506 
507  // improve the found corners' coordinate accuracy
508  if( pattern == CHESSBOARD && found) cornerSubPix( viewGray, pointbuf, Size(11,11),
509  Size(-1,-1), TermCriteria( TermCriteria::EPS+TermCriteria::COUNT, 30, 0.1 ));
510 
511  if( mode == CAPTURING && found &&
512  (!capture.isOpened() || clock() - prevTimestamp > delay*1e-3*CLOCKS_PER_SEC) )
513  {
514  imagePoints.push_back(pointbuf);
515  prevTimestamp = clock();
516  blink = capture.isOpened();
517  }
518 
519  if(found)
520  drawChessboardCorners( view, boardSize, Mat(pointbuf), found );
521 
522  string msg = mode == CAPTURING ? "100/100" :
523  mode == CALIBRATED ? "Calibrated" : "Press 'g' to start";
524  int baseLine = 0;
525  Size textSize = getTextSize(msg, 1, 1, 1, &baseLine);
526  Point textOrigin(view.cols - 2*textSize.width - 10, view.rows - 2*baseLine - 10);
527 
528  if( mode == CAPTURING )
529  {
530  if(undistortImage)
531  msg = format( "%d/%d Undist", (int)imagePoints.size(), nframes );
532  else
533  msg = format( "%d/%d", (int)imagePoints.size(), nframes );
534  }
535 
536  putText( view, msg, textOrigin, 1, 1,
537  mode != CALIBRATED ? Scalar(0,0,255) : Scalar(0,255,0));
538 
539  if( blink )
540  bitwise_not(view, view);
541 
542  if( mode == CALIBRATED && undistortImage )
543  {
544  Mat temp = view.clone();
545  undistort(temp, view, cameraMatrix, distCoeffs);
546  }
547 
548  imshow("Image View", view);
549  int key = 0xff & waitKey(capture.isOpened() ? 50 : 500);
550 
551  if( (key & 255) == 27 )
552  break;
553 
554  if( key == 'u' && mode == CALIBRATED )
555  undistortImage = !undistortImage;
556 
557  if( capture.isOpened() && key == 'g' )
558  {
559  mode = CAPTURING;
560  imagePoints.clear();
561  }
562 
563  if( mode == CAPTURING && imagePoints.size() >= (unsigned)nframes )
564  {
565  if( runAndSave(outputFilename, imagePoints, imageSize,
566  boardSize, pattern, squareSize, aspectRatio,
567  flags, cameraMatrix, distCoeffs,
568  writeExtrinsics, writePoints))
569  mode = CALIBRATED;
570  else
571  mode = DETECTION;
572  if( !capture.isOpened() )
573  break;
574  }
575  }
576 
577  if( !capture.isOpened() && showUndistorted )
578  {
579  Mat view, rview, map1, map2;
580  initUndistortRectifyMap(cameraMatrix, distCoeffs, Mat(),
581  getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, imageSize, 1, imageSize, 0),
582  imageSize, CV_16SC2, map1, map2);
583 
584  for( i = 0; i < (int)imageList.size(); i++ )
585  {
586  view = imread(imageList[i], 1);
587  if(view.empty())
588  continue;
589  //undistort( view, rview, cameraMatrix, distCoeffs, cameraMatrix );
590  remap(view, rview, map1, map2, INTER_LINEAR);
591  imshow("Image View", rview);
592  int c = 0xff & waitKey();
593  if( (c & 255) == 27 || c == 'q' || c == 'Q' )
594  break;
595  }
596  }
597 
598  return 0;
599 }
600 
filename
XmlRpcServer s
static void saveCameraParams(const string &filename, Size imageSize, Size boardSize, float squareSize, float aspectRatio, int flags, const Mat &cameraMatrix, const Mat &distCoeffs, const vector< Mat > &rvecs, const vector< Mat > &tvecs, const vector< float > &reprojErrs, const vector< vector< Point2f > > &imagePoints, double totalAvgErr)
const char * usage
static bool runAndSave(const string &outputFilename, const vector< vector< Point2f > > &imagePoints, Size imageSize, Size boardSize, Pattern patternType, float squareSize, float aspectRatio, int flags, Mat &cameraMatrix, Mat &distCoeffs, bool writeExtrinsics, bool writePoints)
ROSCPP_DECL std::string remap(const std::string &name)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
int main(int argc, char **argv)
static void help()
static bool runCalibration(vector< vector< Point2f > > imagePoints, Size imageSize, Size boardSize, Pattern patternType, float squareSize, float aspectRatio, int flags, Mat &cameraMatrix, Mat &distCoeffs, vector< Mat > &rvecs, vector< Mat > &tvecs, vector< float > &reprojErrs, double &totalAvgErr)
static bool readStringList(const string &filename, vector< string > &l)
static void calcChessboardCorners(Size boardSize, float squareSize, vector< Point3f > &corners, Pattern patternType=CHESSBOARD)
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const
const char * liveCaptureHelp
static double computeReprojectionErrors(const vector< vector< Point3f > > &objectPoints, const vector< vector< Point2f > > &imagePoints, const vector< Mat > &rvecs, const vector< Mat > &tvecs, const Mat &cameraMatrix, const Mat &distCoeffs, vector< float > &perViewErrors)
static bool readInputFile(const string &filename, vector< string > &l)


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