kinect2_calibration.cpp
Go to the documentation of this file.
1 
18 #include <stdlib.h>
19 #include <stdio.h>
20 #include <iostream>
21 #include <sstream>
22 #include <fstream>
23 #include <string>
24 #include <vector>
25 #include <mutex>
26 #include <thread>
27 
28 #include <dirent.h>
29 #include <sys/stat.h>
30 
31 #include <opencv2/opencv.hpp>
32 
33 #include <ros/ros.h>
34 #include <ros/spinner.h>
35 #include <sensor_msgs/CameraInfo.h>
36 #include <sensor_msgs/Image.h>
37 
38 #include <cv_bridge/cv_bridge.h>
39 
42 
46 
49 
50 
51 enum Mode
52 {
55 };
56 
57 enum Source
58 {
60  IR,
62 };
63 
64 class Recorder
65 {
66 private:
67  const bool circleBoard;
69 
70  const cv::Size boardDims;
71  const float boardSize;
72  const Source mode;
73 
74  const std::string path;
75  const std::string topicColor, topicIr, topicDepth;
76  std::mutex lock;
77 
78  bool update;
80  cv::Mat color, ir, irGrey, depth;
81 
82  size_t frame;
83  std::vector<int> params;
84 
85  std::vector<cv::Point3f> board;
86  std::vector<cv::Point2f> pointsColor, pointsIr;
87 
94 
95  int minIr, maxIr;
96  cv::Ptr<cv::CLAHE> clahe;
97 
98 public:
99  Recorder(const std::string &path, const std::string &topicColor, const std::string &topicIr, const std::string &topicDepth,
100  const Source mode, const bool circleBoard, const bool symmetric, const cv::Size &boardDims, const float boardSize)
101  : circleBoard(circleBoard), boardDims(boardDims), boardSize(boardSize), mode(mode), path(path), topicColor(topicColor), topicIr(topicIr),
102  topicDepth(topicDepth), update(false), foundColor(false), foundIr(false), frame(0), nh("~"), spinner(0), it(nh), minIr(0), maxIr(0x7FFF)
103  {
104  if(symmetric)
105  {
106  circleFlags = cv::CALIB_CB_SYMMETRIC_GRID + cv::CALIB_CB_CLUSTERING;
107  }
108  else
109  {
110  circleFlags = cv::CALIB_CB_ASYMMETRIC_GRID + cv::CALIB_CB_CLUSTERING;
111  }
112 
113  params.push_back(CV_IMWRITE_PNG_COMPRESSION);
114  params.push_back(9);
115 
116  board.resize(boardDims.width * boardDims.height);
117  for(size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
118  {
119  for(size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
120  {
121  board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
122  }
123  }
124 
125  clahe = cv::createCLAHE(1.5, cv::Size(32, 32));
126  }
127 
129  {
130  }
131 
132  void run()
133  {
134  startRecord();
135 
136  display();
137 
138  stopRecord();
139  }
140 
141 private:
142  void startRecord()
143  {
144  OUT_INFO("Controls:" << std::endl
145  << FG_YELLOW " [ESC, q]" NO_COLOR " - Exit" << std::endl
146  << FG_YELLOW " [SPACE, s]" NO_COLOR " - Save current frame" << std::endl
147  << FG_YELLOW " [l]" NO_COLOR " - decrease min and max value for IR value range" << std::endl
148  << FG_YELLOW " [h]" NO_COLOR " - increase min and max value for IR value range" << std::endl
149  << FG_YELLOW " [1]" NO_COLOR " - decrease min value for IR value range" << std::endl
150  << FG_YELLOW " [2]" NO_COLOR " - increase min value for IR value range" << std::endl
151  << FG_YELLOW " [3]" NO_COLOR " - decrease max value for IR value range" << std::endl
152  << FG_YELLOW " [4]" NO_COLOR " - increase max value for IR value range");
153 
154  image_transport::TransportHints hints("compressed");
155  subImageColor = new image_transport::SubscriberFilter(it, topicColor, 4, hints);
156  subImageIr = new image_transport::SubscriberFilter(it, topicIr, 4, hints);
157  subImageDepth = new image_transport::SubscriberFilter(it, topicDepth, 4, hints);
158 
160  sync->registerCallback(boost::bind(&Recorder::callback, this, _1, _2, _3));
161 
162  spinner.start();
163  }
164 
165  void stopRecord()
166  {
167  spinner.stop();
168 
169  delete sync;
170  delete subImageColor;
171  delete subImageIr;
172  delete subImageDepth;
173  }
174 
175  void convertIr(const cv::Mat &ir, cv::Mat &grey)
176  {
177  const float factor = 255.0f / (maxIr - minIr);
178  grey.create(ir.rows, ir.cols, CV_8U);
179 
180  #pragma omp parallel for
181  for(size_t r = 0; r < (size_t)ir.rows; ++r)
182  {
183  const uint16_t *itI = ir.ptr<uint16_t>(r);
184  uint8_t *itO = grey.ptr<uint8_t>(r);
185 
186  for(size_t c = 0; c < (size_t)ir.cols; ++c, ++itI, ++itO)
187  {
188  *itO = std::min(std::max(*itI - minIr, 0) * factor, 255.0f);
189  }
190  }
191  clahe->apply(grey, grey);
192  }
193 
194  void findMinMax(const cv::Mat &ir, const std::vector<cv::Point2f> &pointsIr)
195  {
196  minIr = 0xFFFF;
197  maxIr = 0;
198  for(size_t i = 0; i < pointsIr.size(); ++i)
199  {
200  const cv::Point2f &p = pointsIr[i];
201  cv::Rect roi(std::max(0, (int)p.x - 2), std::max(0, (int)p.y - 2), 9, 9);
202  roi.width = std::min(roi.width, ir.cols - roi.x);
203  roi.height = std::min(roi.height, ir.rows - roi.y);
204 
205  findMinMax(ir(roi));
206  }
207  }
208 
209  void findMinMax(const cv::Mat &ir)
210  {
211  for(size_t r = 0; r < (size_t)ir.rows; ++r)
212  {
213  const uint16_t *it = ir.ptr<uint16_t>(r);
214 
215  for(size_t c = 0; c < (size_t)ir.cols; ++c, ++it)
216  {
217  minIr = std::min(minIr, (int) * it);
218  maxIr = std::max(maxIr, (int) * it);
219  }
220  }
221  }
222 
223  void callback(const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageIr, const sensor_msgs::Image::ConstPtr imageDepth)
224  {
225  std::vector<cv::Point2f> pointsColor, pointsIr;
226  cv::Mat color, ir, irGrey, irScaled, depth;
227  bool foundColor = false;
228  bool foundIr = false;
229 
230  if(mode == COLOR || mode == SYNC)
231  {
232  readImage(imageColor, color);
233  }
234  if(mode == IR || mode == SYNC)
235  {
236  readImage(imageIr, ir);
237  readImage(imageDepth, depth);
238  cv::resize(ir, irScaled, cv::Size(), 2.0, 2.0, cv::INTER_CUBIC);
239 
240  convertIr(irScaled, irGrey);
241  }
242 
243  if(circleBoard)
244  {
245  switch(mode)
246  {
247  case COLOR:
248  foundColor = cv::findCirclesGrid(color, boardDims, pointsColor, circleFlags);
249  break;
250  case IR:
251  foundIr = cv::findCirclesGrid(irGrey, boardDims, pointsIr, circleFlags);
252  break;
253  case SYNC:
254  foundColor = cv::findCirclesGrid(color, boardDims, pointsColor, circleFlags);
255  foundIr = cv::findCirclesGrid(irGrey, boardDims, pointsIr, circleFlags);
256  break;
257  }
258  }
259  else
260  {
261  const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::COUNT, 100, DBL_EPSILON);
262  switch(mode)
263  {
264  case COLOR:
265  foundColor = cv::findChessboardCorners(color, boardDims, pointsColor, cv::CALIB_CB_FAST_CHECK);
266  break;
267  case IR:
268  foundIr = cv::findChessboardCorners(irGrey, boardDims, pointsIr, cv::CALIB_CB_ADAPTIVE_THRESH);
269  break;
270  case SYNC:
271  foundColor = cv::findChessboardCorners(color, boardDims, pointsColor, cv::CALIB_CB_FAST_CHECK);
272  foundIr = cv::findChessboardCorners(irGrey, boardDims, pointsIr, cv::CALIB_CB_ADAPTIVE_THRESH);
273  break;
274  }
275  if(foundColor)
276  {
277  cv::cornerSubPix(color, pointsColor, cv::Size(11, 11), cv::Size(-1, -1), termCriteria);
278  }
279  if(foundIr)
280  {
281  cv::cornerSubPix(irGrey, pointsIr, cv::Size(11, 11), cv::Size(-1, -1), termCriteria);
282  }
283  }
284 
285  if(foundIr)
286  {
287  // Update min and max ir value based on checkerboard values
288  findMinMax(irScaled, pointsIr);
289  }
290 
291  lock.lock();
292  this->color = color;
293  this->ir = ir;
294  this->irGrey = irGrey;
295  this->depth = depth;
296  this->foundColor = foundColor;
297  this->foundIr = foundIr;
298  this->pointsColor = pointsColor;
299  this->pointsIr = pointsIr;
300  update = true;
301  lock.unlock();
302  }
303 
304  void display()
305  {
306  std::vector<cv::Point2f> pointsColor, pointsIr;
307  cv::Mat color, ir, irGrey, depth;
308  cv::Mat colorDisp, irDisp;
309  bool foundColor = false;
310  bool foundIr = false;
311  bool save = false;
312  bool running = true;
313 
314  std::chrono::milliseconds duration(1);
315  while(!update && ros::ok())
316  {
317  std::this_thread::sleep_for(duration);
318  }
319 
320  for(; ros::ok() && running;)
321  {
322  if(update)
323  {
324  lock.lock();
325  color = this->color;
326  ir = this->ir;
327  irGrey = this->irGrey;
328  depth = this->depth;
329  foundColor = this->foundColor;
330  foundIr = this->foundIr;
331  pointsColor = this->pointsColor;
332  pointsIr = this->pointsIr;
333  update = false;
334  lock.unlock();
335 
336  if(mode == COLOR || mode == SYNC)
337  {
338  cv::cvtColor(color, colorDisp, CV_GRAY2BGR);
339  cv::drawChessboardCorners(colorDisp, boardDims, pointsColor, foundColor);
340  //cv::resize(colorDisp, colorDisp, cv::Size(), 0.5, 0.5);
341  //cv::flip(colorDisp, colorDisp, 1);
342  }
343  if(mode == IR || mode == SYNC)
344  {
345  cv::cvtColor(irGrey, irDisp, CV_GRAY2BGR);
346  cv::drawChessboardCorners(irDisp, boardDims, pointsIr, foundIr);
347  //cv::resize(irDisp, irDisp, cv::Size(), 0.5, 0.5);
348  //cv::flip(irDisp, irDisp, 1);
349  }
350  }
351 
352  switch(mode)
353  {
354  case COLOR:
355  cv::imshow("color", colorDisp);
356  break;
357  case IR:
358  cv::imshow("ir", irDisp);
359  break;
360  case SYNC:
361  cv::imshow("color", colorDisp);
362  cv::imshow("ir", irDisp);
363  break;
364  }
365 
366  int key = cv::waitKey(10);
367  switch(key & 0xFF)
368  {
369  case ' ':
370  case 's':
371  save = true;
372  break;
373  case 27:
374  case 'q':
375  running = false;
376  break;
377  case '1':
378  minIr = std::max(0, minIr - 100);
379  break;
380  case '2':
381  minIr = std::min(maxIr - 1, minIr + 100);
382  break;
383  case '3':
384  maxIr = std::max(minIr + 1, maxIr - 100);
385  break;
386  case '4':
387  maxIr = std::min(0xFFFF, maxIr + 100);
388  break;
389  case 'l':
390  minIr = std::max(0, minIr - 100);
391  maxIr = std::max(minIr + 1, maxIr - 100);
392  break;
393  case 'h':
394  maxIr = std::min(0x7FFF, maxIr + 100);
395  minIr = std::min(maxIr - 1, minIr + 100);
396  break;
397  }
398 
399  if(save && ((mode == COLOR && foundColor) || (mode == IR && foundIr) || (mode == SYNC && foundColor && foundIr)))
400  {
401  store(color, ir, irGrey, depth, pointsColor, pointsIr);
402  save = false;
403  }
404  }
405  cv::destroyAllWindows();
406  cv::waitKey(100);
407  }
408 
409  void readImage(const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
410  {
412  pCvImage = cv_bridge::toCvShare(msgImage, msgImage->encoding);
413  pCvImage->image.copyTo(image);
414  }
415 
416  void store(const cv::Mat &color, const cv::Mat &ir, const cv::Mat &irGrey, const cv::Mat &depth, const std::vector<cv::Point2f> &pointsColor, std::vector<cv::Point2f> &pointsIr)
417  {
418  std::ostringstream oss;
419  oss << std::setfill('0') << std::setw(4) << frame++;
420  const std::string frameNumber(oss.str());
421  OUT_INFO("storing frame: " << frameNumber);
422  std::string base = path + frameNumber;
423 
424  for(size_t i = 0; i < pointsIr.size(); ++i)
425  {
426  pointsIr[i].x /= 2.0;
427  pointsIr[i].y /= 2.0;
428  }
429 
430  if(mode == SYNC)
431  {
432  base += CALIB_SYNC;
433  }
434 
435  if(mode == COLOR || mode == SYNC)
436  {
437  cv::imwrite(base + CALIB_FILE_COLOR, color, params);
438 
439  cv::FileStorage file(base + CALIB_POINTS_COLOR, cv::FileStorage::WRITE);
440  file << "points" << pointsColor;
441  }
442 
443  if(mode == IR || mode == SYNC)
444  {
445  cv::imwrite(base + CALIB_FILE_IR, ir, params);
446  cv::imwrite(base + CALIB_FILE_IR_GREY, irGrey, params);
447  cv::imwrite(base + CALIB_FILE_DEPTH, depth, params);
448 
449  cv::FileStorage file(base + CALIB_POINTS_IR, cv::FileStorage::WRITE);
450  file << "points" << pointsIr;
451  }
452  }
453 };
454 
456 {
457 private:
458  const bool circleBoard;
459  const cv::Size boardDims;
460  const float boardSize;
461  const int flags;
462 
463  const Source mode;
464  const std::string path;
465 
466  std::vector<cv::Point3f> board;
467 
468  std::vector<std::vector<cv::Point3f> > pointsBoard;
469  std::vector<std::vector<cv::Point2f> > pointsColor;
470  std::vector<std::vector<cv::Point2f> > pointsIr;
471 
472  cv::Size sizeColor;
473  cv::Size sizeIr;
474 
475  cv::Mat cameraMatrixColor, distortionColor, rotationColor, translationColor, projectionColor;
476  cv::Mat cameraMatrixIr, distortionIr, rotationIr, translationIr, projectionIr;
477  cv::Mat rotation, translation, essential, fundamental, disparity;
478 
479  std::vector<cv::Mat> rvecsColor, tvecsColor;
480  std::vector<cv::Mat> rvecsIr, tvecsIr;
481 
482 public:
483  CameraCalibration(const std::string &path, const Source mode, const bool circleBoard, const cv::Size &boardDims, const float boardSize, const bool rational)
484  : circleBoard(circleBoard), boardDims(boardDims), boardSize(boardSize), flags(rational ? cv::CALIB_RATIONAL_MODEL : 0), mode(mode), path(path), sizeColor(1920, 1080), sizeIr(512, 424)
485  {
486  board.resize(boardDims.width * boardDims.height);
487  for(size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
488  {
489  for(size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
490  {
491  board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
492  }
493  }
494  }
495 
497  {
498  }
499 
500  bool restore()
501  {
502  std::vector<std::string> filesSync;
503  std::vector<std::string> filesColor;
504  std::vector<std::string> filesIr;
505 
506  DIR *dp;
507  struct dirent *dirp;
508  size_t posColor, posIr, posSync;
509 
510  if((dp = opendir(path.c_str())) == NULL)
511  {
512  OUT_ERROR("Error opening: " << path);
513  return false;
514  }
515 
516  while((dirp = readdir(dp)) != NULL)
517  {
518  std::string filename = dirp->d_name;
519 
520  if(dirp->d_type != DT_REG)
521  {
522  continue;
523  }
524 
525  posSync = filename.rfind(CALIB_SYNC);
526  posColor = filename.rfind(CALIB_FILE_COLOR);
527 
528  if(posSync != std::string::npos)
529  {
530  if(posColor != std::string::npos)
531  {
532  std::string frameName = filename.substr(0, posColor);
533  filesSync.push_back(frameName);
534  filesColor.push_back(frameName);
535  filesIr.push_back(frameName);
536  }
537  continue;
538  }
539 
540  if(posColor != std::string::npos)
541  {
542  std::string frameName = filename.substr(0, posColor);
543  filesColor.push_back(frameName);
544  continue;
545  }
546 
547  posIr = filename.rfind(CALIB_FILE_IR_GREY);
548  if(posIr != std::string::npos)
549  {
550  std::string frameName = filename.substr(0, posIr);
551  filesIr.push_back(frameName);
552  continue;
553  }
554  }
555  closedir(dp);
556 
557  std::sort(filesColor.begin(), filesColor.end());
558  std::sort(filesIr.begin(), filesIr.end());
559  std::sort(filesSync.begin(), filesSync.end());
560 
561  bool ret = true;
562  switch(mode)
563  {
564  case COLOR:
565  if(filesColor.empty())
566  {
567  OUT_ERROR("no files found!");
568  return false;
569  }
570  pointsColor.resize(filesColor.size());
571  pointsBoard.resize(filesColor.size(), board);
572  ret = ret && readFiles(filesColor, CALIB_POINTS_COLOR, pointsColor);
573  break;
574  case IR:
575  if(filesIr.empty())
576  {
577  OUT_ERROR("no files found!");
578  return false;
579  }
580  pointsIr.resize(filesIr.size());
581  pointsBoard.resize(filesIr.size(), board);
582  ret = ret && readFiles(filesIr, CALIB_POINTS_IR, pointsIr);
583  break;
584  case SYNC:
585  if(filesColor.empty() || filesIr.empty())
586  {
587  OUT_ERROR("no files found!");
588  return false;
589  }
590  pointsColor.resize(filesColor.size());
591  pointsIr.resize(filesSync.size());
592  pointsColor.resize(filesSync.size());
593  pointsBoard.resize(filesSync.size(), board);
594  ret = ret && readFiles(filesSync, CALIB_POINTS_COLOR, pointsColor);
595  ret = ret && readFiles(filesSync, CALIB_POINTS_IR, pointsIr);
596  ret = ret && checkSyncPointsOrder();
597  ret = ret && loadCalibration();
598  break;
599  }
600  return ret;
601  }
602 
603  void calibrate()
604  {
605  switch(mode)
606  {
607  case COLOR:
608  calibrateIntrinsics(sizeColor, pointsBoard, pointsColor, cameraMatrixColor, distortionColor, rotationColor, projectionColor, rvecsColor, tvecsColor);
609  break;
610  case IR:
611  calibrateIntrinsics(sizeIr, pointsBoard, pointsIr, cameraMatrixIr, distortionIr, rotationIr, projectionIr, rvecsIr, tvecsIr);
612  break;
613  case SYNC:
614  calibrateExtrinsics();
615  break;
616  }
617  storeCalibration();
618  }
619 
620 private:
621  bool readFiles(const std::vector<std::string> &files, const std::string &ext, std::vector<std::vector<cv::Point2f> > &points) const
622  {
623  bool ret = true;
624  #pragma omp parallel for
625  for(size_t i = 0; i < files.size(); ++i)
626  {
627  std::string pointsname = path + files[i] + ext;
628 
629  #pragma omp critical
630  OUT_INFO("restoring file: " << files[i] << ext);
631 
632  cv::FileStorage file(pointsname, cv::FileStorage::READ);
633  if(!file.isOpened())
634  {
635  #pragma omp critical
636  {
637  ret = false;
638  OUT_ERROR("couldn't open file: " << files[i] << ext);
639  }
640  }
641  else
642  {
643  file["points"] >> points[i];
644  }
645  }
646  return ret;
647  }
648 
650  {
651  if(pointsColor.size() != pointsIr.size())
652  {
653  OUT_ERROR("number of detected color and ir patterns does not match!");
654  return false;
655  }
656 
657  for(size_t i = 0; i < pointsColor.size(); ++i)
658  {
659  const std::vector<cv::Point2f> &pColor = pointsColor[i];
660  const std::vector<cv::Point2f> &pIr = pointsIr[i];
661 
662  if(pColor.front().y > pColor.back().y || pColor.front().x > pColor.back().x)
663  {
664  std::reverse(pointsColor[i].begin(), pointsColor[i].end());
665  }
666 
667  if(pIr.front().y > pIr.back().y || pIr.front().x > pIr.back().x)
668  {
669  std::reverse(pointsIr[i].begin(), pointsIr[i].end());
670  }
671  }
672  return true;
673  }
674 
675  void calibrateIntrinsics(const cv::Size &size, const std::vector<std::vector<cv::Point3f> > &pointsBoard, const std::vector<std::vector<cv::Point2f> > &points,
676  cv::Mat &cameraMatrix, cv::Mat &distortion, cv::Mat &rotation, cv::Mat &projection, std::vector<cv::Mat> &rvecs, std::vector<cv::Mat> &tvecs)
677  {
678  if(points.empty())
679  {
680  OUT_ERROR("no data for calibration provided!");
681  return;
682  }
683  const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 50, DBL_EPSILON);
684  double error;
685 
686  OUT_INFO("calibrating intrinsics...");
687  error = cv::calibrateCamera(pointsBoard, points, size, cameraMatrix, distortion, rvecs, tvecs, flags, termCriteria);
688  OUT_INFO("re-projection error: " << error << std::endl);
689 
690  OUT_INFO("Camera Matrix:" << std::endl << cameraMatrix);
691  OUT_INFO("Distortion Coeeficients:" << std::endl << distortion << std::endl);
692  rotation = cv::Mat::eye(3, 3, CV_64F);
693  projection = cv::Mat::eye(4, 4, CV_64F);
694  cameraMatrix.copyTo(projection(cv::Rect(0, 0, 3, 3)));
695  }
696 
698  {
699  if(pointsColor.size() != pointsIr.size())
700  {
701  OUT_ERROR("number of detected color and ir patterns does not match!");
702  return;
703  }
704  if(pointsColor.empty() || pointsIr.empty())
705  {
706  OUT_ERROR("no data for calibration provided!");
707  return;
708  }
709  const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 100, DBL_EPSILON);
710  double error;
711 
712  OUT_INFO("Camera Matrix Color:" << std::endl << cameraMatrixColor);
713  OUT_INFO("Distortion Coeeficients Color:" << std::endl << distortionColor << std::endl);
714  OUT_INFO("Camera Matrix Ir:" << std::endl << cameraMatrixIr);
715  OUT_INFO("Distortion Coeeficients Ir:" << std::endl << distortionIr << std::endl);
716 
717  OUT_INFO("calibrating Color and Ir extrinsics...");
718 #if CV_MAJOR_VERSION == 2
719  error = cv::stereoCalibrate(pointsBoard, pointsIr, pointsColor, cameraMatrixIr, distortionIr, cameraMatrixColor, distortionColor, sizeColor,
720  rotation, translation, essential, fundamental, termCriteria, cv::CALIB_FIX_INTRINSIC);
721 #elif CV_MAJOR_VERSION == 3
722  error = cv::stereoCalibrate(pointsBoard, pointsIr, pointsColor, cameraMatrixIr, distortionIr, cameraMatrixColor, distortionColor, sizeColor,
723  rotation, translation, essential, fundamental, cv::CALIB_FIX_INTRINSIC, termCriteria);
724 #endif
725  OUT_INFO("re-projection error: " << error << std::endl);
726 
727  OUT_INFO("Rotation:" << std::endl << rotation);
728  OUT_INFO("Translation:" << std::endl << translation);
729  OUT_INFO("Essential:" << std::endl << essential);
730  OUT_INFO("Fundamental:" << std::endl << fundamental << std::endl);
731  }
732 
734  {
735  cv::FileStorage fs;
736 
737  switch(mode)
738  {
739  case SYNC:
740  fs.open(path + K2_CALIB_POSE, cv::FileStorage::WRITE);
741  break;
742  case COLOR:
743  fs.open(path + K2_CALIB_COLOR, cv::FileStorage::WRITE);
744  break;
745  case IR:
746  fs.open(path + K2_CALIB_IR, cv::FileStorage::WRITE);
747  break;
748  }
749 
750  if(!fs.isOpened())
751  {
752  OUT_ERROR("couldn't store calibration data!");
753  return;
754  }
755 
756  switch(mode)
757  {
758  case SYNC:
759  fs << K2_CALIB_ROTATION << rotation;
760  fs << K2_CALIB_TRANSLATION << translation;
761  fs << K2_CALIB_ESSENTIAL << essential;
762  fs << K2_CALIB_FUNDAMENTAL << fundamental;
763  break;
764  case COLOR:
765  fs << K2_CALIB_CAMERA_MATRIX << cameraMatrixColor;
766  fs << K2_CALIB_DISTORTION << distortionColor;
767  fs << K2_CALIB_ROTATION << rotationColor;
768  fs << K2_CALIB_PROJECTION << projectionColor;
769  break;
770  case IR:
771  fs << K2_CALIB_CAMERA_MATRIX << cameraMatrixIr;
772  fs << K2_CALIB_DISTORTION << distortionIr;
773  fs << K2_CALIB_ROTATION << rotationIr;
774  fs << K2_CALIB_PROJECTION << projectionIr;
775  break;
776  }
777  fs.release();
778  }
779 
781  {
782  cv::FileStorage fs;
783 
784  if(fs.open(path + K2_CALIB_COLOR, cv::FileStorage::READ))
785  {
786  fs[K2_CALIB_CAMERA_MATRIX] >> cameraMatrixColor;
787  fs[K2_CALIB_DISTORTION] >> distortionColor;
788  fs[K2_CALIB_ROTATION] >> rotationColor;
789  fs[K2_CALIB_PROJECTION] >> projectionColor;
790  fs.release();
791  }
792  else
793  {
794  OUT_ERROR("couldn't load color calibration data!");
795  return false;
796  }
797 
798  if(fs.open(path + K2_CALIB_IR, cv::FileStorage::READ))
799  {
800  fs[K2_CALIB_CAMERA_MATRIX] >> cameraMatrixIr;
801  fs[K2_CALIB_DISTORTION] >> distortionIr;
802  fs[K2_CALIB_ROTATION] >> rotationIr;
803  fs[K2_CALIB_PROJECTION] >> projectionIr;
804  fs.release();
805  }
806  else
807  {
808  OUT_ERROR("couldn't load ir calibration data!");
809  return false;
810  }
811 
812  return true;
813  }
814 };
815 
817 {
818 private:
819  const std::string path;
820 
821  std::vector<cv::Point3f> board;
822  std::vector<std::vector<cv::Point2f> > points;
823  std::vector<std::string> images;
824 
825  cv::Size size;
826 
827  cv::Mat cameraMatrix, distortion, rotation, translation;
828  cv::Mat mapX, mapY;
829 
830  double fx, fy, cx, cy;
831 
832  std::ofstream plot;
833 
834 public:
835  DepthCalibration(const std::string &path, const cv::Size &boardDims, const float boardSize)
836  : path(path), size(512, 424)
837  {
838  board.resize(boardDims.width * boardDims.height);
839  for(size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
840  {
841  for(size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
842  {
843  board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
844  }
845  }
846  }
847 
849  {
850  }
851 
852  bool restore()
853  {
854  std::vector<std::string> files;
855 
856  DIR *dp;
857  struct dirent *dirp;
858  size_t pos;
859 
860  if((dp = opendir(path.c_str())) == NULL)
861  {
862  OUT_ERROR("Error opening: " << path);
863  return false;
864  }
865 
866  while((dirp = readdir(dp)) != NULL)
867  {
868  std::string filename = dirp->d_name;
869 
870  if(dirp->d_type != DT_REG)
871  {
872  continue;
873  }
874 
875  /*pos = filename.rfind(CALIB_SYNC);
876  if(pos != std::string::npos)
877  {
878  continue;
879  }*/
880 
881  pos = filename.rfind(CALIB_FILE_IR_GREY);
882  if(pos != std::string::npos)
883  {
884  std::string frameName = filename.substr(0, pos);
885  files.push_back(frameName);
886  continue;
887  }
888  }
889  closedir(dp);
890 
891  std::sort(files.begin(), files.end());
892 
893  if(files.empty())
894  {
895  OUT_ERROR("no files found!");
896  return false;
897  }
898 
899  bool ret = readFiles(files);
900  ret = ret && loadCalibration();
901 
902  if(ret)
903  {
904  cv::initUndistortRectifyMap(cameraMatrix, distortion, cv::Mat(), cameraMatrix, size, CV_32FC1, mapX, mapY);
905  fx = cameraMatrix.at<double>(0, 0);
906  fy = cameraMatrix.at<double>(1, 1);
907  cx = cameraMatrix.at<double>(0, 2);
908  cy = cameraMatrix.at<double>(1, 2);
909  }
910  return ret;
911  }
912 
913  void calibrate()
914  {
915  plot.open(path + "plot.dat", std::ios_base::trunc);
916  if(!plot.is_open())
917  {
918  OUT_ERROR("couldn't open 'plot.dat'!");
919  return;
920  }
921  if(images.empty())
922  {
923  OUT_ERROR("no images found!");
924  return;
925  }
926 
927  plot << "# Columns:" << std::endl
928  << "# 1: X" << std::endl
929  << "# 2: Y" << std::endl
930  << "# 3: computed depth" << std::endl
931  << "# 4: measured depth" << std::endl
932  << "# 5: difference between computed and measured depth" << std::endl;
933 
934  std::vector<double> depthDists, imageDists;
935  for(size_t i = 0; i < images.size(); ++i)
936  {
937  OUT_INFO("frame: " << images[i]);
938  plot << "# frame: " << images[i] << std::endl;
939 
940  cv::Mat depth, planeNormal, region;
941  double planeDistance;
942  cv::Rect roi;
943 
944  depth = cv::imread(images[i], cv::IMREAD_ANYDEPTH);
945  if(depth.empty())
946  {
947  OUT_ERROR("couldn't load image '" << images[i] << "'!");
948  return;
949  }
950 
951  cv::remap(depth, depth, mapX, mapY, cv::INTER_NEAREST);
952  computeROI(depth, points[i], region, roi);
953 
954  getPlane(i, planeNormal, planeDistance);
955 
956  computePointDists(planeNormal, planeDistance, region, roi, depthDists, imageDists);
957  }
958  compareDists(imageDists, depthDists);
959  }
960 
961 private:
962  void compareDists(const std::vector<double> &imageDists, const std::vector<double> &depthDists) const
963  {
964  if(imageDists.size() != depthDists.size())
965  {
966  OUT_ERROR("number of real and computed distance samples does not match!");
967  return;
968  }
969  if(imageDists.empty() || depthDists.empty())
970  {
971  OUT_ERROR("no distance sample data!");
972  return;
973  }
974 
975  double avg = 0, sqavg = 0, var = 0, stddev = 0;
976  std::vector<double> diffs(imageDists.size());
977 
978  for(size_t i = 0; i < imageDists.size(); ++i)
979  {
980  diffs[i] = imageDists[i] - depthDists[i];
981  avg += diffs[i];
982  sqavg += diffs[i] * diffs[i];
983  }
984  sqavg = sqrt(sqavg / imageDists.size());
985  avg /= imageDists.size();
986 
987  for(size_t i = 0; i < imageDists.size(); ++i)
988  {
989  const double diff = diffs[i] - avg;
990  var += diff * diff;
991  }
992  var = var / (imageDists.size());
993  stddev = sqrt(var);
994 
995  std::sort(diffs.begin(), diffs.end());
996  OUT_INFO("stats on difference:" << std::endl
997  << " avg: " << avg << std::endl
998  << " var: " << var << std::endl
999  << " stddev: " << stddev << std::endl
1000  << " rms: " << sqavg << std::endl
1001  << " median: " << diffs[diffs.size() / 2]);
1002 
1003  storeCalibration(avg * 1000.0);
1004  }
1005 
1006  void computePointDists(const cv::Mat &normal, const double distance, const cv::Mat &region, const cv::Rect &roi, std::vector<double> &depthDists, std::vector<double> &imageDists)
1007  {
1008  for(int r = 0; r < region.rows; ++r)
1009  {
1010  const uint16_t *itD = region.ptr<uint16_t>(r);
1011  cv::Point p(roi.x, roi.y + r);
1012 
1013  for(int c = 0; c < region.cols; ++c, ++itD, ++p.x)
1014  {
1015  const double dDist = *itD / 1000.0;
1016 
1017  if(dDist < 0.1)
1018  {
1019  continue;
1020  }
1021 
1022  const double iDist = computeDistance(p, normal, distance);
1023  const double diff = iDist - dDist;
1024 
1025  if(std::abs(diff) > 0.08)
1026  {
1027  continue;
1028  }
1029  depthDists.push_back(dDist);
1030  imageDists.push_back(iDist);
1031  plot << p.x << ' ' << p.y << ' ' << iDist << ' ' << dDist << ' ' << diff << std::endl;
1032  }
1033  }
1034  }
1035 
1036  double computeDistance(const cv::Point &pointImage, const cv::Mat &normal, const double distance) const
1037  {
1038  cv::Mat point = cv::Mat(3, 1, CV_64F);
1039 
1040  point.at<double>(0) = (pointImage.x - cx) / fx;
1041  point.at<double>(1) = (pointImage.y - cy) / fy;
1042  point.at<double>(2) = 1;
1043 
1044  double t = distance / normal.dot(point);
1045  point = point * t;
1046 
1047  return point.at<double>(2);
1048  }
1049 
1050  void getPlane(const size_t index, cv::Mat &normal, double &distance) const
1051  {
1052  cv::Mat rvec, rotation, translation;
1053  //cv::solvePnP(board, points[index], cameraMatrix, distortion, rvec, translation, false, cv::EPNP);
1054 #if CV_MAJOR_VERSION == 2
1055  cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, board.size(), cv::noArray(), cv::ITERATIVE);
1056 #elif CV_MAJOR_VERSION == 3
1057  cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, 0.99, cv::noArray(), cv::SOLVEPNP_ITERATIVE);
1058 #endif
1059  cv::Rodrigues(rvec, rotation);
1060 
1061  normal = cv::Mat(3, 1, CV_64F);
1062  normal.at<double>(0) = 0;
1063  normal.at<double>(1) = 0;
1064  normal.at<double>(2) = 1;
1065  normal = rotation * normal;
1066  distance = normal.dot(translation);
1067  }
1068 
1069  void computeROI(const cv::Mat &depth, const std::vector<cv::Point2f> &points, cv::Mat &region, cv::Rect &roi) const
1070  {
1071  std::vector<cv::Point2f> norm;
1072  std::vector<cv::Point> undist, hull;
1073 
1074  cv::undistortPoints(points, norm, cameraMatrix, distortion);
1075  undist.reserve(norm.size());
1076 
1077  for(size_t i = 0; i < norm.size(); ++i)
1078  {
1079  cv::Point p;
1080  p.x = (int)round(norm[i].x * fx + cx);
1081  p.y = (int)round(norm[i].y * fy + cy);
1082  if(p.x >= 0 && p.x < depth.cols && p.y >= 0 && p.y < depth.rows)
1083  {
1084  undist.push_back(p);
1085  }
1086  }
1087 
1088  roi = cv::boundingRect(undist);
1089 
1090  cv::Mat mask = cv::Mat::zeros(depth.rows, depth.cols, CV_8U);
1091 
1092  cv::convexHull(undist, hull);
1093  cv::fillConvexPoly(mask, hull, CV_RGB(255, 255, 255));
1094 
1095  cv::Mat tmp;
1096  depth.copyTo(tmp, mask);
1097  tmp(roi).copyTo(region);
1098  }
1099 
1100  bool readFiles(const std::vector<std::string> &files)
1101  {
1102  points.resize(files.size());
1103  images.resize(files.size());
1104  bool ret = true;
1105 
1106  #pragma omp parallel for
1107  for(size_t i = 0; i < files.size(); ++i)
1108  {
1109  std::string pointsname = path + files[i] + CALIB_POINTS_IR;
1110 
1111  #pragma omp critical
1112  OUT_INFO("restoring file: " << files[i]);
1113 
1114  cv::FileStorage file(pointsname, cv::FileStorage::READ);
1115  if(!file.isOpened())
1116  {
1117  #pragma omp critical
1118  {
1119  OUT_ERROR("couldn't read '" << pointsname << "'!");
1120  ret = false;
1121  }
1122  }
1123  else
1124  {
1125  file["points"] >> points[i];
1126  file.release();
1127  images[i] = path + files[i] + CALIB_FILE_DEPTH;
1128  }
1129  }
1130  return ret;
1131  }
1132 
1134  {
1135  cv::FileStorage fs;
1136 
1137  if(fs.open(path + K2_CALIB_IR, cv::FileStorage::READ))
1138  {
1139  fs[K2_CALIB_CAMERA_MATRIX] >> cameraMatrix;
1140  fs[K2_CALIB_DISTORTION] >> distortion;
1141  fs.release();
1142  }
1143  else
1144  {
1145  OUT_ERROR("couldn't read calibration '" << path + K2_CALIB_IR << "'!");
1146  return false;
1147  }
1148 
1149  return true;
1150  }
1151 
1152  void storeCalibration(const double depthShift) const
1153  {
1154  cv::FileStorage fs;
1155 
1156  if(fs.open(path + K2_CALIB_DEPTH, cv::FileStorage::WRITE))
1157  {
1158  fs << K2_CALIB_DEPTH_SHIFT << depthShift;
1159  fs.release();
1160  }
1161  else
1162  {
1163  OUT_ERROR("couldn't store depth calibration!");
1164  }
1165  }
1166 };
1167 
1168 void help(const std::string &path)
1169 {
1170  std::cout << path << FG_BLUE " [options]" << std::endl
1171  << FG_GREEN " name" NO_COLOR ": " FG_YELLOW "'any string'" NO_COLOR " equals to the kinect2_bridge topic base name" << std::endl
1172  << FG_GREEN " mode" NO_COLOR ": " FG_YELLOW "'record'" NO_COLOR " or " FG_YELLOW "'calibrate'" << std::endl
1173  << FG_GREEN " source" NO_COLOR ": " FG_YELLOW "'color'" NO_COLOR ", " FG_YELLOW "'ir'" NO_COLOR ", " FG_YELLOW "'sync'" NO_COLOR ", " FG_YELLOW "'depth'" << std::endl
1174  << FG_GREEN " board" NO_COLOR ":" << std::endl
1175  << FG_YELLOW " 'circle<WIDTH>x<HEIGHT>x<SIZE>' " NO_COLOR "for symmetric circle grid" << std::endl
1176  << FG_YELLOW " 'acircle<WIDTH>x<HEIGHT>x<SIZE>' " NO_COLOR "for asymmetric circle grid" << std::endl
1177  << FG_YELLOW " 'chess<WIDTH>x<HEIGHT>x<SIZE>' " NO_COLOR "for chessboard pattern" << std::endl
1178  << FG_GREEN " distortion model" NO_COLOR ": " FG_YELLOW "'rational'" NO_COLOR " for using model with 8 instead of 5 coefficients" << std::endl
1179  << FG_GREEN " output path" NO_COLOR ": " FG_YELLOW "'-path <PATH>'" NO_COLOR << std::endl;
1180 }
1181 
1182 int main(int argc, char **argv)
1183 {
1184 #if EXTENDED_OUTPUT
1186  if(!getenv("ROSCONSOLE_FORMAT"))
1187  {
1189  ros::console::g_formatter.init("[${severity}] ${message}");
1190  }
1191 #endif
1192 
1193  Mode mode = RECORD;
1194  Source source = SYNC;
1195  bool circleBoard = false;
1196  bool symmetric = true;
1197  bool rational = false;
1198  bool calibDepth = false;
1199  cv::Size boardDims = cv::Size(7, 6);
1200  float boardSize = 0.108;
1201  std::string ns = K2_DEFAULT_NS;
1202  std::string path = "./";
1203 
1204  ros::init(argc, argv, "kinect2_calib", ros::init_options::AnonymousName);
1205 
1206  if(!ros::ok())
1207  {
1208  return 0;
1209  }
1210 
1211  for(int argI = 1; argI < argc; ++ argI)
1212  {
1213  std::string arg(argv[argI]);
1214 
1215  if(arg == "--help" || arg == "--h" || arg == "-h" || arg == "-?" || arg == "--?")
1216  {
1217  help(argv[0]);
1218  ros::shutdown();
1219  return 0;
1220  }
1221  else if(arg == "record")
1222  {
1223  mode = RECORD;
1224  }
1225  else if(arg == "calibrate")
1226  {
1227  mode = CALIBRATE;
1228  }
1229  else if(arg == "color")
1230  {
1231  source = COLOR;
1232  }
1233  else if(arg == "ir")
1234  {
1235  source = IR;
1236  }
1237  else if(arg == "sync")
1238  {
1239  source = SYNC;
1240  }
1241  else if(arg == "depth")
1242  {
1243  calibDepth = true;
1244  }
1245  else if(arg == "rational")
1246  {
1247  rational = true;
1248  }
1249  else if(arg.find("circle") == 0 && arg.find('x') != arg.rfind('x') && arg.rfind('x') != std::string::npos)
1250  {
1251  circleBoard = true;
1252  const size_t start = 6;
1253  const size_t leftX = arg.find('x');
1254  const size_t rightX = arg.rfind('x');
1255  const size_t end = arg.size();
1256 
1257  int width = atoi(arg.substr(start, leftX - start).c_str());
1258  int height = atoi(arg.substr(leftX + 1, rightX - leftX + 1).c_str());
1259  boardSize = atof(arg.substr(rightX + 1, end - rightX + 1).c_str());
1260  boardDims = cv::Size(width, height);
1261  }
1262  else if((arg.find("circle") == 0 || arg.find("acircle") == 0) && arg.find('x') != arg.rfind('x') && arg.rfind('x') != std::string::npos)
1263  {
1264  symmetric = arg.find("circle") == 0;
1265  circleBoard = true;
1266  const size_t start = 6 + (symmetric ? 0 : 1);
1267  const size_t leftX = arg.find('x');
1268  const size_t rightX = arg.rfind('x');
1269  const size_t end = arg.size();
1270 
1271  int width = atoi(arg.substr(start, leftX - start).c_str());
1272  int height = atoi(arg.substr(leftX + 1, rightX - leftX + 1).c_str());
1273  boardSize = atof(arg.substr(rightX + 1, end - rightX + 1).c_str());
1274  boardDims = cv::Size(width, height);
1275  }
1276  else if(arg.find("chess") == 0 && arg.find('x') != arg.rfind('x') && arg.rfind('x') != std::string::npos)
1277  {
1278  circleBoard = false;
1279  const size_t start = 5;
1280  const size_t leftX = arg.find('x');
1281  const size_t rightX = arg.rfind('x');
1282  const size_t end = arg.size();
1283 
1284  int width = atoi(arg.substr(start, leftX - start).c_str());
1285  int height = atoi(arg.substr(leftX + 1, rightX - leftX + 1).c_str());
1286  boardSize = atof(arg.substr(rightX + 1, end - rightX + 1).c_str());
1287  boardDims = cv::Size(width, height);
1288  }
1289  else if(arg == "-path" && ++argI < argc)
1290  {
1291  arg = argv[argI];
1292  struct stat fileStat;
1293  if(stat(arg.c_str(), &fileStat) == 0 && S_ISDIR(fileStat.st_mode))
1294  {
1295  path = arg;
1296  }
1297  else
1298  {
1299  OUT_ERROR("Unknown path: " << arg);
1300  help(argv[0]);
1301  ros::shutdown();
1302  return 0;
1303  }
1304  }
1305  else
1306  {
1307  ns = arg;
1308  }
1309  }
1310 
1311  std::string topicColor = "/" + ns + K2_TOPIC_HD + K2_TOPIC_IMAGE_MONO;
1312  std::string topicIr = "/" + ns + K2_TOPIC_SD + K2_TOPIC_IMAGE_IR;
1313  std::string topicDepth = "/" + ns + K2_TOPIC_SD + K2_TOPIC_IMAGE_DEPTH;
1314  OUT_INFO("Start settings:" << std::endl
1315  << " Mode: " FG_CYAN << (mode == RECORD ? "record" : "calibrate") << NO_COLOR << std::endl
1316  << " Source: " FG_CYAN << (calibDepth ? "depth" : (source == COLOR ? "color" : (source == IR ? "ir" : "sync"))) << NO_COLOR << std::endl
1317  << " Board: " FG_CYAN << (circleBoard ? "circles" : "chess") << NO_COLOR << std::endl
1318  << " Dimensions: " FG_CYAN << boardDims.width << " x " << boardDims.height << NO_COLOR << std::endl
1319  << " Field size: " FG_CYAN << boardSize << NO_COLOR << std::endl
1320  << "Dist. model: " FG_CYAN << (rational ? '8' : '5') << " coefficients" << NO_COLOR << std::endl
1321  << "Topic color: " FG_CYAN << topicColor << NO_COLOR << std::endl
1322  << " Topic ir: " FG_CYAN << topicIr << NO_COLOR << std::endl
1323  << "Topic depth: " FG_CYAN << topicDepth << NO_COLOR << std::endl
1324  << " Path: " FG_CYAN << path << NO_COLOR << std::endl);
1325 
1326  if(!ros::master::check())
1327  {
1328  OUT_ERROR("checking ros master failed.");
1329  return -1;
1330  }
1331  if(mode == RECORD)
1332  {
1333  Recorder recorder(path, topicColor, topicIr, topicDepth, source, circleBoard, symmetric, boardDims, boardSize);
1334 
1335  OUT_INFO("starting recorder...");
1336  recorder.run();
1337 
1338  OUT_INFO("stopped recording...");
1339  }
1340  else if(calibDepth)
1341  {
1342  DepthCalibration calib(path, boardDims, boardSize);
1343 
1344  OUT_INFO("restoring files...");
1345  calib.restore();
1346 
1347  OUT_INFO("starting calibration...");
1348  calib.calibrate();
1349  }
1350  else
1351  {
1352  CameraCalibration calib(path, source, circleBoard, boardDims, boardSize, rational);
1353 
1354  OUT_INFO("restoring files...");
1355  calib.restore();
1356 
1357  OUT_INFO("starting calibration...");
1358  calib.calibrate();
1359  }
1360 
1361  return 0;
1362 }
std::mutex lock
void calibrateIntrinsics(const cv::Size &size, const std::vector< std::vector< cv::Point3f > > &pointsBoard, const std::vector< std::vector< cv::Point2f > > &points, cv::Mat &cameraMatrix, cv::Mat &distortion, cv::Mat &rotation, cv::Mat &projection, std::vector< cv::Mat > &rvecs, std::vector< cv::Mat > &tvecs)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string topicIr
filename
ROSCPP_DECL bool check()
#define K2_CALIB_PROJECTION
#define K2_TOPIC_SD
void compareDists(const std::vector< double > &imageDists, const std::vector< double > &depthDists) const
CameraCalibration(const std::string &path, const Source mode, const bool circleBoard, const cv::Size &boardDims, const float boardSize, const bool rational)
const bool circleBoard
#define K2_TOPIC_IMAGE_IR
void storeCalibration(const double depthShift) const
#define FG_GREEN
#define K2_DEFAULT_NS
f
#define FG_YELLOW
int main(int argc, char **argv)
std::vector< cv::Point3f > board
#define K2_CALIB_CAMERA_MATRIX
const std::string path
#define K2_CALIB_DEPTH_SHIFT
#define CALIB_FILE_IR
#define K2_CALIB_POSE
void help(const std::string &path)
const std::string topicDepth
#define OUT_ERROR(msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
image_transport::SubscriberFilter * subImageDepth
std::vector< cv::Point3f > board
ros::NodeHandle nh
#define OUT_INFO(msg)
#define CALIB_POINTS_IR
#define ROSCONSOLE_AUTOINIT
void findMinMax(const cv::Mat &ir)
const std::string path
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::string > images
#define K2_CALIB_ESSENTIAL
std::vector< cv::Point2f > pointsIr
#define CALIB_POINTS_COLOR
cv::Ptr< cv::CLAHE > clahe
#define K2_CALIB_DEPTH
void init(const char *fmt)
void getPlane(const size_t index, cv::Mat &normal, double &distance) const
Connection registerCallback(C &callback)
#define K2_CALIB_TRANSLATION
Recorder(const std::string &path, const std::string &topicColor, const std::string &topicIr, const std::string &topicDepth, const Source mode, const bool circleBoard, const bool symmetric, const cv::Size &boardDims, const float boardSize)
const std::string topicColor
std::vector< std::vector< cv::Point3f > > pointsBoard
const std::string path
void store(const cv::Mat &color, const cv::Mat &ir, const cv::Mat &irGrey, const cv::Mat &depth, const std::vector< cv::Point2f > &pointsColor, std::vector< cv::Point2f > &pointsIr)
std::vector< cv::Mat > tvecsIr
std::vector< cv::Mat > tvecsColor
#define K2_TOPIC_IMAGE_MONO
ROSCPP_DECL bool ok()
message_filters::Synchronizer< ColorIrDepthSyncPolicy > * sync
#define K2_CALIB_IR
TFSIMD_FORCE_INLINE const tfScalar & x() const
DepthCalibration(const std::string &path, const cv::Size &boardDims, const float boardSize)
#define K2_CALIB_DISTORTION
const float boardSize
std::vector< cv::Point3f > board
const cv::Size boardDims
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
#define K2_TOPIC_IMAGE_DEPTH
ros::AsyncSpinner spinner
bool readFiles(const std::vector< std::string > &files, const std::string &ext, std::vector< std::vector< cv::Point2f > > &points) const
#define CALIB_FILE_COLOR
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > ColorIrDepthSyncPolicy
void computePointDists(const cv::Mat &normal, const double distance, const cv::Mat &region, const cv::Rect &roi, std::vector< double > &depthDists, std::vector< double > &imageDists)
#define FG_BLUE
std::vector< std::vector< cv::Point2f > > pointsIr
#define K2_CALIB_FUNDAMENTAL
std::vector< cv::Point2f > pointsColor
void convertIr(const cv::Mat &ir, cv::Mat &grey)
bool readFiles(const std::vector< std::string > &files)
std::vector< std::vector< cv::Point2f > > points
#define CALIB_FILE_IR_GREY
#define K2_CALIB_ROTATION
#define FG_CYAN
void findMinMax(const cv::Mat &ir, const std::vector< cv::Point2f > &pointsIr)
void readImage(const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
std::vector< std::vector< cv::Point2f > > pointsColor
#define NO_COLOR
void callback(const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageIr, const sensor_msgs::Image::ConstPtr imageDepth)
ROSCPP_DECL void shutdown()
const Source mode
ROSCONSOLE_DECL Formatter g_formatter
double computeDistance(const cv::Point &pointImage, const cv::Mat &normal, const double distance) const
image_transport::ImageTransport it
#define K2_CALIB_COLOR
std::vector< int > params
#define CALIB_FILE_DEPTH
image_transport::SubscriberFilter * subImageIr
#define K2_TOPIC_HD
void computeROI(const cv::Mat &depth, const std::vector< cv::Point2f > &points, cv::Mat &region, cv::Rect &roi) const
image_transport::SubscriberFilter * subImageColor


kinect2_calibration
Author(s):
autogenerated on Wed Jan 3 2018 03:48:10