31 #include "Image/ByteImage.h"
32 #include "Image/ImageProcessor.h"
33 #include "Image/IplImageAdaptor.h"
35 #include <opencv2/opencv.hpp>
45 #include <opencv2/core.hpp>
46 #include <opencv2/core/utility.hpp>
47 #include <opencv2/imgproc.hpp>
48 #include <opencv2/calib3d.hpp>
49 #include <opencv2/imgcodecs.hpp>
50 #include <opencv2/videoio.hpp>
51 #include <opencv2/highgui.hpp>
71 static double computeReprojectionErrors(
const std::vector<std::vector<cv::Point3f> >& objectPoints,
72 const std::vector<std::vector<cv::Point2f> >& imagePoints,
73 const std::vector<cv::Mat>& rvecs,
const std::vector<cv::Mat>& tvecs,
74 const cv::Mat& cameraMatrix,
const cv::Mat& distCoeffs,
75 std::vector<float>& perViewErrors)
77 std::vector<cv::Point2f> imagePoints2;
78 size_t totalPoints = 0;
79 double totalErr = 0, err;
80 perViewErrors.resize(objectPoints.size());
82 for (
size_t i = 0; i < objectPoints.size(); ++i)
84 cv::projectPoints(objectPoints[i], rvecs[i], tvecs[i], cameraMatrix, distCoeffs, imagePoints2);
85 err =
cv::norm(imagePoints[i], imagePoints2, cv::NORM_L2);
87 size_t n = objectPoints[i].size();
89 totalErr += err * err;
97 static void calcBoardCornerPositions(cv::Size boardSize,
float squareSize, std::vector<cv::Point3f>& corners,
106 for (
int i = 0; i < boardSize.height; ++i)
107 for (
int j = 0; j < boardSize.width; ++j)
109 corners.push_back(cv::Point3f(j * squareSize, i * squareSize, 0));
114 for (
int i = 0; i < boardSize.height; i++)
115 for (
int j = 0; j < boardSize.width; j++)
117 corners.push_back(cv::Point3f((2 * j + i % 2)*squareSize, i * squareSize, 0));
126 static bool runCalibration(
visionx::Settings&
s, cv::Size& imageSize, cv::Mat& cameraMatrix, cv::Mat& distCoeffs,
127 std::vector<std::vector<cv::Point2f>> imagePoints, std::vector<cv::Mat>& rvecs, std::vector<cv::Mat>& tvecs,
128 std::vector<float>& reprojErrs,
double& totalAvgErr)
131 cameraMatrix = cv::Mat::eye(3, 3, CV_64F);
132 if (
s.flag & cv::CALIB_FIX_ASPECT_RATIO)
134 cameraMatrix.at<
double>(0, 0) =
s.aspectRatio;
137 distCoeffs = cv::Mat::zeros(8, 1, CV_64F);
139 std::vector<std::vector<cv::Point3f> > objectPoints(1);
140 calcBoardCornerPositions(
s.boardSize,
s.squareSize, objectPoints[0],
s.calibrationPattern);
142 objectPoints.resize(imagePoints.size(), objectPoints[0]);
147 rms = cv::calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix, distCoeffs, rvecs, tvecs,
150 ARMARX_INFO <<
"Re-projection error reported by calibrateCamera: " << rms;
152 bool ok = cv::checkRange(cameraMatrix) && cv::checkRange(distCoeffs);
154 totalAvgErr = computeReprojectionErrors(objectPoints, imagePoints, rvecs, tvecs, cameraMatrix,
155 distCoeffs, reprojErrs);
161 static void saveCameraParams(
visionx::Settings&
s, cv::Size& imageSize, cv::Mat& cameraMatrix, cv::Mat& distCoeffs,
162 const std::vector<cv::Mat>& rvecs,
const std::vector<cv::Mat>& tvecs,
163 const std::vector<float>& reprojErrs,
const std::vector<std::vector<cv::Point2f> >& imagePoints,
166 cv::FileStorage fs(
s.outputFileName, cv::FileStorage::WRITE);
170 struct tm* t2 = localtime(&tm);
172 strftime(buf,
sizeof(buf),
"%c", t2);
174 fs <<
"calibration_time" << buf;
176 if (!rvecs.empty() || !reprojErrs.empty())
178 fs <<
"nr_of_frames" << (int)
std::max(rvecs.size(), reprojErrs.size());
180 fs <<
"image_width" << imageSize.width;
181 fs <<
"image_height" << imageSize.height;
182 fs <<
"board_width" <<
s.boardSize.width;
183 fs <<
"board_height" <<
s.boardSize.height;
184 fs <<
"square_size" <<
s.squareSize;
186 if (
s.flag & cv::CALIB_FIX_ASPECT_RATIO)
188 fs <<
"fix_aspect_ratio" <<
s.aspectRatio;
193 std::stringstream flagsStringStream;
195 flagsStringStream <<
"flags:"
196 << (
s.flag & cv::CALIB_USE_INTRINSIC_GUESS ?
" +use_intrinsic_guess" :
"")
197 << (
s.flag & cv::CALIB_FIX_ASPECT_RATIO ?
" +fix_aspectRatio" :
"")
198 << (
s.flag & cv::CALIB_FIX_PRINCIPAL_POINT ?
" +fix_principal_point" :
"")
199 << (
s.flag & cv::CALIB_ZERO_TANGENT_DIST ?
" +zero_tangent_dist" :
"")
200 << (
s.flag & cv::CALIB_FIX_K1 ?
" +fix_k1" :
"")
201 << (
s.flag & cv::CALIB_FIX_K2 ?
" +fix_k2" :
"")
202 << (
s.flag & cv::CALIB_FIX_K3 ?
" +fix_k3" :
"")
203 << (
s.flag & cv::CALIB_FIX_K4 ?
" +fix_k4" :
"")
204 << (
s.flag & cv::CALIB_FIX_K5 ?
" +fix_k5" :
"")
205 << (
s.flag & cv::CALIB_FIX_K6 ?
" +fix_k6" :
"");
207 fs.writeComment(flagsStringStream.str());
210 fs <<
"flags" <<
s.flag;
212 fs <<
"camera_matrix" << cameraMatrix;
213 fs <<
"distortion_coefficients" << distCoeffs;
215 fs <<
"avg_reprojection_error" << totalAvgErr;
216 if (
s.writeExtrinsics && !reprojErrs.empty())
218 fs <<
"per_view_reprojection_errors" << cv::Mat(reprojErrs);
221 if (
s.writeExtrinsics && !rvecs.empty() && !tvecs.empty())
223 CV_Assert(rvecs[0].type() == tvecs[0].type());
224 cv::Mat bigmat((
int)rvecs.size(), 6, CV_MAKETYPE(rvecs[0].type(), 1));
225 bool needReshapeR = rvecs[0].depth() != 1 ? true :
false;
226 bool needReshapeT = tvecs[0].depth() != 1 ? true :
false;
228 for (
size_t i = 0; i < rvecs.size(); i++)
230 cv::Mat r = bigmat(cv::Range(
int(i),
int(i + 1)), cv::Range(0, 3));
231 cv::Mat t = bigmat(cv::Range(
int(i),
int(i + 1)), cv::Range(3, 6));
235 rvecs[i].reshape(1, 1).copyTo(r);
240 CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1);
246 tvecs[i].reshape(1, 1).copyTo(t);
250 CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1);
254 fs.writeComment(
"a set of 6-tuples (rotation vector + translation vector) for each view");
255 fs <<
"extrinsic_parameters" << bigmat;
258 if (
s.writePoints && !imagePoints.empty())
260 cv::Mat imagePtMat((
int)imagePoints.size(), (
int)imagePoints[0].size(), CV_32FC2);
261 for (
size_t i = 0; i < imagePoints.size(); i++)
263 cv::Mat r = imagePtMat.row(
int(i)).reshape(2, imagePtMat.cols);
264 cv::Mat imgpti(imagePoints[i]);
267 fs <<
"image_points" << imagePtMat;
271 bool runCalibrationAndSave(
visionx::Settings&
s, cv::Size imageSize, cv::Mat& cameraMatrix, cv::Mat& distCoeffs,
272 std::vector<std::vector<cv::Point2f> > imagePoints)
274 std::vector<cv::Mat> rvecs, tvecs;
275 std::vector<float> reprojErrs;
276 double totalAvgErr = 0;
278 bool ok = runCalibration(
s, imageSize, cameraMatrix, distCoeffs, imagePoints, rvecs, tvecs, reprojErrs,
280 ARMARX_INFO << (
ok ?
"Calibration succeeded" :
"Calibration failed")
281 <<
". avg re projection error = " << totalAvgErr;
284 saveCameraParams(
s, imageSize, cameraMatrix, distCoeffs, rvecs, tvecs, reprojErrs, imagePoints,
300 providerName = getProperty<std::string>(
"ImageProviderAdapterName").getValue();
304 waitingTimeBetweenCaptures = IceUtil::Time::milliSeconds(getProperty<int>(
"WaitingIntervalBetweenImages"));
305 std::string image_side = getProperty<std::string>(
"ImageToUse").getValue();
306 if (image_side ==
"left")
310 else if (image_side ==
"right")
316 throw std::runtime_error(
"ImageToUse must be either left or right");
324 imageProviderPrx = getProxy<ImageProviderInterfacePrx>(providerName);
325 StereoCalibrationInterfacePrx calibrationProvider = StereoCalibrationInterfacePrx::checkedCast(imageProviderInfo.
proxy);
326 auto cam = calibrationProvider->getStereoCalibration();
327 auto calib = imageID == 0 ? cam.calibrationLeft : cam.calibrationRight;
328 auto focal_lengths = calib.cameraParam.focalLength;
330 cameraImages =
new CByteImage*[2];
344 if (getProperty<bool>(
"EnableFixAspectRatio"))
346 m_settings.
aspectRatio = focal_lengths.at(0) / focal_lengths.at(1);
366 throw std::runtime_error(
"Invalid input detected. Application stopping.");
370 << m_settings.
boardSize.height <<
" squares with square size of "
377 delete cameraImages[0];
378 delete cameraImages[1];
379 delete[] cameraImages;
398 if (IceUtil::Time::now() - timeOfLastCapture < waitingTimeBetweenCaptures)
403 ARMARX_INFO <<
"Capturing image for calibration #" << imagePoints.size();
405 timeOfLastCapture = IceUtil::Time::now();
409 if (m_mode == CAPTURING && imagePoints.size() >= (
size_t) m_settings.
nrFrames)
412 if (runCalibrationAndSave(m_settings, imageSize, cameraMatrix, distCoeffs, imagePoints))
419 imageSize = view.size();
422 cv::flip(view, view, 0);
426 std::vector<cv::Point2f> pointBuf;
430 int chessBoardFlags = cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_NORMALIZE_IMAGE | cv::CALIB_CB_FAST_CHECK;
436 found = cv::findChessboardCorners(view, m_settings.
boardSize, pointBuf, chessBoardFlags);
439 found = cv::findCirclesGrid(view, m_settings.
boardSize, pointBuf);
442 found = cv::findCirclesGrid(view, m_settings.
boardSize, pointBuf, cv::CALIB_CB_ASYMMETRIC_GRID);
457 cv::cvtColor(view, viewGray, cv::COLOR_BGR2GRAY);
458 cv::cornerSubPix(viewGray, pointBuf, cv::Size(11, 11),
462 if (m_mode == CAPTURING)
464 imagePoints.push_back(pointBuf);
468 cv::drawChessboardCorners(view, m_settings.
boardSize, cv::Mat(pointBuf), found);