Optimize calibrateCamera with Schur‑complement LM and parallel Jacobian accumulation#28461
Optimize calibrateCamera with Schur‑complement LM and parallel Jacobian accumulation#28461asmorkalov merged 8 commits intoopencv:4.xfrom
Conversation
|
@Ron12777 Thanks a lot for the contribution. It looks very promising!
|
…pdated header with modernized info.
| CALIB_USE_LU = (1 << 17), //!< use LU instead of SVD decomposition for solving. much faster but potentially less precise | ||
| CALIB_USE_EXTRINSIC_GUESS = (1 << 22) //!< for stereoCalibrate | ||
| CALIB_USE_EXTRINSIC_GUESS = (1 << 22), //!< for stereoCalibrate | ||
| CALIB_USE_LEGACY = (1 << 23) //!< use legacy calibrateCamera implementation |
There was a problem hiding this comment.
The name is not clear, because the algorithm evolves in time and we always have some legacy behaviour. I propose to name it CALIB_DISABLE_SCHUR_COMPLEMENT or similar to describe the logic change.
modules/calib3d/src/calibration.cpp
Outdated
| Size imageSize, int iFixedPoint, Mat& cameraMatrix, Mat& distCoeffs, | ||
| Mat rvecs, Mat tvecs, Mat newObjPoints, Mat stdDevs, | ||
| Mat perViewErr, int flags, const TermCriteria& termCrit ) | ||
| static double calibrateCameraInternalLegacy( const Mat& objectPoints, |
There was a problem hiding this comment.
Please move the notes about Matlab calibration engine by Jean-Yves Bouguet here. Also I propose to rename the function with Jean-Yves name or similar as "legacy" is not meaningful name for the algorithm.
modules/calib3d/src/calibration.cpp
Outdated
| return std::sqrt(reprojErr/total); | ||
| } | ||
|
|
||
| static double calibrateCameraInternal( const Mat& objectPoints, |
There was a problem hiding this comment.
Similar naming here too.
|
A note on the |
|
I cannot speak about the maths as I am not an expert on this topic. Since this method will be the default one, in my opinion it should be verified on multiple datasets that the current and the PR methods give the same results. Could be:
The main deviation between the current and the PR seems to be about the distortion parameters estimation. The global reprojection error could also be worth to be plotted. Maybe the new solver gives better estimated parameters, maybe not. For my uses cases, camera calibration is an offline procedure, is performed once, so computation time is not critical wrt. to calibration accuracy. And I would want to be sure that there is no regression. About the camera calibration procedure, I have bookmarked these links:
In short, and from what I have gathered, tilted views up to 45° are important for depth estimation and to estimate the intrinsic parameters (focal length, principal point). Good coverage of the image plane is important for distortion estimation. Usually, the larger the board appears in the image, the better it is. Update Another reference from the DLR CalDe and DLR CalLab calibration tool:
|
I will run some testing on some other datasets (there are a lot of collections of images that people have taken for camera calibration) and will update you guys on what the deviation looks like. |
|
Some investigations:
As you can see, it calculates perfectly fine, except for Terbouche 10 images. N = 7
N = 8
N = 9
N = 10
so it is not an issue with the new solver, the old solver also gets erratic with it. uEye brings in the tilt depth right away so we see it has little deviation with base and fast Also on where this spike comes from: It appears to come from image 127 of my testing images Conclusion: |
|
Fantastic research! Thanks a lot for the great job! |
|
Thanks for providing results on additional datasets. For the Terbouche dataset, it looks like they wanted to strictly acquire images at the working distance? Indeed, a thorough analysis of the calibration results is important to discard problematic images. When looking at the doc, you may want to remove:
and if relevant add your references to the bibtex file: opencv.bib and update the description of the calibrateCamera() function with your approach
|
|
Updated docs. Let me know if there's anything else that should be done before merging. |
|
I have found some good quality datasets: I have done a quick comparison test for curiosity. To create the images list:
To calibrate:
The reprojection error results outputed by the exe between OpenCV 4.x and the PR:
Only for the GoPro Hero 4 I have enabled the k3 distortion term. I have also not tweaked the calibration parameters. |
|
Thanks a lot for the great optimization! |
|
Wahoo ! |










Summary
calibrateCamerafor faster runtime without changing outputs using Schur‑complement LM, Parallel Jacobian accumulation, alongside other optimizations.Performance
Testing repo
Testing
Related
See details at https://github.com/opencv/opencv/wiki/How_to_contribute#making-a-good-pull-request
Patch to opencv_extra has the same branch name.