JeVoisBase  1.21
JeVois Smart Embedded Machine Vision Toolkit Base Modules
Share this page:
Loading...
Searching...
No Matches
CalibrateCamera.C
Go to the documentation of this file.
1// ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
2//
3// JeVois Smart Embedded Machine Vision Toolkit - Copyright (C) 2024 by Laurent Itti, the University of Southern
4// California (USC), and iLab at USC. See http://iLab.usc.edu and http://jevois.org for information about this project.
5//
6// This file is part of the JeVois Smart Embedded Machine Vision Toolkit. This program is free software; you can
7// redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software
8// Foundation, version 2. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
9// without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
10// License for more details. You should have received a copy of the GNU General Public License along with this program;
11// if not, write to the Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
12//
13// Contact information: Laurent Itti - 3641 Watt Way, HNB-07A - Los Angeles, CA 90089-2520 - USA.
14// Tel: +1 213 740 3527 - itti@pollux.usc.edu - http://iLab.usc.edu - http://jevois.org
15// ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
16/*! \file */
17
18// icon by flaticon
19
20#include <jevois/Core/Module.H>
21#include <jevois/Core/Engine.H>
22#include <jevois/Debug/Timer.H>
24#include <jevoisbase/Components/ArUco/ArUco.H> // for dictionary enum
25#include <opencv2/core.hpp>
26#include <opencv2/core/utility.hpp>
27#include <opencv2/imgproc.hpp>
28#include <opencv2/calib3d.hpp>
29#include <opencv2/objdetect/charuco_detector.hpp>
30#include <chrono>
31
32static jevois::ParameterCategory const ParamCateg("Camera Calibration Options");
33
34//! Enum for parameter \relates CalibrateCamera
35JEVOIS_DEFINE_ENUM_CLASS(Pattern, (ChessBoard) (ChArUcoBoard) (CirclesGrid) (AsymmetricCirclesGrid) );
36
37//! Parameter \relates CalibrateCamera
38JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(pattern, Pattern, "Type of calibration board pattern to use",
39 Pattern::ChessBoard, Pattern_Values, ParamCateg);
40
41//! Parameter \relates CalibrateCamera
42JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(dictionary, aruco::Dict, "ArUco dictionary to use",
43 aruco::Dict::D4X4_50, aruco::Dict_Values, ParamCateg);
44
45//! Parameter \relates CalibrateCamera
46JEVOIS_DECLARE_PARAMETER(squareSize, float, "Size of each tile (check) in user-chosen units (e.g., mm, inch, etc). The "
47 "unit used here is the one that will be used once calibrated to report 3D coordinates "
48 "of objects relative to the camera",
49 23.0f, ParamCateg);
50
51//! Parameter \relates CalibrateCamera
52JEVOIS_DECLARE_PARAMETER(markerSize, float, "ChArUco marker size in user-chosen units (e.g., mm, inch, "
53 "etc). The unit used here is the one that will be used once calibrated to report 3D "
54 "coordinates of objects relative to the camera",
55 27.0f, ParamCateg);
56
57//! Parameter \relates CalibrateCamera
58JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(boardSize, cv::Size, "Board size [width height] in number of horizontal and "
59 "vertical tiles/disks. (Note: for asymmetric circle grid, count the number of "
60 "disks on each row, then the number of rows). The product width * height "
61 "should be the total number of tiles/disks on the grid.)",
62 { 11, 7 }, ParamCateg);
63
64//! Parameter \relates CalibrateCamera
65JEVOIS_DECLARE_PARAMETER(aspectRatio, float, "Fixed aspect ratio value to use when non-zero, or auto when 0.0",
66 0.0F, ParamCateg);
67
68//! Parameter \relates CalibrateCamera
69JEVOIS_DECLARE_PARAMETER(zeroTangentDist, bool, "Assume zero tangential distortion coefficients P1, P2 and do "
70 "not try to optimize them, i.e., assume board is exactly planar",
71 true, ParamCateg);
72
73//! Parameter \relates CalibrateCamera
74JEVOIS_DECLARE_PARAMETER(fixPrincipalPoint, bool, "Fix principal point at center, otherwise find its location",
75 true, ParamCateg);
76
77//! Parameter \relates CalibrateCamera
78JEVOIS_DECLARE_PARAMETER(fishEye, bool, "Use fisheye model. Should be true if using a wide-angle lens that "
79 "produces significant barrel distortion, otherwise false",
80 false, ParamCateg);
81
82//! Parameter \relates CalibrateCamera
83JEVOIS_DECLARE_PARAMETER(winSize, unsigned char, "Half of search window size for sub-pixel corner refinement",
84 11, ParamCateg);
85
86//! Parameter \relates CalibrateCamera
87JEVOIS_DECLARE_PARAMETER(fixK1, bool, "Fix (do not try to optimize) K1 radial distortion parameter",
88 false, ParamCateg);
89
90//! Parameter \relates CalibrateCamera
91JEVOIS_DECLARE_PARAMETER(fixK2, bool, "Fix (do not try to optimize) K2 radial distortion parameter",
92 false, ParamCateg);
93
94//! Parameter \relates CalibrateCamera
95JEVOIS_DECLARE_PARAMETER(fixK3, bool, "Fix (do not try to optimize) K3 radial distortion parameter",
96 false, ParamCateg);
97
98//! Parameter \relates CalibrateCamera
99JEVOIS_DECLARE_PARAMETER(showUndistorted, bool, "Once calibrated, show undistorted image instead of original capture",
100 false, ParamCateg);
101
102//! Parameter \relates CalibrateCamera
103JEVOIS_DECLARE_PARAMETER(grab, bool, "Grab one image, try to detect the calibration pattern, and add to list of "
104 "detected patterns so far. Click this for at least 5 images showing your calibration board "
105 "under various viewpoints. When enough boards have been successfully captured, click "
106 "'calibrate'",
107 false, ParamCateg);
108
109//! Parameter \relates CalibrateCamera
110JEVOIS_DECLARE_PARAMETER(calibrate, bool, "Calibrate using all the grabbed boards so far. You first need to grab "
111 "enough good views of your calibration board before you can calibrate.",
112 false, ParamCateg);
113
114//! Helper module to calibrate a given sensor+lens combo, which allows ArUco and other modules to do 3D pose estimation
115/*! Just follow the on-screen prompts to calibrate your camera. The calibration results will be saved into
116 /jevois[pro]/share/camera/ on microSD and will be automatically loaded when using a machine vision module that uses
117 camera calibration, for example \jvmod{DemoArUco} or \jvmod{FirstVision}.
118
119 The basic workflow is:
120
121 - print a calibration board and affix is to a good planar surface (e.g., an acrylic board, aluminum board, etc). Or
122 buy a board, for example from https://calib.io or similar.
123
124 - decide which sensor, resolution, and lens you want to calibrate. The sensor should be detected at boot time (check
125 \p engine::camerasens system parameter). The lens can be set manually through the \p engine::cameralens
126 parameter. The default lens is called "standard". For the resolution, edit videomappings.cfg and add a mode for
127 the CalibrateCamera module that will use the same resolution as the one you want to use later for machine
128 vision. Several commented-out examples are already in videomappings.cfg, so likely you can just uncomment one of
129 them. Then run the corresponding version of the \jvmod{CalibrateCamera} module.
130
131 - set the parameters to match the board type, board width and height in number of tiles, tile size in the unit that
132 you want to later use to estimate distance to detected objects (e.g., in millimeters, inches, etc), and possibly
133 ChArUco marker size and dictionary.
134
135 - point the camera towards the board so that the full board is in the camera view. Click 'grab'. Change the
136 viewpoint and repeat at least 5 times. Use various 3D viewpoints.
137
138 - click 'calibrate' and the calibration will be computed and saved to microSD for that sensor, resolution, and
139 lens. It will be ready to be loaded by modules that want to use it.
140
141 The default settings are for a 11x7 Chess Board that was created using the online generator at https://calib.io and
142 which you can get from http://jevois.org/data/calib.io_checker_260x200_7x11_23.pdf -
143 When you print the board, make sure you print at 100% scale. You should confirm that the checks in the printout are
144 23mm x 23mm.
145
146 An alternate chess board with fewer checks may be desirable at low resolutions, such as the 7x5 chess board at
147 http://jevois.org/data/calib.io_checker_260x200_5x7_36.pdf - if you use it, set board size to '7 5', and square size
148 to '36' to match it.
149
150 If you are using a wide-angle fish-eye lens with a lot of distortion, turn on the \p fishEye parameter.
151
152 You can also use a ChArUco board, though we have actually obtained worse reprojection errors with these boards. You
153 can print the board at http://jevois.org/data/calib.io_charuco_260x200_5x7_36_27_DICT_4X4.pdf at 100% scale, and you
154 should confirm that the checks in the printout are 36mm x 36mm, and the ArUco patterns within the white checks are
155 27mm x 27mm. If you use it, you need to set the board type, size, marker size, and square size parameters to match
156 it. An alternate board with more ChArUcos is at
157 http://jevois.org/data/calib.io_charuco_260x200_7x11_23_17_DICT_4X4.pdf
158
159
160 @author Laurent Itti
161
162 @displayname Calibrate Camera
163 @videomapping YUYV 320 495 30.0 YUYV 320 240 30.0 JeVois DemoArUco
164 @videomapping YUYV 640 975 20.0 YUYV 640 480 20.0 JeVois DemoArUco
165 @email itti\@usc.edu
166 @address University of Southern California, HNB-07A, 3641 Watt Way, Los Angeles, CA 90089-2520, USA
167 @copyright Copyright (C) 2024 by Laurent Itti, iLab and the University of Southern California
168 @mainurl http://jevois.org
169 @supporturl http://jevois.org/doc
170 @otherurl http://iLab.usc.edu
171 @license GPL v3
172 @distribution Unrestricted
173 @restrictions None
174 \ingroup modules */
176 public jevois::Parameter<pattern, dictionary, squareSize, markerSize, boardSize,
177 aspectRatio, zeroTangentDist, fixPrincipalPoint, winSize,
178 fishEye, fixK1, fixK2, fixK3, showUndistorted, grab, calibrate>
179{
180 public:
181 // ####################################################################################################
182 //! Constructor
183 // ####################################################################################################
185
186 // ####################################################################################################
187 //! Virtual destructor for safe inheritance
188 // ####################################################################################################
190 { }
191
192 // ####################################################################################################
193 //! Process one captured image
194 // ####################################################################################################
195 void process_frame(cv::Mat const & view)
196 {
197 // Add one image, or run the whole calibration if we have enough images:
198 if (grab::get())
199 {
200 grab::set(false);
201
202 // Try to detect the board:
203 std::vector<cv::Point2f> pointBuf;
204 int chessBoardFlags = cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_NORMALIZE_IMAGE;
205
206 // fast check erroneously fails with high distortions like fisheye
207 if (fishEye::get() == false) chessBoardFlags |= cv::CALIB_CB_FAST_CHECK;
208
209 // Find feature points:
210 cv::Size bs = boardSize::get();
211
212 bool found = false;
213 switch (pattern::get())
214 {
215 case Pattern::ChessBoard:
216 found = cv::findChessboardCorners(view, cv::Size(bs.width - 1, bs.height - 1), pointBuf, chessBoardFlags);
217 if (found)
218 {
219 // Improve the found corners' coordinate accuracy for chessboard:
220 cv::Mat viewGray;
221 cv::cvtColor(view, viewGray, cv::COLOR_BGR2GRAY);
222 cv::cornerSubPix(viewGray, pointBuf, cv::Size(winSize::get(), winSize::get()), cv::Size(-1,-1),
223 cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::COUNT, 30, 0.0001));
224 }
225 break;
226
227 case Pattern::ChArUcoBoard:
228 {
229 // May need to instantiate a detector
230 if (! itsChArUcoDetector)
231 {
232 // Instantiate the dictionary:
233 cv::aruco::Dictionary dico = ArUco::getDictionary(dictionary::get());
234 cv::aruco::CharucoBoard ch_board({boardSize::get().width, boardSize::get().height}, squareSize::get(),
235 markerSize::get(), dico);
236 cv::aruco::DetectorParameters detector_params;
237 detector_params.cornerRefinementMethod = int(cv::aruco::CORNER_REFINE_NONE); // recommended by docs
238
239 cv::aruco::CharucoParameters charuco_params;
240 charuco_params.tryRefineMarkers = true;
241 charuco_params.cameraMatrix = itsCameraMatrix;
242 charuco_params.distCoeffs = itsDistCoeffs;
243 itsChArUcoDetector.reset(new cv::aruco::CharucoDetector(ch_board, charuco_params, detector_params));
244 }
245
246 // Detect the board:
247 std::vector<int> markerIds, charucoIds;
248 std::vector<std::vector<cv::Point2f> > markerCorners;
249 itsChArUcoDetector->detectBoard(view, pointBuf, charucoIds, markerCorners, markerIds);
250 size_t needed_num = (size_t)((bs.height - 1)*(bs.width - 1));
251 LINFO("ChArUco: detected "<< pointBuf.size() << " out of " << needed_num << " corners");
252 found = (pointBuf.size() == needed_num);
253
254 // Special handling of charuco boards:
255 if (found)
256 {
257 LINFO("ChArUco calibration board successfully detected");
258
259 itsImagePoints.push_back(pointBuf);
260
261 // Draw the corners into the image:
262 itsLastGoodView = view.clone();
263 itsLastGoodTime = std::chrono::steady_clock::now();
264 if (markerIds.size() > 0)
265 cv::aruco::drawDetectedMarkers(itsLastGoodView, markerCorners);
266 if (charucoIds.size() > 0)
267 cv::aruco::drawDetectedCornersCharuco(itsLastGoodView, pointBuf, charucoIds, cv::Scalar(255, 0, 0));
268 }
269 break;
270 }
271
272 case Pattern::CirclesGrid:
273 found = findCirclesGrid(view, bs, pointBuf);
274 break;
275
276 case Pattern::AsymmetricCirclesGrid:
277 found = findCirclesGrid(view, bs, pointBuf, cv::CALIB_CB_ASYMMETRIC_GRID);
278 break;
279 }
280
281 // Common handling of non-charuco boards:
282 if (pattern::get() != Pattern::ChArUcoBoard)
283 if (found)
284 {
285 LINFO("Calibration board successfully detected");
286
287 itsImagePoints.push_back(pointBuf);
288
289 // Draw the corners into the image:
290 itsLastGoodView = view.clone();
291 itsLastGoodTime = std::chrono::steady_clock::now();
292 drawChessboardCorners(itsLastGoodView, cv::Size(bs.width - 1, bs.height - 1), cv::Mat(pointBuf), found);
293
294 }
295 else engine()->reportError("Calibration board was not detected. Make sure it is in full view with no "
296 "occlusions, reflections, strong shadows, etc.");
297 }
298
299 // Do we want to calibrate now?
300 if (calibrate::get())
301 {
302 calibrate::set(false);
303
304 if (itsImagePoints.size() < 5)
305 engine()->reportError("Need at least 5 good board views before calibration");
306 else
307 {
309
310 if (itsCalibrated == false)
311 {
312 engine()->reportError("Calibration failed. Let's try again.");
313 restart();
314 }
315 }
316 }
317
318 // If we are calibrated, show either live view or undistorted view:
319 if (itsCalibrated)
320 {
321 if (showUndistorted::get())
322 {
323 cv::Mat temp = view.clone();
324 if (fishEye::get())
325 {
326 cv::Mat newCamMat;
327 cv::fisheye::estimateNewCameraMatrixForUndistortRectify(itsCameraMatrix, itsDistCoeffs, itsImageSize,
328 cv::Matx33d::eye(), newCamMat, 1);
329 cv::fisheye::undistortImage(temp, itsLastGoodView, itsCameraMatrix, itsDistCoeffs, newCamMat);
330 }
331 else cv::undistort(temp, itsLastGoodView, itsCameraMatrix, itsDistCoeffs);
332 }
333 else itsLastGoodView = view;
334 }
335 }
336
337 // ####################################################################################################
339 {
340 itsCalibrated = false;
341
342 // Gather the calibration flags:
343 itsFlag = 0;
344 if (fishEye::get())
345 {
346 itsFlag = cv::fisheye::CALIB_FIX_SKEW | cv::fisheye::CALIB_RECOMPUTE_EXTRINSIC;
347 if (fixK1::get()) itsFlag |= cv::fisheye::CALIB_FIX_K1;
348 if (fixK2::get()) itsFlag |= cv::fisheye::CALIB_FIX_K2;
349 if (fixK3::get()) itsFlag |= cv::fisheye::CALIB_FIX_K3;
350 if (fixPrincipalPoint::get()) itsFlag |= cv::fisheye::CALIB_FIX_PRINCIPAL_POINT;
351 }
352 else
353 {
354 if (fixPrincipalPoint::get()) itsFlag |= cv::CALIB_FIX_PRINCIPAL_POINT;
355 if (zeroTangentDist::get()) itsFlag |= cv::CALIB_ZERO_TANGENT_DIST;
356 if (aspectRatio::get()) itsFlag |= cv::CALIB_FIX_ASPECT_RATIO;
357 if (fixK1::get()) itsFlag |= cv::CALIB_FIX_K1;
358 if (fixK2::get()) itsFlag |= cv::CALIB_FIX_K2;
359 if (fixK3::get()) itsFlag |= cv::CALIB_FIX_K3;
360 }
361
362 std::vector<cv::Mat> rvecs, tvecs;
363 std::vector<float> reprojErrs;
364 std::vector<cv::Point3f> newObjPoints;
365
366 itsCalibrated = runCalibration(rvecs, tvecs, reprojErrs, itsAvgErr, newObjPoints);
367
368 // If calibrated, save the calibration now:
369 if (itsCalibrated)
370 {
372 calib.sensor = engine()->camerasens::get();
373 calib.lens = engine()->cameralens::get();
374 calib.w = itsImageSize.width;
375 calib.h = itsImageSize.height;
376 calib.camMatrix = itsCameraMatrix;
377 calib.distCoeffs = itsDistCoeffs;
378 calib.avgReprojErr = itsAvgErr;
379
380 engine()->saveCameraCalibration(calib);
381 }
382 }
383
384 // ####################################################################################################
385 double computeReprojectionErrors(std::vector<std::vector<cv::Point3f>> const & objectPoints,
386 std::vector<cv::Mat> const & rvecs, std::vector<cv::Mat> const & tvecs,
387 std::vector<float> & perViewErrors)
388 {
389 std::vector<cv::Point2f> imagePoints2;
390 size_t totalPoints = 0;
391 double totalErr = 0, err;
392 perViewErrors.resize(objectPoints.size());
393
394 for (size_t i = 0; i < objectPoints.size(); ++i )
395 {
396 if (fishEye::get())
397 cv::fisheye::projectPoints(objectPoints[i], imagePoints2, rvecs[i], tvecs[i], itsCameraMatrix, itsDistCoeffs);
398 else
399 cv::projectPoints(objectPoints[i], rvecs[i], tvecs[i], itsCameraMatrix, itsDistCoeffs, imagePoints2);
400
401 err = cv::norm(itsImagePoints[i], imagePoints2, cv::NORM_L2);
402
403 size_t n = objectPoints[i].size();
404 perViewErrors[i] = (float) std::sqrt(err*err/n);
405 totalErr += err*err;
406 totalPoints += n;
407 }
408
409 return std::sqrt(totalErr / totalPoints);
410 }
411
412 // ####################################################################################################
413 void calcBoardCornerPositions(cv::Size boardsiz, float squaresiz, std::vector<cv::Point3f> & corners)
414 {
415 corners.clear();
416
417 switch (pattern::get())
418 {
419 case Pattern::ChessBoard:
420 case Pattern::CirclesGrid:
421 for (int i = 0; i < boardsiz.height - 1; ++i)
422 for (int j = 0; j < boardsiz.width - 1; ++j)
423 corners.push_back(cv::Point3f(j*squaresiz, i*squaresiz, 0));
424 break;
425
426 case Pattern::ChArUcoBoard:
427 for (int i = 0; i < boardsiz.height - 1; ++i)
428 for (int j = 0; j < boardsiz.width - 1; ++j)
429 corners.push_back(cv::Point3f(j*squaresiz, i*squaresiz, 0));
430 break;
431
432 case Pattern::AsymmetricCirclesGrid:
433 for (int i = 0; i < boardsiz.height - 1; i++)
434 for (int j = 0; j < boardsiz.width - 1; j++)
435 corners.push_back(cv::Point3f((2 * j + i % 2)*squaresiz, i*squaresiz, 0));
436 break;
437 }
438 }
439
440 // ####################################################################################################
441 bool runCalibration(std::vector<cv::Mat> & rvecs, std::vector<cv::Mat> & tvecs, std::vector<float> & reprojErrs,
442 double & totalAvgErr, std::vector<cv::Point3f> & newObjPoints)
443 {
444 itsCameraMatrix = cv::Mat::eye(3, 3, CV_64F);
445 if (fishEye::get() == false && itsFlag & cv::CALIB_FIX_ASPECT_RATIO)
446 itsCameraMatrix.at<double>(0,0) = aspectRatio::get();
447 if (fishEye::get()) itsDistCoeffs = cv::Mat::zeros(4, 1, CV_64F);
448 else itsDistCoeffs = cv::Mat::zeros(8, 1, CV_64F);
449
450 std::vector<std::vector<cv::Point3f> > objectPoints(1);
451 calcBoardCornerPositions(boardSize::get(), squareSize::get(), objectPoints[0]);
452 newObjPoints = objectPoints[0];
453
454 objectPoints.resize(itsImagePoints.size(), objectPoints[0]);
455
456 // Find intrinsic and extrinsic camera parameters
457 double rms;
458
459 if (fishEye::get())
460 {
461 cv::Mat _rvecs, _tvecs;
462 rms = cv::fisheye::calibrate(objectPoints, itsImagePoints, itsImageSize, itsCameraMatrix, itsDistCoeffs,
463 _rvecs, _tvecs, itsFlag);
464
465 rvecs.reserve(_rvecs.rows);
466 tvecs.reserve(_tvecs.rows);
467 for (int i = 0; i < int(objectPoints.size()); i++)
468 {
469 rvecs.push_back(_rvecs.row(i));
470 tvecs.push_back(_tvecs.row(i));
471 }
472 }
473 else
474 {
475 int iFixedPoint = -1;
476 rms = cv::calibrateCameraRO(objectPoints, itsImagePoints, itsImageSize, iFixedPoint,
477 itsCameraMatrix, itsDistCoeffs, rvecs, tvecs, newObjPoints,
478 itsFlag | cv::CALIB_USE_LU);
479 }
480
481 LINFO("Re-projection error reported by calibrateCamera: "<< rms);
482
483 bool ok = cv::checkRange(itsCameraMatrix) && cv::checkRange(itsDistCoeffs);
484
485 objectPoints.clear();
486 objectPoints.resize(itsImagePoints.size(), newObjPoints);
487 totalAvgErr = computeReprojectionErrors(objectPoints, rvecs, tvecs, reprojErrs);
488
489 return ok;
490 }
491
492 // ####################################################################################################
493 //! Processing function with video output to USB
494 // ####################################################################################################
495 virtual void process(jevois::InputFrame && inframe, jevois::OutputFrame && outframe) override
496 {
497 static jevois::Timer timer("processing", 100, LOG_DEBUG);
498
499 // Wait for next available camera image:
500 jevois::RawImage const inimg = inframe.get();
501
502 timer.start();
503
504 // We only handle YUYV input frames, calibration is the same for other formats; any resolution ok:
505 unsigned int const w = inimg.width, h = inimg.height;
506 inimg.require("input", w, h, V4L2_PIX_FMT_YUYV);
507
508 // Update image size:
509 itsImageSize.width = w; itsImageSize.height = h;
510
511 // While we process it, start a thread to wait for out frame and paste the input into it:
512 jevois::RawImage outimg;
513 auto paste_fut = jevois::async([&]() {
514 outimg = outframe.get();
515 outimg.require("output", w, 2*h + 15, V4L2_PIX_FMT_YUYV);
516 jevois::rawimage::paste(inimg, outimg, 0, 0);
517 jevois::rawimage::writeText(outimg, "JeVois Camera Calibration", 3, 3, jevois::yuyv::White);
519 });
520
521 // Convert the image to BGR and process:
522 cv::Mat cvimg = jevois::rawimage::convertToCvBGR(inimg);
523
524 // Detect/calibrate, will update itsCalibrated and itsLastGoodView:
525 process_frame(cvimg);
526
527 // Wait for paste to finish up:
528 paste_fut.get();
529
530 // Let camera know we are done processing the input image:
531 inframe.done();
532
533 // Draw and guide the user:
534 int y = 15, y2 = h + 3; // we use y to print on top image, y2 on bottom image
535
536 // Draw our results if any:
537 if (itsLastGoodView.empty() == false)
538 jevois::rawimage::pasteBGRtoYUYV(itsLastGoodView, outimg, 0, h);
539
540 // If we are now calibrated, show live view, possibly undistorted:
541 if (itsCalibrated)
542 {
543 y2 = jevois::rawimage::itext(outimg, "Calibrated - avg err " + std::to_string(itsAvgErr), y2);
544 if (showUndistorted::get())
545 y2 = jevois::rawimage::itext(outimg, "Undistorted view (see showUndistorted parameter)", y2);
546 else
547 y2 = jevois::rawimage::itext(outimg, "Normal view (see showUndistorted parameter)", y2);
548 }
549 else
550 {
551 // Show some guiding messages:
552 y = jevois::rawimage::itext(outimg, "Set parameters then point to board", y);
553 y = jevois::rawimage::itext(outimg, "Click 'grab' param to grab a board", y);
554 y = jevois::rawimage::itext(outimg, "Vary viewpoints between grabs", y);
555 y = jevois::rawimage::itext(outimg, "Good views so far: " + std::to_string(itsImagePoints.size()), y);
556
557 if (itsImagePoints.size() >= 5)
558 {
559 y = jevois::rawimage::itext(outimg, "Ok to calibrate", y);
560 jevois::rawimage::itext(outimg, "Ok to calibrate", outimg.height - 13);
561 }
562 else
563 {
564 y = jevois::rawimage::itext(outimg, "Need to grab 5+ good views", y);
565 jevois::rawimage::itext(outimg, "Need to grab 5+ good views", outimg.height - 13);
566 }
567 y2 = jevois::rawimage::itext(outimg, "Last grabbed board", y2);
568 }
569
570 // Show processing fps:
571 std::string const & fpscpu = timer.stop();
572 jevois::rawimage::writeText(outimg, fpscpu, 3, h - 13, jevois::yuyv::White);
573
574 // Send the output image with our processing results to the host over USB:
575 outframe.send();
576 }
577
578#ifdef JEVOIS_PRO
579 // ####################################################################################################
580 //! Processing function with zero-copy and GUI on JeVois-Pro
581 // ####################################################################################################
582 virtual void process(jevois::InputFrame && inframe, jevois::GUIhelper & helper) override
583 {
584 static jevois::Timer timer("processing", 100, LOG_DEBUG);
585
586 // Start the GUI frame:
587 unsigned short winw, winh;
588 helper.startFrame(winw, winh);
589
590 // Draw the full-resolution camera frame:
591 int x = 0, y = 0; unsigned short iw = 0, ih = 0;
592 helper.drawInputFrame("camera", inframe, x, y, iw, ih);
593 helper.itext("JeVois-Pro Camera Calibration");
594
595 // Wait for next available camera image at processing resolution, get it as RGB:
596 cv::Mat cvimg = inframe.getCvRGBp();
597 itsImageSize.width = cvimg.cols;
598 itsImageSize.height = cvimg.rows;
599 inframe.done();
600
601 timer.start();
602
603 // Detect/calibrate, will update itsCalibrated and itsLastGoodView:
604 process_frame(cvimg); // fixme they want bgr!
605
606 // If we are now calibrated, show live view, possibly undistorted:
607 if (itsCalibrated)
608 {
609 helper.itext("Camera is now calibrated - average reprojection error = " + std::to_string(itsAvgErr));
610 if (showUndistorted::get())
611 helper.itext("Showing undistorted view. Turn off showUndistorted to see normal view");
612 else
613 helper.itext("Showing normal view. Turn on showUndistorted to see undistorted view");
614
615 int vx = 0, vy = 0; unsigned short vw = 0, vh = 0;
616 helper.drawImage("v", itsLastGoodView, true /*rgb*/, vx, vy, vw, vh, false, true);
617 }
618 else
619 {
620 // Show some guiding messages:
621 helper.itext("Good calibration board views so far: " + std::to_string(itsImagePoints.size()));
622 if (itsImagePoints.size() >= 5)
623 helper.itext("Enough good board views acquired for calibration, you may grab more to improve accuracy,"
624 " or calibrate now.");
625 else
626 helper.itext("Need at least 5 good board views for calibration, keep grabbing, use varied viewpoints");
627
628 // Display last good view for a while, otherwise nothing (live video already drawn):
629 std::chrono::duration<float> const elapsed = std::chrono::steady_clock::now() - itsLastGoodTime;
630 if (elapsed.count() < 2.0F && itsLastGoodView.empty() == false)
631 {
632 helper.itext("Calibration board successfully detected");
633 int vx = 0, vy = 0; unsigned short vw = 0, vh = 0;
634 helper.drawImage("v", itsLastGoodView, true /*rgb*/, vx, vy, vw, vh, false, true);
635 }
636 }
637
638 // Draw a user interface:
639
640 // Set window size applied only on first use ever, otherwise from imgui.ini:
641 ImGui::SetNextWindowPos(ImVec2(100, 100), ImGuiCond_FirstUseEver);
642 ImGui::SetNextWindowSize(ImVec2(500, 400), ImGuiCond_FirstUseEver);
643
644 // Light blue window background:
645 ImGui::PushStyleColor(ImGuiCol_WindowBg, 0xf0ffe0e0);
646
647 if (ImGui::Begin("Calibrate Camera Controls"))
648 {
649 int wrap = ImGui::GetWindowSize().x - ImGui::GetFontSize() * 2.0f;
650 ImGui::PushTextWrapPos(wrap);
651
652 if (itsCalibrated)
653 {
654 ImGui::TextUnformatted("Camera is now calibrated and calibration was saved to disk.");
655 ImGui::TextUnformatted("");
656 ImGui::Text("Average reprojection error: %f (lower is better)", itsAvgErr);
657 ImGui::TextUnformatted("");
658 ImGui::Separator();
659
660 if (ImGui::Button("Grab more views")) itsCalibrated = false;
661 }
662 else if (itsReady == false)
663 {
664 if (itsImagePoints.empty())
665 {
666 ImGui::TextUnformatted("To get started, switch to the Parameters tab of the main window, "
667 "and set some parameters.");
668 ImGui::TextUnformatted("");
669 ImGui::TextUnformatted("Critical parameters are:");
670 ImGui::TextUnformatted("");
671 ImGui::Bullet();
672 ImGui::Text("pattern - choose a board type (chessboard, ChArUco, etc)");
673 ImGui::Bullet();
674 ImGui::Text("fishEye - whether you are using a fish-eye (wide angle) lens");
675 ImGui::Bullet();
676 ImGui::Text("squareSize - physical size in your chosen units (mm, inch, etc) of one board square");
677 ImGui::Bullet();
678 ImGui::Text("markerSize - if using ChArUco, physical size of markers in your units");
679 ImGui::Bullet();
680 ImGui::Text("boardSize - horizontal and vertical number of tiles");
681
682 ImGui::TextUnformatted("");
683 ImGui::Separator();
684 }
685 itsReady = ImGui::Button("Ready!");
686 }
687 else
688 {
689 ImGui::TextUnformatted("Point the camera so that you get a full view of the calibration board, "
690 "then click Grab.");
691 if (itsImagePoints.empty() == false)
692 {
693 ImGui::TextUnformatted("");
694 ImGui::TextUnformatted("Move the camera around to get a variety of viewpoints.");
695 ImGui::TextUnformatted("Need at least 5 valid viewpoints. The more the better.");
696 ImGui::TextUnformatted("");
697 ImGui::Text("Good board views so far: %zu", itsImagePoints.size());
698 }
699 ImGui::TextUnformatted("");
700 ImGui::Separator();
701 if (ImGui::Button("Grab")) grab::set(true);
702 if (itsImagePoints.size() >= 5)
703 {
704 ImGui::SameLine(); ImGui::TextUnformatted(" "); ImGui::SameLine();
705 if (ImGui::Button("Calibrate now")) calibrate::set(true);
706 }
707 }
708
709 // Always show a start over button, except at the every beginning:
710 if (itsReady)
711 {
712 ImGui::SameLine(); ImGui::TextUnformatted(" "); ImGui::SameLine();
713 if (ImGui::Button("Start over")) restart();
714 }
715
716 ImGui::PopTextWrapPos();
717 }
718
719 ImGui::End();
720 ImGui::PopStyleColor();
721
722 // Show processing fps:
723 std::string const & fpscpu = timer.stop();
724 helper.iinfo(inframe, fpscpu, winw, winh);
725
726 // Render the image and GUI:
727 helper.endFrame();
728 }
729#endif
730
731 protected:
732 // Restart if some params changed:
733 void restart()
734 {
735 itsChArUcoDetector.reset();
736 itsReady = false;
737 itsAvgErr = 0.0;
738 itsCalibrated = false;
739 itsImagePoints.clear();
740 }
741
742 //! Restart when some critical params are changed:
743 virtual void onParamChange(pattern const & par, Pattern const & val) { restart(); }
744 virtual void onParamChange(dictionary const & par, aruco::Dict const & val) { restart(); }
745 virtual void onParamChange(boardSize const & par, cv::Size const & val) { restart(); }
746
747 private:
748 bool itsReady = false;
749 bool itsCalibrated = false;
750 int itsFlag = 0;
751 cv::Size itsImageSize;
752 std::vector<std::vector<cv::Point2f> > itsImagePoints;
753 cv::Mat itsCameraMatrix = cv::Mat::eye(3, 3, CV_64F);
754 cv::Mat itsDistCoeffs = cv::Mat::zeros(8, 1, CV_64F);
755 cv::Mat itsLastGoodView;
756 std::chrono::time_point<std::chrono::steady_clock> itsLastGoodTime;
757 std::shared_ptr<cv::aruco::CharucoDetector> itsChArUcoDetector;
758 double itsAvgErr = 0.0;
759};
760
761// Allow the module to be loaded as a shared object (.so) file:
JEVOIS_REGISTER_MODULE(ArUcoBlob)
int h
static cv::aruco::Dictionary getDictionary(aruco::Dict d)
Static method to allow anyone to get the ArUco dictionary for a given value of our dictionary paramet...
Definition ArUco.C:28
Helper module to calibrate a given sensor+lens combo, which allows ArUco and other modules to do 3D p...
JEVOIS_DECLARE_PARAMETER(fishEye, bool, "Use fisheye model. Should be true if using a wide-angle lens that " "produces significant barrel distortion, otherwise false", false, ParamCateg)
Parameter.
JEVOIS_DEFINE_ENUM_CLASS(Pattern,(ChessBoard)(ChArUcoBoard)(CirclesGrid)(AsymmetricCirclesGrid))
Enum for parameter.
JEVOIS_DECLARE_PARAMETER(aspectRatio, float, "Fixed aspect ratio value to use when non-zero, or auto when 0.0", 0.0F, ParamCateg)
Parameter.
void process_frame(cv::Mat const &view)
Process one captured image.
void calcBoardCornerPositions(cv::Size boardsiz, float squaresiz, std::vector< cv::Point3f > &corners)
JEVOIS_DECLARE_PARAMETER(fixPrincipalPoint, bool, "Fix principal point at center, otherwise find its location", true, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(fixK1, bool, "Fix (do not try to optimize) K1 radial distortion parameter", false, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(winSize, unsigned char, "Half of search window size for sub-pixel corner refinement", 11, ParamCateg)
Parameter.
double computeReprojectionErrors(std::vector< std::vector< cv::Point3f > > const &objectPoints, std::vector< cv::Mat > const &rvecs, std::vector< cv::Mat > const &tvecs, std::vector< float > &perViewErrors)
JEVOIS_DECLARE_PARAMETER(fixK2, bool, "Fix (do not try to optimize) K2 radial distortion parameter", false, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(fixK3, bool, "Fix (do not try to optimize) K3 radial distortion parameter", false, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(dictionary, aruco::Dict, "ArUco dictionary to use", aruco::Dict::D4X4_50, aruco::Dict_Values, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(showUndistorted, bool, "Once calibrated, show undistorted image instead of original capture", false, ParamCateg)
Parameter.
virtual void onParamChange(pattern const &par, Pattern const &val)
Restart when some critical params are changed:
virtual void process(jevois::InputFrame &&inframe, jevois::GUIhelper &helper) override
Processing function with zero-copy and GUI on JeVois-Pro.
bool runCalibration(std::vector< cv::Mat > &rvecs, std::vector< cv::Mat > &tvecs, std::vector< float > &reprojErrs, double &totalAvgErr, std::vector< cv::Point3f > &newObjPoints)
JEVOIS_DECLARE_PARAMETER(squareSize, float, "Size of each tile (check) in user-chosen units (e.g., mm, inch, etc). The " "unit used here is the one that will be used once calibrated to report 3D coordinates " "of objects relative to the camera", 23.0f, ParamCateg)
Parameter.
virtual void process(jevois::InputFrame &&inframe, jevois::OutputFrame &&outframe) override
Processing function with video output to USB.
JEVOIS_DECLARE_PARAMETER(markerSize, float, "ChArUco marker size in user-chosen units (e.g., mm, inch, " "etc). The unit used here is the one that will be used once calibrated to report 3D " "coordinates of objects relative to the camera", 27.0f, ParamCateg)
Parameter.
virtual void onParamChange(dictionary const &par, aruco::Dict const &val)
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(boardSize, cv::Size, "Board size [width height] in number of horizontal and " "vertical tiles/disks. (Note: for asymmetric circle grid, count the number of " "disks on each row, then the number of rows). The product width * height " "should be the total number of tiles/disks on the grid.)", { 11, 7 }, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(calibrate, bool, "Calibrate using all the grabbed boards so far. You first need to grab " "enough good views of your calibration board before you can calibrate.", false, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(pattern, Pattern, "Type of calibration board pattern to use", Pattern::ChessBoard, Pattern_Values, ParamCateg)
Parameter.
JEVOIS_DECLARE_PARAMETER(grab, bool, "Grab one image, try to detect the calibration pattern, and add to list of " "detected patterns so far. Click this for at least 5 images showing your calibration board " "under various viewpoints. When enough boards have been successfully captured, click " "'calibrate'", false, ParamCateg)
Parameter.
virtual ~CalibrateCamera()
Virtual destructor for safe inheritance.
JEVOIS_DECLARE_PARAMETER(zeroTangentDist, bool, "Assume zero tangential distortion coefficients P1, P2 and do " "not try to optimize them, i.e., assume board is exactly planar", true, ParamCateg)
Parameter.
virtual void onParamChange(boardSize const &par, cv::Size const &val)
jevois::CameraLens lens
jevois::CameraSensor sensor
friend friend class Module
void drawInputFrame(char const *name, InputFrame const &frame, int &x, int &y, unsigned short &w, unsigned short &h, bool noalias=false, bool casync=false)
bool startFrame(unsigned short &w, unsigned short &h)
void iinfo(jevois::InputFrame const &inframe, std::string const &fpscpu, unsigned short winw=0, unsigned short winh=0)
void itext(char const *txt, ImU32 const &col=IM_COL32_BLACK_TRANS, int line=-1)
void drawImage(char const *name, RawImage const &img, int &x, int &y, unsigned short &w, unsigned short &h, bool noalias=false, bool isoverlay=false)
unsigned int width
unsigned int height
void require(char const *info, unsigned int w, unsigned int h, unsigned int f) const
std::string const & stop(double *seconds)
#define LINFO(msg)
void paste(RawImage const &src, RawImage &dest, int dx, int dy)
void writeText(RawImage &img, std::string const &txt, int x, int y, unsigned int col, Font font=Font6x10)
void drawFilledRect(RawImage &img, int x, int y, unsigned int w, unsigned int h, unsigned int col)
cv::Mat convertToCvBGR(RawImage const &src)
int itext(RawImage &img, std::string const &txt, int y=3, unsigned int col=jevois::yuyv::White, Font font=Font6x10)
void pasteBGRtoYUYV(cv::Mat const &src, RawImage &dst, int dx, int dy)
std::future< std::invoke_result_t< std::decay_t< Function >, std::decay_t< Args >... > > async(Function &&f, Args &&... args)
unsigned short constexpr Black
unsigned short constexpr White