CalibrationCreator2.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package VisionX::ArmarXObjects::CalibrationCreator2
17  * @author Christian R. G. Dreher <c.dreher@kit.edu>
18  * @date 2020
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #include "CalibrationCreator2.h"
24 
25 // VisionX
26 //#include <VisionX/tools/TypeMapping.h>
29 
30 // IVT
31 #include "Image/ByteImage.h"
32 #include "Image/ImageProcessor.h"
33 #include "Image/IplImageAdaptor.h"
34 
35 #include <opencv2/opencv.hpp>
36 
37 #include <sys/time.h>
38 
39 #include <iostream>
40 #include <sstream>
41 #include <string>
42 #include <ctime>
43 #include <cstdio>
44 
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>
52 
53 
54 //static inline void read(const FileNode& node, Settings& x, const Settings& default_value = Settings())
55 //{
56 // if(node.empty())
57 // x = default_value;
58 // else
59 // x.read(node);
60 //}
61 
62 //static inline void write(FileStorage& fs, const String&, const Settings& s )
63 //{
64 // s.write(fs);
65 //}
66 
67 namespace
68 {
69 
70 
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)
76  {
77  std::vector<cv::Point2f> imagePoints2;
78  size_t totalPoints = 0;
79  double totalErr = 0, err;
80  perViewErrors.resize(objectPoints.size());
81 
82  for (size_t i = 0; i < objectPoints.size(); ++i)
83  {
84  cv::projectPoints(objectPoints[i], rvecs[i], tvecs[i], cameraMatrix, distCoeffs, imagePoints2);
85  err = cv::norm(imagePoints[i], imagePoints2, cv::NORM_L2);
86 
87  size_t n = objectPoints[i].size();
88  perViewErrors[i] = (float) std::sqrt(err * err / n);
89  totalErr += err * err;
90  totalPoints += n;
91  }
92 
93  return std::sqrt(totalErr / totalPoints);
94  }
95 
96 
97  static void calcBoardCornerPositions(cv::Size boardSize, float squareSize, std::vector<cv::Point3f>& corners,
98  visionx::Settings::Pattern patternType /*= Settings::CHESSBOARD*/)
99  {
100  corners.clear();
101 
102  switch (patternType)
103  {
106  for (int i = 0; i < boardSize.height; ++i)
107  for (int j = 0; j < boardSize.width; ++j)
108  {
109  corners.push_back(cv::Point3f(j * squareSize, i * squareSize, 0));
110  }
111  break;
112 
114  for (int i = 0; i < boardSize.height; i++)
115  for (int j = 0; j < boardSize.width; j++)
116  {
117  corners.push_back(cv::Point3f((2 * j + i % 2)*squareSize, i * squareSize, 0));
118  }
119  break;
120  default:
121  break;
122  }
123  }
124 
125 
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)
129  {
130  //! [fixed_aspect]
131  cameraMatrix = cv::Mat::eye(3, 3, CV_64F);
132  if (s.flag & cv::CALIB_FIX_ASPECT_RATIO)
133  {
134  cameraMatrix.at<double>(0, 0) = s.aspectRatio;
135  }
136  //! [fixed_aspect]
137  distCoeffs = cv::Mat::zeros(8, 1, CV_64F);
138 
139  std::vector<std::vector<cv::Point3f> > objectPoints(1);
140  calcBoardCornerPositions(s.boardSize, s.squareSize, objectPoints[0], s.calibrationPattern);
141 
142  objectPoints.resize(imagePoints.size(), objectPoints[0]);
143 
144  //Find intrinsic and extrinsic camera parameters
145  double rms;
146 
147  rms = cv::calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix, distCoeffs, rvecs, tvecs,
148  s.flag);
149 
150  ARMARX_INFO << "Re-projection error reported by calibrateCamera: " << rms;
151 
152  bool ok = cv::checkRange(cameraMatrix) && cv::checkRange(distCoeffs);
153 
154  totalAvgErr = computeReprojectionErrors(objectPoints, imagePoints, rvecs, tvecs, cameraMatrix,
155  distCoeffs, reprojErrs);
156 
157  return ok;
158  }
159 
160 
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,
164  double totalAvgErr)
165  {
166  cv::FileStorage fs(s.outputFileName, cv::FileStorage::WRITE);
167 
168  time_t tm;
169  time(&tm);
170  struct tm* t2 = localtime(&tm);
171  char buf[1024];
172  strftime(buf, sizeof(buf), "%c", t2);
173 
174  fs << "calibration_time" << buf;
175 
176  if (!rvecs.empty() || !reprojErrs.empty())
177  {
178  fs << "nr_of_frames" << (int)std::max(rvecs.size(), reprojErrs.size());
179  }
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;
185 
186  if (s.flag & cv::CALIB_FIX_ASPECT_RATIO)
187  {
188  fs << "fix_aspect_ratio" << s.aspectRatio;
189  }
190 
191  if (s.flag)
192  {
193  std::stringstream flagsStringStream;
194 
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" : "");
206 
207  fs.writeComment(flagsStringStream.str());
208  }
209 
210  fs << "flags" << s.flag;
211 
212  fs << "camera_matrix" << cameraMatrix;
213  fs << "distortion_coefficients" << distCoeffs;
214 
215  fs << "avg_reprojection_error" << totalAvgErr;
216  if (s.writeExtrinsics && !reprojErrs.empty())
217  {
218  fs << "per_view_reprojection_errors" << cv::Mat(reprojErrs);
219  }
220 
221  if (s.writeExtrinsics && !rvecs.empty() && !tvecs.empty())
222  {
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;
227 
228  for (size_t i = 0; i < rvecs.size(); i++)
229  {
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));
232 
233  if (needReshapeR)
234  {
235  rvecs[i].reshape(1, 1).copyTo(r);
236  }
237  else
238  {
239  //*.t() is MatExpr (not Mat) so we can use assignment operator
240  CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1);
241  r = rvecs[i].t();
242  }
243 
244  if (needReshapeT)
245  {
246  tvecs[i].reshape(1, 1).copyTo(t);
247  }
248  else
249  {
250  CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1);
251  t = tvecs[i].t();
252  }
253  }
254  fs.writeComment("a set of 6-tuples (rotation vector + translation vector) for each view");
255  fs << "extrinsic_parameters" << bigmat;
256  }
257 
258  if (s.writePoints && !imagePoints.empty())
259  {
260  cv::Mat imagePtMat((int)imagePoints.size(), (int)imagePoints[0].size(), CV_32FC2);
261  for (size_t i = 0; i < imagePoints.size(); i++)
262  {
263  cv::Mat r = imagePtMat.row(int(i)).reshape(2, imagePtMat.cols);
264  cv::Mat imgpti(imagePoints[i]);
265  imgpti.copyTo(r);
266  }
267  fs << "image_points" << imagePtMat;
268  }
269  }
270 
271  bool runCalibrationAndSave(visionx::Settings& s, cv::Size imageSize, cv::Mat& cameraMatrix, cv::Mat& distCoeffs,
272  std::vector<std::vector<cv::Point2f> > imagePoints)
273  {
274  std::vector<cv::Mat> rvecs, tvecs;
275  std::vector<float> reprojErrs;
276  double totalAvgErr = 0;
277 
278  bool ok = runCalibration(s, imageSize, cameraMatrix, distCoeffs, imagePoints, rvecs, tvecs, reprojErrs,
279  totalAvgErr);
280  ARMARX_INFO << (ok ? "Calibration succeeded" : "Calibration failed")
281  << ". avg re projection error = " << totalAvgErr;
282 
283  if (ok)
284  saveCameraParams(s, imageSize, cameraMatrix, distCoeffs, rvecs, tvecs, reprojErrs, imagePoints,
285  totalAvgErr);
286  return ok;
287  }
288 
289 }
290 
291 namespace visionx
292 {
293 
294  const std::string
295  CalibrationCreator2::default_name = "CalibrationCreator2";
296 
297 
299  {
300  providerName = getProperty<std::string>("ImageProviderAdapterName").getValue();
301  usingImageProvider(providerName);
302 
303  getProperty(m_outputFileName, "OutputFileName");
304  waitingTimeBetweenCaptures = IceUtil::Time::milliSeconds(getProperty<int>("WaitingIntervalBetweenImages"));
305  std::string image_side = getProperty<std::string>("ImageToUse").getValue();
306  if (image_side == "left")
307  {
308  imageID = 0;
309  }
310  else if (image_side == "right")
311  {
312  imageID = 1;
313  }
314  else
315  {
316  throw std::runtime_error("ImageToUse must be either left or right");
317  }
318  }
319 
320 
322  {
323  visionx::ImageProviderInfo imageProviderInfo = getImageProvider(providerName);
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;
329 
330  cameraImages = new CByteImage*[2];
331  cameraImages[0] = tools::createByteImage(imageProviderInfo);
332  cameraImages[1] = tools::createByteImage(imageProviderInfo);
333 
334  // cv::Size ; The size of the board -> Number of items by width and height
335  getProperty(m_settings.boardSize.width, "NumberOfColumns");
336  getProperty(m_settings.boardSize.height, "NumberOfRows");
337  // Pattern ; One of the Chessboard, circles, or asymmetric circle pattern
338  m_settings.calibrationPattern = Settings::Pattern::CHESSBOARD;
339  // float ; The size of a square in your defined unit (point, millimeter,etc).
340  getProperty(m_settings.squareSize, "PatternSquareSize");
341  // int ; The number of frames to use from the input for calibration
342  getProperty(m_settings.nrFrames, "NumberOfImages");
343  //float ; The aspect ratio
344  if (getProperty<bool>("EnableFixAspectRatio"))
345  {
346  m_settings.aspectRatio = focal_lengths.at(0) / focal_lengths.at(1);
347  }
348  else
349  {
350  m_settings.aspectRatio = 0;
351  }
352  //bool ; Write detected feature points
353  m_settings.writePoints = true;
354  //bool ; Write extrinsic parameters
355  m_settings.writeExtrinsics = false;
356  //bool ; Flip the captured images around the horizontal axis
357  m_settings.flipVertical = false;
358  //std::string ; The name of the file where to write
359  m_settings.outputFileName = m_outputFileName;
360  //bool ;
361  getProperty(m_settings.useK3ToK6, "UseAdditionalParams");
362 
363  m_settings.validate();
364  if (not m_settings.goodInput)
365  {
366  throw std::runtime_error("Invalid input detected. Application stopping.");
367  }
368 
369  ARMARX_INFO << "Board info: " << m_settings.boardSize.width << "x"
370  << m_settings.boardSize.height << " squares with square size of "
371  << m_settings.squareSize;
372  }
373 
374 
376  {
377  delete cameraImages[0];
378  delete cameraImages[1];
379  delete[] cameraImages;
380  }
381 
382 
384  {
385 
386  }
387 
388 
390  {
391  cv::Mat view;
392 
393  if (not waitForImages(1000))
394  {
395  return;
396  }
397 
398  if (IceUtil::Time::now() - timeOfLastCapture < waitingTimeBetweenCaptures)
399  {
400  return;
401  }
402 
403  ARMARX_INFO << "Capturing image for calibration #" << imagePoints.size();
404  getImages(cameraImages);
405  timeOfLastCapture = IceUtil::Time::now();
406  visionx::imrec::convert(*cameraImages[imageID], view);
407 
408  //----- If no more image, or got enough, then stop calibration and show result -------------
409  if (m_mode == CAPTURING && imagePoints.size() >= (size_t) m_settings.nrFrames)
410  {
411  ARMARX_IMPORTANT << "Running calibration now...";
412  if (runCalibrationAndSave(m_settings, imageSize, cameraMatrix, distCoeffs, imagePoints))
413  {
414  m_mode = CALIBRATED;
415  }
416  ARMARX_IMPORTANT << "Done writing calibration file.";
417  }
418 
419  imageSize = view.size(); // Format input image.
420  if (m_settings.flipVertical)
421  {
422  cv::flip(view, view, 0);
423  }
424 
425  //! [find_pattern]
426  std::vector<cv::Point2f> pointBuf;
427 
428  bool found;
429 
430  int chessBoardFlags = cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_NORMALIZE_IMAGE | cv::CALIB_CB_FAST_CHECK;
431 
432  switch (m_settings.calibrationPattern) // Find feature points on the input format
433  {
435  ARMARX_DEBUG << "Searching chessboard corners...";
436  found = cv::findChessboardCorners(view, m_settings.boardSize, pointBuf, chessBoardFlags);
437  break;
439  found = cv::findCirclesGrid(view, m_settings.boardSize, pointBuf);
440  break;
442  found = cv::findCirclesGrid(view, m_settings.boardSize, pointBuf, cv::CALIB_CB_ASYMMETRIC_GRID);
443  break;
444  default:
445  found = false;
446  break;
447  }
448  //! [find_pattern]
449 
450  //! [pattern_found]
451  if (found) // If done with success,
452  {
453  // improve the found corners' coordinate accuracy for chessboard
454  if (m_settings.calibrationPattern == Settings::CHESSBOARD)
455  {
456  cv::Mat viewGray;
457  cv::cvtColor(view, viewGray, cv::COLOR_BGR2GRAY);
458  cv::cornerSubPix(viewGray, pointBuf, cv::Size(11, 11),
459  cv::Size(-1, -1), cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::COUNT, 30, 0.1));
460  }
461 
462  if (m_mode == CAPTURING)
463  {
464  imagePoints.push_back(pointBuf);
465  }
466 
467  // Draw the corners.
468  cv::drawChessboardCorners(view, m_settings.boardSize, cv::Mat(pointBuf), found);
469  }
470  //! [pattern_found]
471 
472  //----------------------------- Output Text ------------------------------------------------
473  //! [output_text]
474 
475  // //------------------------- Video capture output undistorted ------------------------------
476  // //! [output_undistorted]
477  // if (m_mode == CALIBRATED && m_settings.showUndistorsed)
478  // {
479  // cv::Mat temp = view.clone();
480  // cv::undistort(temp, view, cameraMatrix, distCoeffs);
481  // }
482  // //! [output_undistorted]
483 
484  //------------------------------ Show image and check for input commands -------------------
485  //! [await_input]
486  }
487 
488 }
visionx::Settings::Pattern
Pattern
Definition: CalibrationCreator2.h:54
visionx::Settings::validate
void validate()
Definition: CalibrationCreator2.h:56
GfxTL::sqrt
VectorXD< D, T > sqrt(const VectorXD< D, T > &a)
Definition: VectorXD.h:662
visionx::Settings::calibrationPattern
Pattern calibrationPattern
Definition: CalibrationCreator2.h:107
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
visionx::Settings::writePoints
bool writePoints
Definition: CalibrationCreator2.h:111
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
CalibrationCreator2.h
visionx::Settings::useK3ToK6
bool useK3ToK6
Definition: CalibrationCreator2.h:115
visionx::Settings::flipVertical
bool flipVertical
Definition: CalibrationCreator2.h:113
visionx::Settings::CIRCLES_GRID
@ CIRCLES_GRID
Definition: CalibrationCreator2.h:54
visionx::ImageProcessor::getImageProvider
ImageProviderInfo getImageProvider(std::string name, ImageType destinationImageType=eRgb, bool waitForProxy=false)
Select an ImageProvider.
Definition: ImageProcessor.cpp:152
visionx::Settings::goodInput
bool goodInput
Definition: CalibrationCreator2.h:117
visionx::imrecman::ok
@ ok
Definition: ImageRecordingManagerInterface.ice:46
visionx::Settings::squareSize
double squareSize
Definition: CalibrationCreator2.h:108
visionx::tools::createByteImage
CByteImage * createByteImage(const ImageFormatInfo &imageFormat, const ImageType imageType)
Creates a ByteImage for the destination type specified in the given imageProviderInfo.
visionx::Settings
Definition: CalibrationCreator2.h:50
visionx::ImageProviderInfo
Definition: ImageProcessor.h:466
visionx::CalibrationCreator2::onConnectImageProcessor
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
Definition: CalibrationCreator2.cpp:321
visionx::imrec::convert
void convert(const CByteImage &in, cv::Mat &out)
Converts an IVT CByteImage to OpenCV's BGR Mat.
Definition: helper.cpp:41
visionx::Settings::ASYMMETRIC_CIRCLES_GRID
@ ASYMMETRIC_CIRCLES_GRID
Definition: CalibrationCreator2.h:54
visionx::Settings::nrFrames
int nrFrames
Definition: CalibrationCreator2.h:109
visionx::Settings::aspectRatio
float aspectRatio
Definition: CalibrationCreator2.h:110
visionx::CalibrationCreator2::process
void process() override
Process the vision component.
Definition: CalibrationCreator2.cpp:389
visionx::Settings::outputFileName
std::string outputFileName
Definition: CalibrationCreator2.h:114
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
visionx::ImageProcessor::usingImageProvider
void usingImageProvider(std::string name)
Registers a delayed topic subscription and a delayed provider proxy retrieval which all will be avail...
Definition: ImageProcessor.cpp:117
EPS
#define EPS
Definition: gdiam.cpp:2021
max
T max(T t1, T t2)
Definition: gdiam.h:48
visionx::ImageProcessor::getImages
int getImages(CByteImage **ppImages)
Poll images from provider.
Definition: ImageProcessor.cpp:351
visionx::Settings::CHESSBOARD
@ CHESSBOARD
Definition: CalibrationCreator2.h:54
visionx::CalibrationCreator2::onExitImageProcessor
void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: CalibrationCreator2.cpp:383
visionx::ImageProviderInfo::proxy
ImageProviderInterfacePrx proxy
proxy to image provider
Definition: ImageProcessor.h:472
float
#define float
Definition: 16_Level.h:22
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
visionx::CalibrationCreator2::default_name
static const std::string default_name
Definition: CalibrationCreator2.h:128
armarx::PropertyUser::getProperty
Property< PropertyType > getProperty(const std::string &name)
Property creation and retrieval.
Definition: PropertyUser.h:179
visionx::Settings::boardSize
cv::Size boardSize
Definition: CalibrationCreator2.h:106
visionx::Settings::writeExtrinsics
bool writeExtrinsics
Definition: CalibrationCreator2.h:112
ImageUtil.h
helper.h
visionx::CalibrationCreator2::onDisconnectImageProcessor
void onDisconnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component looses network ...
Definition: CalibrationCreator2.cpp:375
visionx::CalibrationCreator2::onInitImageProcessor
void onInitImageProcessor() override
Setup the vision component.
Definition: CalibrationCreator2.cpp:298
armarx::ctrlutil::s
double s(double t, double s0, double v0, double a0, double j)
Definition: CtrlUtil.h:33
visionx::ImageProcessor::waitForImages
bool waitForImages(int milliseconds=1000)
Wait for new images.
Definition: ImageProcessor.cpp:275
norm
double norm(const Point &a)
Definition: point.hpp:94