1
0
mirror of https://github.com/opencv/opencv_contrib.git synced 2025-10-18 08:44:11 +08:00

Update atuco calibration tutorials and faq

This commit is contained in:
Sergei Shutov
2023-01-04 17:58:11 +02:00
parent e247b680a6
commit 46e94a2262
4 changed files with 229 additions and 274 deletions

View File

@@ -1,50 +1,10 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
#include <opencv2/highgui.hpp>
#include <opencv2/calib3d.hpp>
#include <opencv2/objdetect/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib.hpp>
#include <opencv2/imgproc.hpp>
#include <vector>
#include <iostream>
#include <ctime>
#include <iostream>
#include <vector>
#include <opencv2/calib3d.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/objdetect.hpp>
#include "aruco_samples_utility.hpp"
using namespace std;
@@ -138,7 +98,9 @@ int main(int argc, char *argv[]) {
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(dictionaryId));
dictionary = aruco::getPredefinedDictionary(
aruco::PredefinedDictionaryType(dictionaryId)
);
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("cd"), FileStorage::READ);
@@ -153,14 +115,16 @@ int main(int argc, char *argv[]) {
return 0;
}
// create board object
Ptr<aruco::GridBoard> gridboard = new aruco::GridBoard(Size(markersX, markersY), markerLength, markerSeparation, dictionary);
// Create board object
Ptr<aruco::GridBoard> gridboard = new aruco::GridBoard(
Size(markersX, markersY), markerLength, markerSeparation, dictionary
);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
// collected frames for calibration
vector< vector< vector< Point2f > > > allCorners;
vector< vector< int > > allIds;
Size imgSize;
// Collected frames for calibration
vector<vector<vector<Point2f>>> allMarkerCorners;
vector<vector<int>> allMarkerIds;
Size imageSize;
aruco::ArucoDetector detector(dictionary, detectorParams);
@@ -168,65 +132,90 @@ int main(int argc, char *argv[]) {
Mat image, imageCopy;
inputVideo.retrieve(image);
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
vector<int> markerIds;
vector<vector<Point2f>> markerCorners, rejectedMarkers;
// detect markers
detector.detectMarkers(image, corners, ids, rejected);
// Detect markers
detector.detectMarkers(image, markerCorners, markerIds, rejectedMarkers);
// refind strategy to detect more markers
if(refindStrategy) detector.refineDetectedMarkers(image, *board, corners, ids, rejected);
// Refind strategy to detect more markers
if(refindStrategy) {
detector.refineDetectedMarkers(
image, *board, markerCorners, markerIds, rejectedMarkers
);
}
// draw results
// Draw results
image.copyTo(imageCopy);
if(ids.size() > 0) aruco::drawDetectedMarkers(imageCopy, corners, ids);
putText(imageCopy, "Press 'c' to add current frame. 'ESC' to finish and calibrate",
Point(10, 20), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255, 0, 0), 2);
if(!markerIds.empty()) {
aruco::drawDetectedMarkers(imageCopy, markerCorners, markerIds);
}
putText(
imageCopy, "Press 'c' to add current frame. 'ESC' to finish and calibrate",
Point(10, 20), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255, 0, 0), 2
);
imshow("out", imageCopy);
// Wait for key pressed
char key = (char)waitKey(waitTime);
if(key == 27) break;
if(key == 'c' && ids.size() > 0) {
if(key == 27) {
break;
}
if(key == 'c' && !markerIds.empty()) {
cout << "Frame captured" << endl;
allCorners.push_back(corners);
allIds.push_back(ids);
imgSize = image.size();
allMarkerCorners.push_back(markerCorners);
allMarkerIds.push_back(markerIds);
imageSize = image.size();
}
}
if(allIds.size() < 1) {
if(allMarkerIds.empty()) {
cerr << "Not enough captures for calibration" << endl;
return 0;
}
Mat cameraMatrix, distCoeffs;
vector< Mat > rvecs, tvecs;
double repError;
if(calibrationFlags & CALIB_FIX_ASPECT_RATIO) {
cameraMatrix = Mat::eye(3, 3, CV_64F);
cameraMatrix.at< double >(0, 0) = aspectRatio;
cameraMatrix.at<double>(0, 0) = aspectRatio;
}
// prepare data for calibration
vector< vector< Point2f > > allCornersConcatenated;
vector< int > allIdsConcatenated;
vector< int > markerCounterPerFrame;
markerCounterPerFrame.reserve(allCorners.size());
for(unsigned int i = 0; i < allCorners.size(); i++) {
markerCounterPerFrame.push_back((int)allCorners[i].size());
for(unsigned int j = 0; j < allCorners[i].size(); j++) {
allCornersConcatenated.push_back(allCorners[i][j]);
allIdsConcatenated.push_back(allIds[i][j]);
// Prepare data for calibration
vector<Point3f> objectPoints;
vector<Point2f> imagePoints;
vector<Mat> processedObjectPoints, processedImagePoints;
size_t nFrames = allMarkerCorners.size();
for(size_t frame = 0; frame < nFrames; frame++) {
Mat currentImgPoints, currentObjPoints;
board->matchImagePoints(
allMarkerCorners[frame], allMarkerIds[frame],
currentObjPoints, currentImgPoints
);
if(currentImgPoints.total() > 0 && currentObjPoints.total() > 0) {
processedImagePoints.push_back(currentImgPoints);
processedObjectPoints.push_back(currentObjPoints);
}
}
// calibrate camera
repError = aruco::calibrateCameraAruco(allCornersConcatenated, allIdsConcatenated,
markerCounterPerFrame, board, imgSize, cameraMatrix,
distCoeffs, rvecs, tvecs, calibrationFlags);
bool saveOk = saveCameraParams(outputFile, imgSize, aspectRatio, calibrationFlags, cameraMatrix,
distCoeffs, repError);
// Calibrate camera
double repError = calibrateCamera(
processedObjectPoints, processedImagePoints, imageSize,
cameraMatrix, distCoeffs, noArray(), noArray(), noArray(),
noArray(), noArray(), calibrationFlags
);
bool saveOk = saveCameraParams(
outputFile, imageSize, aspectRatio, calibrationFlags, cameraMatrix,
distCoeffs, repError
);
if(!saveOk) {
cerr << "Cannot save output file" << endl;

View File

@@ -1,48 +1,9 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
#include <opencv2/highgui.hpp>
#include <opencv2/calib3d.hpp>
#include <opencv2/aruco/charuco.hpp>
#include <opencv2/imgproc.hpp>
#include <vector>
#include <iostream>
#include <vector>
#include <opencv2/calib3d.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/objdetect.hpp>
#include "aruco_samples_utility.hpp"
using namespace std;
@@ -102,10 +63,10 @@ int main(int argc, char *argv[]) {
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
aruco::DetectorParameters detectorParams = aruco::DetectorParameters();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
bool readOk = detectorParams->readDetectorParameters(fs.root());
bool readOk = detectorParams.readDetectorParameters(fs.root());
if(!readOk) {
cerr << "Invalid detector parameters file" << endl;
return 0;
@@ -153,146 +114,131 @@ int main(int argc, char *argv[]) {
return 0;
}
// create charuco board object
Ptr<aruco::CharucoBoard> charucoboard = new aruco::CharucoBoard(Size(squaresX, squaresY), squareLength, markerLength, dictionary);
Ptr<aruco::Board> board = charucoboard.staticCast<aruco::Board>();
// Create charuco board object
aruco::CharucoBoard board(Size(squaresX, squaresY), squareLength, markerLength, dictionary);
aruco::CharucoParameters charucoParams;
// collect data from each frame
vector< vector< vector< Point2f > > > allCorners;
vector< vector< int > > allIds;
vector< Mat > allImgs;
Size imgSize;
if(refindStrategy) {
charucoParams.tryRefineMarkers = true;
}
aruco::CharucoDetector detector(board, charucoParams, detectorParams);
// Collect data from each frame
vector<Mat> allCharucoCorners;
vector<Mat> allCharucoIds;
vector<vector<Point2f>> allImagePoints;
vector<vector<Point3f>> allObjectPoints;
vector<Mat> allImages;
Size imageSize;
while(inputVideo.grab()) {
Mat image, imageCopy;
inputVideo.retrieve(image);
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
vector<int> markerIds;
vector<vector<Point2f>> markerCorners, rejectedMarkers;
Mat currentCharucoCorners;
Mat currentCharucoIds;
vector<Point3f> currentObjectPoints;
vector<Point2f> currentImagePoints;
// detect markers
aruco::detectMarkers(image, makePtr<aruco::Dictionary>(dictionary), corners, ids, detectorParams, rejected);
// Detect ChArUco board
detector.detectBoard(image, currentCharucoCorners, currentCharucoIds);
// refind strategy to detect more markers
if(refindStrategy) aruco::refineDetectedMarkers(image, board, corners, ids, rejected);
// interpolate charuco corners
Mat currentCharucoCorners, currentCharucoIds;
if(ids.size() > 0)
aruco::interpolateCornersCharuco(corners, ids, image, charucoboard, currentCharucoCorners,
currentCharucoIds);
// draw results
// Draw results
image.copyTo(imageCopy);
if(ids.size() > 0) aruco::drawDetectedMarkers(imageCopy, corners);
if(!markerIds.empty()) {
aruco::drawDetectedMarkers(imageCopy, markerCorners);
}
if(currentCharucoCorners.total() > 0)
if(currentCharucoCorners.total() > 3) {
aruco::drawDetectedCornersCharuco(imageCopy, currentCharucoCorners, currentCharucoIds);
}
putText(imageCopy, "Press 'c' to add current frame. 'ESC' to finish and calibrate",
Point(10, 20), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255, 0, 0), 2);
imshow("out", imageCopy);
// Wait for key pressed
char key = (char)waitKey(waitTime);
if(key == 27) break;
if(key == 'c' && ids.size() > 0) {
if(key == 27) {
break;
}
if(key == 'c' && currentCharucoCorners.total() > 3) {
// Match image points
board.matchImagePoints(currentCharucoCorners, currentCharucoIds, currentObjectPoints, currentImagePoints);
if(currentImagePoints.empty() || currentObjectPoints.empty()) {
cout << "Point matching failed, try again." << endl;
continue;
}
cout << "Frame captured" << endl;
allCorners.push_back(corners);
allIds.push_back(ids);
allImgs.push_back(image);
imgSize = image.size();
allCharucoCorners.push_back(currentCharucoCorners);
allCharucoIds.push_back(currentCharucoIds);
allImagePoints.push_back(currentImagePoints);
allObjectPoints.push_back(currentObjectPoints);
allImages.push_back(image);
imageSize = image.size();
}
}
if(allIds.size() < 1) {
cerr << "Not enough captures for calibration" << endl;
return 0;
}
Mat cameraMatrix, distCoeffs;
vector< Mat > rvecs, tvecs;
double repError;
if(calibrationFlags & CALIB_FIX_ASPECT_RATIO) {
cameraMatrix = Mat::eye(3, 3, CV_64F);
cameraMatrix.at< double >(0, 0) = aspectRatio;
}
// prepare data for calibration
vector< vector< Point2f > > allCornersConcatenated;
vector< int > allIdsConcatenated;
vector< int > markerCounterPerFrame;
markerCounterPerFrame.reserve(allCorners.size());
for(unsigned int i = 0; i < allCorners.size(); i++) {
markerCounterPerFrame.push_back((int)allCorners[i].size());
for(unsigned int j = 0; j < allCorners[i].size(); j++) {
allCornersConcatenated.push_back(allCorners[i][j]);
allIdsConcatenated.push_back(allIds[i][j]);
}
}
// calibrate camera using aruco markers
double arucoRepErr;
arucoRepErr = aruco::calibrateCameraAruco(allCornersConcatenated, allIdsConcatenated,
markerCounterPerFrame, board, imgSize, cameraMatrix,
distCoeffs, noArray(), noArray(), calibrationFlags);
// prepare data for charuco calibration
int nFrames = (int)allCorners.size();
vector< Mat > allCharucoCorners;
vector< Mat > allCharucoIds;
vector< Mat > filteredImages;
allCharucoCorners.reserve(nFrames);
allCharucoIds.reserve(nFrames);
for(int i = 0; i < nFrames; i++) {
// interpolate using camera parameters
Mat currentCharucoCorners, currentCharucoIds;
aruco::interpolateCornersCharuco(allCorners[i], allIds[i], allImgs[i], charucoboard,
currentCharucoCorners, currentCharucoIds, cameraMatrix,
distCoeffs);
allCharucoCorners.push_back(currentCharucoCorners);
allCharucoIds.push_back(currentCharucoIds);
filteredImages.push_back(allImgs[i]);
}
if(allCharucoCorners.size() < 4) {
cerr << "Not enough corners for calibration" << endl;
return 0;
}
// calibrate camera using charuco
repError =
aruco::calibrateCameraCharuco(allCharucoCorners, allCharucoIds, charucoboard, imgSize,
cameraMatrix, distCoeffs, rvecs, tvecs, calibrationFlags);
Mat cameraMatrix, distCoeffs;
if(calibrationFlags & CALIB_FIX_ASPECT_RATIO) {
cameraMatrix = Mat::eye(3, 3, CV_64F);
cameraMatrix.at<double>(0, 0) = aspectRatio;
}
// Calibrate camera using ChArUco
double repError = calibrateCamera(
allObjectPoints, allImagePoints, imageSize,
cameraMatrix, distCoeffs, noArray(), noArray(), noArray(),
noArray(), noArray(), calibrationFlags
);
bool saveOk = saveCameraParams(
outputFile, imageSize, aspectRatio, calibrationFlags,
cameraMatrix, distCoeffs, repError
);
bool saveOk = saveCameraParams(outputFile, imgSize, aspectRatio, calibrationFlags,
cameraMatrix, distCoeffs, repError);
if(!saveOk) {
cerr << "Cannot save output file" << endl;
return 0;
}
cout << "Rep Error: " << repError << endl;
cout << "Rep Error Aruco: " << arucoRepErr << endl;
cout << "Calibration saved to " << outputFile << endl;
// show interpolated charuco corners for debugging
// Show interpolated charuco corners for debugging
if(showChessboardCorners) {
for(unsigned int frame = 0; frame < filteredImages.size(); frame++) {
Mat imageCopy = filteredImages[frame].clone();
if(allIds[frame].size() > 0) {
for(size_t frame = 0; frame < allImages.size(); frame++) {
Mat imageCopy = allImages[frame].clone();
if(allCharucoCorners[frame].total() > 0) {
aruco::drawDetectedCornersCharuco( imageCopy, allCharucoCorners[frame],
allCharucoIds[frame]);
}
if(allCharucoCorners[frame].total() > 0) {
aruco::drawDetectedCornersCharuco(
imageCopy, allCharucoCorners[frame], allCharucoIds[frame]
);
}
imshow("out", imageCopy);
char key = (char)waitKey(0);
if(key == 27) break;
if(key == 27) {
break;
}
}
}

View File

@@ -33,40 +33,58 @@ visible in all the viewpoints.
![ChArUco calibration viewpoints](images/charucocalibration.png)
The function to calibrate is ```calibrateCameraCharuco()```. Example:
The function to calibrate is `cv::calibrateCamera()`. Example:
@code{.cpp}
cv::Ptr<aruco::CharucoBoard> board = ... // create charuco board
cv::Size imgSize = ... // camera image size
Ptr<aruco::CharucoBoard> board = ... // create charuco board
Size imageSize = ... // camera image size
std::vector<std::vector<cv::Point2f>> allCharucoCorners;
std::vector<std::vector<int>> allCharucoIds;
// Detect charuco board from several viewpoints and fill allCharucoCorners and allCharucoIds
...
...
vector<vector<Point2f>> allCharucoCorners;
vector<vector<int>> allCharucoIds;
vector<vector<Point2f>> allImagePoints;
vector<vector<Point3f>> allObjectPoints;
// Detect charuco board from several viewpoints and fill
// allCharucoCorners, allCharucoIds, allImagePoints and allObjectPoints
while(inputVideo.grab()) {
detector.detectBoard(
image, currentCharucoCorners, currentCharucoIds
);
board.matchImagePoints(
currentCharucoCorners, currentCharucoIds,
currentObjectPoints, currentImagePoints
);
...
}
// After capturing in several viewpoints, start calibration
cv::Mat cameraMatrix, distCoeffs;
std::vector<cv::Mat> rvecs, tvecs;
int calibrationFlags = ... // Set calibration flags (same than in calibrateCamera() function)
Mat cameraMatrix, distCoeffs;
vector<Mat> rvecs, tvecs;
double repError = cv::aruco::calibrateCameraCharuco(allCharucoCorners, allCharucoIds, board, imgSize, cameraMatrix, distCoeffs, rvecs, tvecs, calibrationFlags);
// Set calibration flags (same than in calibrateCamera() function)
int calibrationFlags = ...
double repError = calibrateCamera(
allObjectPoints, allImagePoints, imageSize,
cameraMatrix, distCoeffs, rvecs, tvecs, noArray(),
noArray(), noArray(), calibrationFlags
);
@endcode
The ChArUco corners and ChArUco identifiers captured on each viewpoint are stored in the vectors ```allCharucoCorners``` and ```allCharucoIds```, one element per viewpoint.
The ```calibrateCameraCharuco()``` function will fill the ```cameraMatrix``` and ```distCoeffs``` arrays with the camera calibration parameters. It will return the reprojection
error obtained from the calibration. The elements in ```rvecs``` and ```tvecs``` will be filled with the estimated pose of the camera (respect to the ChArUco board)
The `calibrateCamera()` function will fill the `cameraMatrix` and `distCoeffs` arrays with the camera calibration parameters. It will return the reprojection
error obtained from the calibration. The elements in `rvecs` and `tvecs` will be filled with the estimated pose of the camera (respect to the ChArUco board)
in each of the viewpoints.
Finally, the ```calibrationFlags``` parameter determines some of the options for the calibration. Its format is equivalent to the flags parameter in the OpenCV
```calibrateCamera()``` function.
Finally, the `calibrationFlags` parameter determines some of the options for the calibration.
A full working example is included in the `calibrate_camera_charuco.cpp` inside the `modules/aruco/samples/`.
A full working example is included in the `calibrate_camera_charuco.cpp` inside the `samples` folder.
Note: The samples now take input via commandline via the [OpenCV Commandline Parser](http://docs.opencv.org/trunk/d0/d2e/classcv_1_1CommandLineParser.html#gsc.tab=0). For this file the example parameters will look like
@code{.cpp}
"output_path/camera_calib.txt" -w=5 -h=7 -sl=0.04 -ml=0.02 -d=10
"camera_calib.txt" -w=5 -h=7 -sl=0.04 -ml=0.02 -d=10
-v="path_aruco/tutorials/aruco_calibration/images/img_%02d.jpg
-c=path_aruco/samples/tutorial_camera_params.yml
@endcode
@@ -78,40 +96,43 @@ Calibration with ArUco Boards
As it has been stated, it is recommended the use of ChAruco boards instead of ArUco boards for camera calibration, since
ChArUco corners are more accurate than marker corners. However, in some special cases it must be required to use calibration
based on ArUco boards. For these cases, the ```calibrateCameraAruco()``` function is provided. As in the previous case, it
requires the detections of an ArUco board from different viewpoints.
based on ArUco boards. As in the previous case, it requires the detections of an ArUco board from different viewpoints.
![ArUco calibration viewpoints](images/arucocalibration.png)
Example of ```calibrateCameraAruco()``` use:
@code{.cpp}
cv::Ptr<aruco::Board> board = ... // create aruco board
cv::Size imgSize = ... // camera image size
Ptr<aruco::Board> board = ... // create aruco board
Size imgSize = ... // camera image size
std::vector<std::vector<cv::Point2f>> allCornersConcatenated;
std::vector<int> allIdsConcatenated;
std::vector<int> markerCounterPerFrame;
// Detect aruco board from several viewpoints and fill allCornersConcatenated, allIdsConcatenated and markerCounterPerFrame
...
vector<vector<vector<Point2f>>> allMarkerCorners;
vector<vector<int>> allMarkerIds;
// Detect aruco board from several viewpoints and fill allMarkerCorners, allMarkerIds
detector.detectMarkers(image, markerCorners, markerIds, rejectedMarkers);
...
// After capturing in several viewpoints, start calibration
cv::Mat cameraMatrix, distCoeffs;
std::vector<cv::Mat> rvecs, tvecs;
// After capturing in several viewpoints, match image points and start calibration
board->matchImagePoints(
allMarkerCorners[frame], allMarkerIds[frame],
currentObjPoints, currentImgPoints
);
Mat cameraMatrix, distCoeffs;
vector<Mat> rvecs, tvecs;
int calibrationFlags = ... // Set calibration flags (same than in calibrateCamera() function)
double repError = cv::aruco::calibrateCameraAruco(allCornersConcatenated, allIdsConcatenated, markerCounterPerFrame, board, imgSize, cameraMatrix, distCoeffs, rvecs, tvecs, calibrationFlags);
double repError = calibrateCamera(
processedObjectPoints, processedImagePoints, imageSize,
cameraMatrix, distCoeffs, rvecs, tvecs, noArray(),
noArray(), noArray(), calibrationFlags
);
@endcode
In this case, and contrary to the ```calibrateCameraCharuco()``` function, the detected markers on each viewpoint are concatenated in the arrays ```allCornersConcatenated``` and
```allCornersConcatenated``` (the first two parameters). The third parameter, the array ```markerCounterPerFrame```, indicates the number of marker detected on each viewpoint.
The rest of parameters are the same than in ```calibrateCameraCharuco()```, except the board layout object which does not need to be a ```CharucoBoard``` object, it can be
any ```Board``` object.
A full working example is included in the `calibrate_camera.cpp` inside the `modules/aruco/samples/`.
A full working example is included in the `calibrate_camera.cpp` inside the `samples` folder.
Note: The samples now take input via commandline via the [OpenCV Commandline Parser](http://docs.opencv.org/trunk/d0/d2e/classcv_1_1CommandLineParser.html#gsc.tab=0). For this file the example parameters will look like
@code{.cpp}
"_path_/calib.txt" -w=5 -h=7 -l=100 -s=10 -d=10
"camera_calib.txt" -w=5 -h=7 -l=100 -s=10 -d=10
@endcode

View File

@@ -128,7 +128,7 @@ If you are using one of the predefined dictionaries, it is not necessary. Otherw
- Do I need to store the Board information in a file so I can use it in different executions?
If you are using a ```GridBoard``` or a ```ChArUco``` board you only need to store the board measurements that are provided to the ```GridBoard::create()``` or ```ChArUco::create()``` functions.
If you are using a ```GridBoard``` or a ```ChArUco``` board you only need to store the board measurements that are provided to the ```GridBoard::create()``` function or in or `ChArUco` constructor.
If you manually modify the marker ids of the boards, or if you use a different type of board, you should save your board object to file.
- Does the aruco module provide functions to save the Dictionary or Board to file?
@@ -158,6 +158,5 @@ It is important to remark that the estimation of the pose using only 4 coplanar
In general, the ambiguity can be solved, if the camera is near to the marker.
However, as the marker becomes small, the errors in the corner estimation grows and ambiguity comes as a problem.
Try increasing the size of the marker you're using, and you can also try non-symmetrical (aruco_dict_utils.cpp) markers to avoid collisions.
Use multiple markers (ArUco/ChArUco/Diamonds boards) and pose estimation with estimatePoseBoard(), estimatePoseCharucoBoard().
Use solvePnP() with the ```SOLVEPNP_IPPE_SQUARE``` option.
Use multiple markers (ArUco/ChArUco/Diamonds boards) and pose estimation with solvePnP() with the ```SOLVEPNP_IPPE_SQUARE``` option.
More in [this issue](https://github.com/opencv/opencv/issues/8813).