31 #include <opencv2/opencv.hpp> 35 #include <sensor_msgs/CameraInfo.h> 36 #include <sensor_msgs/Image.h> 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)
106 circleFlags = cv::CALIB_CB_SYMMETRIC_GRID + cv::CALIB_CB_CLUSTERING;
110 circleFlags = cv::CALIB_CB_ASYMMETRIC_GRID + cv::CALIB_CB_CLUSTERING;
113 params.push_back(CV_IMWRITE_PNG_COMPRESSION);
116 board.resize(boardDims.width * boardDims.height);
117 for(
size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
119 for(
size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
121 board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
125 clahe = cv::createCLAHE(1.5, cv::Size(32, 32));
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
177 const float factor = 255.0f / (maxIr -
minIr);
178 grey.create(ir.rows, ir.cols, CV_8U);
180 #pragma omp parallel for 181 for(
size_t r = 0; r < (size_t)ir.rows; ++r)
183 const uint16_t *itI = ir.ptr<uint16_t>(r);
184 uint8_t *itO = grey.ptr<uint8_t>(r);
186 for(
size_t c = 0; c < (size_t)ir.cols; ++c, ++itI, ++itO)
188 *itO = std::min(std::max(*itI - minIr, 0) * factor, 255.0
f);
191 clahe->apply(grey, grey);
194 void findMinMax(
const cv::Mat &ir,
const std::vector<cv::Point2f> &pointsIr)
198 for(
size_t i = 0; i < pointsIr.size(); ++i)
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);
211 for(
size_t r = 0; r < (size_t)ir.rows; ++r)
213 const uint16_t *it = ir.ptr<uint16_t>(r);
215 for(
size_t c = 0; c < (size_t)ir.cols; ++c, ++it)
217 minIr = std::min(minIr, (
int) * it);
218 maxIr = std::max(maxIr, (
int) * it);
223 void callback(
const sensor_msgs::Image::ConstPtr imageColor,
const sensor_msgs::Image::ConstPtr imageIr,
const sensor_msgs::Image::ConstPtr imageDepth)
227 bool foundColor =
false;
228 bool foundIr =
false;
234 if(mode ==
IR || mode ==
SYNC)
238 cv::resize(ir, irScaled, cv::Size(), 2.0, 2.0, cv::INTER_CUBIC);
248 foundColor = cv::findCirclesGrid(color, boardDims, pointsColor, circleFlags);
251 foundIr = cv::findCirclesGrid(irGrey, boardDims, pointsIr, circleFlags);
254 foundColor = cv::findCirclesGrid(color, boardDims, pointsColor, circleFlags);
255 foundIr = cv::findCirclesGrid(irGrey, boardDims, pointsIr, circleFlags);
261 const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::COUNT, 100, DBL_EPSILON);
265 foundColor = cv::findChessboardCorners(color, boardDims, pointsColor, cv::CALIB_CB_FAST_CHECK);
268 foundIr = cv::findChessboardCorners(irGrey, boardDims, pointsIr, cv::CALIB_CB_ADAPTIVE_THRESH);
271 foundColor = cv::findChessboardCorners(color, boardDims, pointsColor, cv::CALIB_CB_FAST_CHECK);
272 foundIr = cv::findChessboardCorners(irGrey, boardDims, pointsIr, cv::CALIB_CB_ADAPTIVE_THRESH);
277 cv::cornerSubPix(color, pointsColor, cv::Size(11, 11), cv::Size(-1, -1), termCriteria);
281 cv::cornerSubPix(irGrey, pointsIr, cv::Size(11, 11), cv::Size(-1, -1), termCriteria);
308 cv::Mat colorDisp, irDisp;
309 bool foundColor =
false;
310 bool foundIr =
false;
314 std::chrono::milliseconds duration(1);
317 std::this_thread::sleep_for(duration);
338 cv::cvtColor(color, colorDisp, CV_GRAY2BGR);
339 cv::drawChessboardCorners(colorDisp, boardDims, pointsColor, foundColor);
343 if(mode ==
IR || mode ==
SYNC)
345 cv::cvtColor(irGrey, irDisp, CV_GRAY2BGR);
346 cv::drawChessboardCorners(irDisp, boardDims, pointsIr, foundIr);
355 cv::imshow(
"color", colorDisp);
358 cv::imshow(
"ir", irDisp);
361 cv::imshow(
"color", colorDisp);
362 cv::imshow(
"ir", irDisp);
366 int key = cv::waitKey(10);
378 minIr = std::max(0, minIr - 100);
381 minIr = std::min(maxIr - 1, minIr + 100);
384 maxIr = std::max(minIr + 1, maxIr - 100);
387 maxIr = std::min(0xFFFF, maxIr + 100);
390 minIr = std::max(0, minIr - 100);
391 maxIr = std::max(minIr + 1, maxIr - 100);
394 maxIr = std::min(0x7FFF, maxIr + 100);
395 minIr = std::min(maxIr - 1, minIr + 100);
399 if(save && ((mode ==
COLOR && foundColor) || (mode ==
IR && foundIr) || (mode ==
SYNC && foundColor && foundIr)))
401 store(color, ir, irGrey, depth, pointsColor, pointsIr);
405 cv::destroyAllWindows();
409 void readImage(
const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image)
const 413 pCvImage->image.copyTo(image);
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)
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;
424 for(
size_t i = 0; i < pointsIr.size(); ++i)
426 pointsIr[i].x /= 2.0;
427 pointsIr[i].y /= 2.0;
443 if(mode ==
IR || mode ==
SYNC)
475 cv::Mat cameraMatrixColor, distortionColor, rotationColor,
translationColor, projectionColor;
476 cv::Mat cameraMatrixIr, distortionIr, rotationIr,
translationIr, projectionIr;
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)
486 board.resize(boardDims.width * boardDims.height);
487 for(
size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
489 for(
size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
491 board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
502 std::vector<std::string> filesSync;
503 std::vector<std::string> filesColor;
504 std::vector<std::string> filesIr;
508 size_t posColor, posIr, posSync;
510 if((dp = opendir(path.c_str())) == NULL)
516 while((dirp = readdir(dp)) != NULL)
518 std::string
filename = dirp->d_name;
520 if(dirp->d_type != DT_REG)
528 if(posSync != std::string::npos)
530 if(posColor != std::string::npos)
532 std::string frameName = filename.substr(0, posColor);
533 filesSync.push_back(frameName);
534 filesColor.push_back(frameName);
535 filesIr.push_back(frameName);
540 if(posColor != std::string::npos)
542 std::string frameName = filename.substr(0, posColor);
543 filesColor.push_back(frameName);
548 if(posIr != std::string::npos)
550 std::string frameName = filename.substr(0, posIr);
551 filesIr.push_back(frameName);
557 std::sort(filesColor.begin(), filesColor.end());
558 std::sort(filesIr.begin(), filesIr.end());
559 std::sort(filesSync.begin(), filesSync.end());
565 if(filesColor.empty())
570 pointsColor.resize(filesColor.size());
571 pointsBoard.resize(filesColor.size(),
board);
580 pointsIr.resize(filesIr.size());
581 pointsBoard.resize(filesIr.size(),
board);
585 if(filesColor.empty() || filesIr.empty())
590 pointsColor.resize(filesColor.size());
591 pointsIr.resize(filesSync.size());
592 pointsColor.resize(filesSync.size());
593 pointsBoard.resize(filesSync.size(),
board);
596 ret = ret && checkSyncPointsOrder();
597 ret = ret && loadCalibration();
608 calibrateIntrinsics(sizeColor, pointsBoard, pointsColor, cameraMatrixColor, distortionColor, rotationColor, projectionColor, rvecsColor, tvecsColor);
611 calibrateIntrinsics(sizeIr, pointsBoard, pointsIr, cameraMatrixIr, distortionIr, rotationIr, projectionIr, rvecsIr, tvecsIr);
614 calibrateExtrinsics();
621 bool readFiles(
const std::vector<std::string> &files,
const std::string &ext, std::vector<std::vector<cv::Point2f> > &points)
const 624 #pragma omp parallel for 625 for(
size_t i = 0; i < files.size(); ++i)
627 std::string pointsname = path + files[i] + ext;
630 OUT_INFO(
"restoring file: " << files[i] << ext);
632 cv::FileStorage file(pointsname, cv::FileStorage::READ);
638 OUT_ERROR(
"couldn't open file: " << files[i] << ext);
643 file[
"points"] >> points[i];
651 if(pointsColor.size() != pointsIr.size())
653 OUT_ERROR(
"number of detected color and ir patterns does not match!");
657 for(
size_t i = 0; i < pointsColor.size(); ++i)
659 const std::vector<cv::Point2f> &pColor = pointsColor[i];
660 const std::vector<cv::Point2f> &pIr = pointsIr[i];
662 if(pColor.front().y > pColor.back().y || pColor.front().x > pColor.back().x)
664 std::reverse(pointsColor[i].begin(), pointsColor[i].end());
667 if(pIr.front().y > pIr.back().y || pIr.front().x > pIr.back().x)
669 std::reverse(pointsIr[i].begin(), pointsIr[i].end());
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)
680 OUT_ERROR(
"no data for calibration provided!");
683 const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 50, DBL_EPSILON);
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);
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)));
699 if(pointsColor.size() != pointsIr.size())
701 OUT_ERROR(
"number of detected color and ir patterns does not match!");
704 if(pointsColor.empty() || pointsIr.empty())
706 OUT_ERROR(
"no data for calibration provided!");
709 const cv::TermCriteria termCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 100, DBL_EPSILON);
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);
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);
725 OUT_INFO(
"re-projection error: " << error << std::endl);
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);
746 fs.open(path +
K2_CALIB_IR, cv::FileStorage::WRITE);
752 OUT_ERROR(
"couldn't store calibration data!");
794 OUT_ERROR(
"couldn't load color calibration data!");
798 if(fs.open(path +
K2_CALIB_IR, cv::FileStorage::READ))
808 OUT_ERROR(
"couldn't load ir calibration data!");
822 std::vector<std::vector<cv::Point2f> >
points;
830 double fx,
fy, cx, cy;
836 : path(path), size(512, 424)
838 board.resize(boardDims.width * boardDims.height);
839 for(
size_t r = 0, i = 0; r < (size_t)boardDims.height; ++r)
841 for(
size_t c = 0; c < (size_t)boardDims.width; ++c, ++i)
843 board[i] = cv::Point3f(c * boardSize, r * boardSize, 0);
854 std::vector<std::string> files;
860 if((dp = opendir(path.c_str())) == NULL)
866 while((dirp = readdir(dp)) != NULL)
868 std::string
filename = dirp->d_name;
870 if(dirp->d_type != DT_REG)
882 if(pos != std::string::npos)
884 std::string frameName = filename.substr(0, pos);
885 files.push_back(frameName);
891 std::sort(files.begin(), files.end());
899 bool ret = readFiles(files);
900 ret = ret && loadCalibration();
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);
915 plot.open(path +
"plot.dat", std::ios_base::trunc);
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;
934 std::vector<double> depthDists, imageDists;
935 for(
size_t i = 0; i < images.size(); ++i)
938 plot <<
"# frame: " << images[i] << std::endl;
940 cv::Mat
depth, planeNormal, region;
941 double planeDistance;
944 depth = cv::imread(images[i], cv::IMREAD_ANYDEPTH);
947 OUT_ERROR(
"couldn't load image '" << images[i] <<
"'!");
951 cv::remap(depth, depth, mapX, mapY, cv::INTER_NEAREST);
952 computeROI(depth, points[i], region, roi);
954 getPlane(i, planeNormal, planeDistance);
956 computePointDists(planeNormal, planeDistance, region, roi, depthDists, imageDists);
958 compareDists(imageDists, depthDists);
962 void compareDists(
const std::vector<double> &imageDists,
const std::vector<double> &depthDists)
const 964 if(imageDists.size() != depthDists.size())
966 OUT_ERROR(
"number of real and computed distance samples does not match!");
969 if(imageDists.empty() || depthDists.empty())
975 double avg = 0, sqavg = 0, var = 0, stddev = 0;
976 std::vector<double> diffs(imageDists.size());
978 for(
size_t i = 0; i < imageDists.size(); ++i)
980 diffs[i] = imageDists[i] - depthDists[i];
982 sqavg += diffs[i] * diffs[i];
984 sqavg =
sqrt(sqavg / imageDists.size());
985 avg /= imageDists.size();
987 for(
size_t i = 0; i < imageDists.size(); ++i)
989 const double diff = diffs[i] - avg;
992 var = var / (imageDists.size());
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]);
1003 storeCalibration(avg * 1000.0);
1006 void computePointDists(
const cv::Mat &normal,
const double distance,
const cv::Mat ®ion,
const cv::Rect &roi, std::vector<double> &depthDists, std::vector<double> &imageDists)
1008 for(
int r = 0; r < region.rows; ++r)
1010 const uint16_t *itD = region.ptr<uint16_t>(r);
1011 cv::Point p(roi.x, roi.y + r);
1013 for(
int c = 0; c < region.cols; ++c, ++itD, ++p.x)
1015 const double dDist = *itD / 1000.0;
1022 const double iDist = computeDistance(p, normal, distance);
1023 const double diff = iDist - dDist;
1025 if(std::abs(diff) > 0.08)
1029 depthDists.push_back(dDist);
1030 imageDists.push_back(iDist);
1031 plot << p.x <<
' ' << p.y <<
' ' << iDist <<
' ' << dDist <<
' ' << diff << std::endl;
1036 double computeDistance(
const cv::Point &pointImage,
const cv::Mat &normal,
const double distance)
const 1038 cv::Mat point = cv::Mat(3, 1, CV_64F);
1040 point.at<
double>(0) = (pointImage.x - cx) / fx;
1041 point.at<
double>(1) = (pointImage.y - cy) / fy;
1042 point.at<
double>(2) = 1;
1044 double t = distance / normal.dot(point);
1047 return point.at<
double>(2);
1050 void getPlane(
const size_t index, cv::Mat &normal,
double &distance)
const 1052 cv::Mat rvec, rotation, translation;
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);
1059 cv::Rodrigues(rvec, rotation);
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);
1069 void computeROI(
const cv::Mat &
depth,
const std::vector<cv::Point2f> &points, cv::Mat ®ion, cv::Rect &roi)
const 1071 std::vector<cv::Point2f> norm;
1072 std::vector<cv::Point> undist, hull;
1074 cv::undistortPoints(points, norm, cameraMatrix, distortion);
1075 undist.reserve(norm.size());
1077 for(
size_t i = 0; i < norm.size(); ++i)
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)
1084 undist.push_back(p);
1088 roi = cv::boundingRect(undist);
1090 cv::Mat mask = cv::Mat::zeros(depth.rows, depth.cols, CV_8U);
1092 cv::convexHull(undist, hull);
1093 cv::fillConvexPoly(mask, hull, CV_RGB(255, 255, 255));
1096 depth.copyTo(tmp, mask);
1097 tmp(roi).copyTo(region);
1102 points.resize(files.size());
1103 images.resize(files.size());
1106 #pragma omp parallel for 1107 for(
size_t i = 0; i < files.size(); ++i)
1111 #pragma omp critical 1112 OUT_INFO(
"restoring file: " << files[i]);
1114 cv::FileStorage file(pointsname, cv::FileStorage::READ);
1115 if(!file.isOpened())
1117 #pragma omp critical 1119 OUT_ERROR(
"couldn't read '" << pointsname <<
"'!");
1125 file[
"points"] >> points[i];
1137 if(fs.open(path +
K2_CALIB_IR, cv::FileStorage::READ))
1163 OUT_ERROR(
"couldn't store depth calibration!");
1170 std::cout << path <<
FG_BLUE " [options]" << 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
1186 if(!getenv(
"ROSCONSOLE_FORMAT"))
1196 bool symmetric =
true;
1197 bool rational =
false;
1198 bool calibDepth =
false;
1202 std::string
path =
"./";
1211 for(
int argI = 1; argI < argc; ++ argI)
1213 std::string arg(argv[argI]);
1215 if(arg ==
"--help" || arg ==
"--h" || arg ==
"-h" || arg ==
"-?" || arg ==
"--?")
1221 else if(arg ==
"record")
1225 else if(arg ==
"calibrate")
1229 else if(arg ==
"color")
1233 else if(arg ==
"ir")
1237 else if(arg ==
"sync")
1241 else if(arg ==
"depth")
1245 else if(arg ==
"rational")
1249 else if(arg.find(
"circle") == 0 && arg.find(
'x') != arg.rfind(
'x') && arg.rfind(
'x') != std::string::npos)
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();
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);
1262 else if((arg.find(
"circle") == 0 || arg.find(
"acircle") == 0) && arg.find(
'x') != arg.rfind(
'x') && arg.rfind(
'x') != std::string::npos)
1264 symmetric = arg.find(
"circle") == 0;
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();
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);
1276 else if(arg.find(
"chess") == 0 && arg.find(
'x') != arg.rfind(
'x') && arg.rfind(
'x') != std::string::npos)
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();
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);
1289 else if(arg ==
"-path" && ++argI < argc)
1292 struct stat fileStat;
1293 if(stat(arg.c_str(), &fileStat) == 0 && S_ISDIR(fileStat.st_mode))
1314 OUT_INFO(
"Start settings:" << 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
1320 <<
"Dist. model: " FG_CYAN << (rational ?
'8' :
'5') <<
" coefficients" <<
NO_COLOR << std::endl
1328 OUT_ERROR(
"checking ros master failed.");
1333 Recorder recorder(path, topicColor, topicIr, topicDepth, source, circleBoard, symmetric, boardDims, boardSize);
1347 OUT_INFO(
"starting calibration...");
1352 CameraCalibration calib(path, source, circleBoard, boardDims, boardSize, rational);
1357 OUT_INFO(
"starting calibration...");
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
#define K2_CALIB_PROJECTION
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)
#define K2_TOPIC_IMAGE_IR
void storeCalibration(const double depthShift) const
int main(int argc, char **argv)
std::vector< cv::Point3f > board
#define K2_CALIB_CAMERA_MATRIX
#define K2_CALIB_DEPTH_SHIFT
void help(const std::string &path)
const std::string topicDepth
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
#define ROSCONSOLE_AUTOINIT
void findMinMax(const cv::Mat &ir)
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
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
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
message_filters::Synchronizer< ColorIrDepthSyncPolicy > * sync
TFSIMD_FORCE_INLINE const tfScalar & x() const
DepthCalibration(const std::string &path, const cv::Size &boardDims, const float boardSize)
#define K2_CALIB_DISTORTION
std::vector< cv::Point3f > board
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
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 ®ion, const cv::Rect &roi, std::vector< double > &depthDists, std::vector< double > &imageDists)
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
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
void calibrateExtrinsics()
void callback(const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageIr, const sensor_msgs::Image::ConstPtr imageDepth)
ROSCPP_DECL void shutdown()
bool checkSyncPointsOrder()
ROSCONSOLE_DECL Formatter g_formatter
double computeDistance(const cv::Point &pointImage, const cv::Mat &normal, const double distance) const
image_transport::ImageTransport it
std::vector< int > params
image_transport::SubscriberFilter * subImageIr
void computeROI(const cv::Mat &depth, const std::vector< cv::Point2f > &points, cv::Mat ®ion, cv::Rect &roi) const
image_transport::SubscriberFilter * subImageColor