Commit 31be03a8 authored by Wenfeng CAI's avatar Wenfeng CAI Committed by Alexander Alekhin

Merge pull request #12772 from xoox:calib-release-object

More accurate pinhole camera calibration with imperfect planar target (#12772)
43 commits:

* Add derivatives with respect to object points

Add an output parameter to calculate derivatives of image points with
respect to 3D coordinates of object points. The output jacobian matrix
is a 2Nx3N matrix where N is the number of points.

This commit introduces incompatibility to old function signature.

* Set zero for dpdo matrix before using

dpdo is a sparse matrix with only non-zero value close to major
diagonal. Set it to zero because only elements near major diagonal are
computed.

* Add jacobian columns to projectPoints()

The output jacobian matrix of derivatives with respect to coordinates of
3D object points are added. This might break callers who assume the
columns of jacobian matrix.

* Adapt test code to updated project functions

The test cases for projectPoints() and cvProjectPoints2() are updated to
fit new function signatures.

* Add accuracy test code for dpdo

* Add badarg test for dpdo

* Add new enum item for new calibration method

CALIB_RELEASE_OBJECT is used to whether to release 3D coordinates of
object points. The method was proposed in: K. H. Strobl and G. Hirzinger.
"More Accurate Pinhole Camera Calibration with Imperfect Planar Target".
In Proceedings of the IEEE International Conference on Computer Vision
(ICCV 2011), 1st IEEE Workshop on Challenges and Opportunities in Robot
Perception, Barcelona, Spain, pp. 1068-1075, November 2011.

* Add releasing object method into internal function

It's a simple extension of the standard calibration scheme. We choose to
fix the first and last object point and a user-selected fixed point.

* Add interfaces for extended calibration method

* Refine document for calibrateCamera()

When releasing object points, only the z coordinates of the
objectPoints[0].back is fixed.

* Add link to strobl2011iccv paper

* Improve documentation for calibrateCamera()

* Add implementations of wrapping calibrateCamera()

* Add checking for params of new calibration method

If input parameters are not qualified, then fall back to standard
calibration method.

* Add camera calibration method of releasing object

The current implementation is equal to or better than
https://github.com/xoox/calibrel

* Update doc for CALIB_RELEASE_OBJECT

CALIB_USE_QR or CALIB_USE_LU could be used for faster calibration with
potentially less precise and less stable in some rare cases.

* Add RELEASE_OBJECT calibration to tutorial code

To select the calibration method of releasing object points, a command
line parameter `-d=<number>` should be provided.

* Update tutorial doc for camera_calibration

If the method of releasing object points is merged into OpenCV. It will
be expected to be firstly released in 4.1, I think.

* Reduce epsilon for cornerSubPix()

Epsilon of 0.1 is a bigger one. Preciser corner positions are required
with calibration method of releasing object.

* Refine camera calibration tutorial

The hypothesis coordinates are used to indicate which distance must be
measured between two specified object points.

* Update sample calibration code method selection

Similar to camera_calibration tutorial application, a command line
argument `-dt=<number>` is used to select the calibration method.

* Add guard to flags of cvCalibrateCamera2()

cvCalibrateCamera2() doesn't accept CALIB_RELEASE_OBJECT unless overload
interface is added in the future.

* Simplify fallback when iFixedPoint is out of range

* Refactor projectPoints() to keep compatibilities

* Fix arg string "Bad rvecs header"

* Read calibration flags from test data files

Instead of being hard coded into source file, the calibration flags will
be read from test data files.
opencv_extra/testdata/cv/cameracalibration/calib?.dat must be sync with
the test code.

* Add new C interface of cvCalibrateCamera4()

With this new added C interface, the extended calibration method with
CALIB_RELEASE_OBJECT can be called by C API.

* Add regression test of extended calibration method

It has been tested with new added test data in xoox:calib-release-object
branch of opencv_extra.

* Fix assertion in test_cameracalibration.cpp

The total number of refined 3D object coordinates is checked.

* Add checker for iFixedPoint in cvCalibrateCamera4

If iFixedPoint is out of rational range, fall back to standard method.

* Fix documentation for overloaded calibrateCamera()

* Remove calibration flag of CALIB_RELEASE_OBJECT

The method selection is based on the range of the index of fixed point.
For minus values, standard calibration method will be chosen.  Values in
a rational range will make the object-releasing calibration method
selected.

* Use new interfaces instead of function overload

Existing interfaces are preserved and new interfaces are added. Since
most part of the code base are shared, calibrateCamera() is now a
wrapper function of calibrateCameraRO().

* Fix exported name of calibrateCameraRO()

* Update documentation for calibrateCameraRO()

The circumstances where this method is mostly helpful are described.

* Add note on the rigidity of the calibration target

* Update documentation for calibrateCameraRO()

It is clarified that iFixedPoint is used as a switch to select
calibration method. If input data are not qualified, exceptions will be
thrown instead of fallback scheme.

* Clarify iFixedPoint as switch and remove fallback

iFixedPoint is now used as a switch for calibration method selection. No
fallback scheme is utilized anymore. If the input data are not
qualified, exceptions will be thrown.

* Add badarg test for object-releasing method

* Fix document format of sample list

List items of same level should be indented the same way. Otherwise they
will be formatted as nested lists by Doxygen.

* Add brief intro for objectPoints and imagePoints

* Sync tutorial to sample calibration code

* Update tutorial compatibility version to 4.0
parent ca3848d7
......@@ -77,8 +77,8 @@ Source code
You may also find the source code in the `samples/cpp/tutorial_code/calib3d/camera_calibration/`
folder of the OpenCV source library or [download it from here
](https://github.com/opencv/opencv/tree/master/samples/cpp/tutorial_code/calib3d/camera_calibration/camera_calibration.cpp). The program has a
single argument: the name of its configuration file. If none is given then it will try to open the
](https://github.com/opencv/opencv/tree/master/samples/cpp/tutorial_code/calib3d/camera_calibration/camera_calibration.cpp). For the usage of the program, run it with `-h` argument. The program has an
essential argument: the name of its configuration file. If none is given then it will try to open the
one named "default.xml". [Here's a sample configuration file
](https://github.com/opencv/opencv/tree/master/samples/cpp/tutorial_code/calib3d/camera_calibration/in_VID5.xml) in XML format. In the
configuration file you may choose to use camera as an input, a video file or an image list. If you
......@@ -131,6 +131,8 @@ Explanation
Similar images result in similar equations, and similar equations at the calibration step will
form an ill-posed problem, so the calibration will fail. For square images the positions of the
corners are only approximate. We may improve this by calling the @ref cv::cornerSubPix function.
(`winSize` is used to control the side length of the search window. Its default value is 11.
`winSzie` may be changed by command line parameter `--winSize=<number>`.)
It will produce better calibration result. After this we add a valid inputs result to the
*imagePoints* vector to collect all of the equations into a single container. Finally, for
visualization feedback purposes we will draw the found points on the input image using @ref
......@@ -170,7 +172,7 @@ of the calibration variables we'll create these variables here and pass on both
calibration and saving function. Again, I'll not show the saving part as that has little in common
with the calibration. Explore the source file in order to find out how and what:
@snippet samples/cpp/tutorial_code/calib3d/camera_calibration/camera_calibration.cpp run_and_save
We do the calibration with the help of the @ref cv::calibrateCamera function. It has the following
We do the calibration with the help of the @ref cv::calibrateCameraRO function. It has the following
parameters:
- The object points. This is a vector of *Point3f* vector that for each input image describes how
......@@ -184,13 +186,33 @@ parameters:
@code{.cpp}
vector<vector<Point3f> > objectPoints(1);
calcBoardCornerPositions(s.boardSize, s.squareSize, objectPoints[0], s.calibrationPattern);
objectPoints[0][s.boardSize.width - 1].x = objectPoints[0][0].x + grid_width;
newObjPoints = objectPoints[0];
objectPoints.resize(imagePoints.size(),objectPoints[0]);
@endcode
@note If your calibration board is inaccurate, unmeasured, roughly planar targets (Checkerboard
patterns on paper using off-the-shelf printers are the most convenient calibration targets and
most of them are not accurate enough.), a method from @cite strobl2011iccv can be utilized to
dramatically improve the accuracies of the estimated camera intrinsic parameters. This new
calibration method will be called if command line parameter `-d=<number>` is provided. In the
above code snippet, `grid_width` is actually the value set by `-d=<number>`. It's the measured
distance between top-left (0, 0, 0) and top-right (s.squareSize*(s.boardSize.width-1), 0, 0)
corners of the pattern grid points. It should be measured precisely with rulers or vernier calipers.
After calibration, newObjPoints will be updated with refined 3D coordinates of object points.
- The image points. This is a vector of *Point2f* vector which for each input image contains
coordinates of the important points (corners for chessboard and centers of the circles for the
circle pattern). We have already collected this from @ref cv::findChessboardCorners or @ref
cv::findCirclesGrid function. We just need to pass it on.
- The size of the image acquired from the camera, video file or the images.
- The index of the object point to be fixed. We set it to -1 to request standard calibration method.
If the new object-releasing method to be used, set it to the index of the top-right corner point
of the calibration board grid. See cv::calibrateCameraRO for detailed explanation.
@code{.cpp}
int iFixedPoint = -1;
if (release_object)
iFixedPoint = s.boardSize.width - 1;
@endcode
- The camera matrix. If we used the fixed aspect ratio option we need to set \f$f_x\f$:
@snippet samples/cpp/tutorial_code/calib3d/camera_calibration/camera_calibration.cpp fixed_aspect
- The distortion coefficient matrix. Initialize with zero.
......@@ -202,11 +224,15 @@ parameters:
coordinate space). The 7-th and 8-th parameters are the output vector of matrices containing in
the i-th position the rotation and translation vector for the i-th object point to the i-th
image point.
- The updated output vector of calibration pattern points. This parameter is ignored with standard
calibration method.
- The final argument is the flag. You need to specify here options like fix the aspect ratio for
the focal length, assume zero tangential distortion or to fix the principal point.
the focal length, assume zero tangential distortion or to fix the principal point. Here we use
CALIB_USE_LU to get faster calibration speed.
@code{.cpp}
double rms = calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix,
distCoeffs, rvecs, tvecs, s.flag|CV_CALIB_FIX_K4|CV_CALIB_FIX_K5);
rms = calibrateCameraRO(objectPoints, imagePoints, imageSize, iFixedPoint,
cameraMatrix, distCoeffs, rvecs, tvecs, newObjPoints,
s.flag | CALIB_USE_LU);
@endcode
- The function returns the average re-projection error. This number gives a good estimation of
precision of the found parameters. This should be as close to zero as possible. Given the
......
......@@ -13,7 +13,7 @@ Although we get most of our images in a 2D format they do come from a 3D world.
- @subpage tutorial_camera_calibration
*Compatibility:* \> OpenCV 2.0
*Compatibility:* \> OpenCV 4.0
*Author:* Bernát Gábor
......
......@@ -39,3 +39,16 @@
year={2013},
publisher={IEEE}
}
@inproceedings{strobl2011iccv,
title={More accurate pinhole camera calibration with imperfect planar target},
author={Strobl, Klaus H. and Hirzinger, Gerd},
booktitle={2011 IEEE International Conference on Computer Vision (ICCV)},
pages={1068-1075},
month={Nov},
year={2011},
address={Barcelona, Spain},
publisher={IEEE},
url={https://elib.dlr.de/71888/1/strobl_2011iccv.pdf},
doi={10.1109/ICCVW.2011.6130369}
}
......@@ -170,7 +170,7 @@ pattern (every view is described by several 3D-2D point correspondences).
*rectification* transformation that makes the camera optical axes parallel.
@note
- A calibration sample for 3 cameras in horizontal position can be found at
- A calibration sample for 3 cameras in horizontal position can be found at
opencv_source_code/samples/cpp/3calibration.cpp
- A calibration sample based on a sequence of images can be found at
opencv_source_code/samples/cpp/calibration.cpp
......@@ -1077,7 +1077,7 @@ The algorithm performs the following steps:
patternSize=cvSize(cols,rows) in findChessboardCorners .
@sa
findChessboardCorners, solvePnP, initCameraMatrix2D, stereoCalibrate, undistort
calibrateCameraRO, findChessboardCorners, solvePnP, initCameraMatrix2D, stereoCalibrate, undistort
*/
CV_EXPORTS_AS(calibrateCameraExtended) double calibrateCamera( InputArrayOfArrays objectPoints,
InputArrayOfArrays imagePoints, Size imageSize,
......@@ -1089,18 +1089,89 @@ CV_EXPORTS_AS(calibrateCameraExtended) double calibrateCamera( InputArrayOfArray
int flags = 0, TermCriteria criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON) );
/** @overload double calibrateCamera( InputArrayOfArrays objectPoints,
/** @overload */
CV_EXPORTS_W double calibrateCamera( InputArrayOfArrays objectPoints,
InputArrayOfArrays imagePoints, Size imageSize,
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray stdDeviations, OutputArray perViewErrors,
int flags = 0, TermCriteria criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON) )
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON) );
/** @brief Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
This function is an extension of calibrateCamera() with the method of releasing object which was
proposed in @cite strobl2011iccv. In many common cases with inaccurate, unmeasured, roughly planar
targets (calibration plates), this method can dramatically improve the precision of the estimated
camera parameters. Both the object-releasing method and standard method are supported by this
function. Use the parameter **iFixedPoint** for method selection. In the internal implementation,
calibrateCamera() is a wrapper for this function.
@param objectPoints Vector of vectors of calibration pattern points in the calibration pattern
coordinate space. See calibrateCamera() for details. If the method of releasing object to be used,
the identical calibration board must be used in each view and it must be fully visible, and all
objectPoints[i] must be the same and all points should be roughly close to a plane. **The calibration
target has to be rigid, or at least static if the camera (rather than the calibration target) is
shifted for grabbing images.**
@param imagePoints Vector of vectors of the projections of calibration pattern points. See
calibrateCamera() for details.
@param imageSize Size of the image used only to initialize the intrinsic camera matrix.
@param iFixedPoint The index of the 3D object point in objectPoints[0] to be fixed. It also acts as
a switch for calibration method selection. If object-releasing method to be used, pass in the
parameter in the range of [1, objectPoints[0].size()-2], otherwise a value out of this range will
make standard calibration method selected. Usually the top-right corner point of the calibration
board grid is recommended to be fixed when object-releasing method being utilized. According to
\cite strobl2011iccv, two other points are also fixed. In this implementation, objectPoints[0].front
and objectPoints[0].back.z are used. With object-releasing method, accurate rvecs, tvecs and
newObjPoints are only possible if coordinates of these three fixed points are accurate enough.
@param cameraMatrix Output 3x3 floating-point camera matrix. See calibrateCamera() for details.
@param distCoeffs Output vector of distortion coefficients. See calibrateCamera() for details.
@param rvecs Output vector of rotation vectors estimated for each pattern view. See calibrateCamera()
for details.
@param tvecs Output vector of translation vectors estimated for each pattern view.
@param newObjPoints The updated output vector of calibration pattern points. The coordinates might
be scaled based on three fixed points. The returned coordinates are accurate only if the above
mentioned three fixed points are accurate. If not needed, noArray() can be passed in. This parameter
is ignored with standard calibration method.
@param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
See calibrateCamera() for details.
@param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
See calibrateCamera() for details.
@param stdDeviationsObjPoints Output vector of standard deviations estimated for refined coordinates
of calibration pattern points. It has the same size and order as objectPoints[0] vector. This
parameter is ignored with standard calibration method.
@param perViewErrors Output vector of the RMS re-projection error estimated for each pattern view.
@param flags Different flags that may be zero or a combination of some predefined values. See
calibrateCamera() for details. If the method of releasing object is used, the calibration time may
be much longer. CALIB_USE_QR or CALIB_USE_LU could be used for faster calibration with potentially
less precise and less stable in some rare cases.
@param criteria Termination criteria for the iterative optimization algorithm.
@return the overall RMS re-projection error.
The function estimates the intrinsic camera parameters and extrinsic parameters for each of the
views. The algorithm is based on @cite Zhang2000, @cite BouguetMCT and @cite strobl2011iccv. See
calibrateCamera() for other detailed explanations.
@sa
calibrateCamera, findChessboardCorners, solvePnP, initCameraMatrix2D, stereoCalibrate, undistort
*/
CV_EXPORTS_W double calibrateCamera( InputArrayOfArrays objectPoints,
InputArrayOfArrays imagePoints, Size imageSize,
CV_EXPORTS_AS(calibrateCameraROExtended) double calibrateCameraRO( InputArrayOfArrays objectPoints,
InputArrayOfArrays imagePoints, Size imageSize, int iFixedPoint,
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray newObjPoints,
OutputArray stdDeviationsIntrinsics,
OutputArray stdDeviationsExtrinsics,
OutputArray stdDeviationsObjPoints,
OutputArray perViewErrors,
int flags = 0, TermCriteria criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON) );
/** @overload */
CV_EXPORTS_W double calibrateCameraRO( InputArrayOfArrays objectPoints,
InputArrayOfArrays imagePoints, Size imageSize, int iFixedPoint,
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray newObjPoints,
int flags = 0, TermCriteria criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON) );
......
......@@ -263,6 +263,22 @@ CVAPI(double) cvCalibrateCamera2( const CvMat* object_points,
CvTermCriteria term_crit CV_DEFAULT(cvTermCriteria(
CV_TERMCRIT_ITER+CV_TERMCRIT_EPS,30,DBL_EPSILON)) );
/* Finds intrinsic and extrinsic camera parameters
from a few views of known calibration pattern */
CVAPI(double) cvCalibrateCamera4( const CvMat* object_points,
const CvMat* image_points,
const CvMat* point_counts,
CvSize image_size,
int iFixedPoint,
CvMat* camera_matrix,
CvMat* distortion_coeffs,
CvMat* rotation_vectors CV_DEFAULT(NULL),
CvMat* translation_vectors CV_DEFAULT(NULL),
CvMat* newObjPoints CV_DEFAULT(NULL),
int flags CV_DEFAULT(0),
CvTermCriteria term_crit CV_DEFAULT(cvTermCriteria(
CV_TERMCRIT_ITER+CV_TERMCRIT_EPS,30,DBL_EPSILON)) );
/* Computes various useful characteristics of the camera from the data computed by
cvCalibrateCamera2 */
CVAPI(void) cvCalibrationMatrixValues( const CvMat *camera_matrix,
......
This diff is collapsed.
......@@ -54,7 +54,7 @@ protected:
void run(int);
void run_func(void) {}
const static int M = 1;
const static int M = 2;
Size imgSize;
Size corSize;
......@@ -67,16 +67,18 @@ protected:
CvMat* imgPts;
CvMat* npoints;
Size imageSize;
int iFixedPoint;
CvMat *cameraMatrix;
CvMat *distCoeffs;
CvMat *rvecs;
CvMat *tvecs;
CvMat *newObjPts;
int flags;
void operator()() const
{
cvCalibrateCamera2(objPts, imgPts, npoints, cvSize(imageSize),
cameraMatrix, distCoeffs, rvecs, tvecs, flags );
cvCalibrateCamera4(objPts, imgPts, npoints, cvSize(imageSize), iFixedPoint,
cameraMatrix, distCoeffs, rvecs, tvecs, newObjPts, flags );
}
};
};
......@@ -97,6 +99,7 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
Mat_<Point2f>(corSize.height, corSize.width, (Point2f*)&exp_corn[0]).copyTo(corners);
CvMat objPts, imgPts, npoints, cameraMatrix, distCoeffs, rvecs, tvecs;
CvMat newObjPts;
Mat zeros(1, sizeof(CvMat), CV_8U, Scalar(0));
C_Caller caller, bad_caller;
......@@ -108,6 +111,7 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
caller.distCoeffs = &distCoeffs;
caller.rvecs = &rvecs;
caller.tvecs = &tvecs;
caller.newObjPts = &newObjPts;
/////////////////////////////
Mat objPts_cpp;
......@@ -117,19 +121,31 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
Mat distCoeffs_cpp;
Mat rvecs_cpp;
Mat tvecs_cpp;
Mat newObjPts_cpp;
objPts_cpp.create(corSize, CV_32FC3);
for(int j = 0; j < corSize.height; ++j)
for(int i = 0; i < corSize.width; ++i)
objPts_cpp.at<Point3f>(j, i) = Point3i(i, j, 0);
objPts_cpp = objPts_cpp.reshape(3, 1);
Mat objPts_cpp_all(1, objPts_cpp.cols * M, CV_32FC3);
for(int i = 0; i < M; i++)
objPts_cpp.copyTo(objPts_cpp_all.colRange(objPts_cpp.cols * i, objPts_cpp.cols * (i + 1)));
objPts_cpp = objPts_cpp_all;
caller.iFixedPoint = -1;
imgPts_cpp = corners.clone().reshape(2, 1);
Mat imgPts_cpp_all(1, imgPts_cpp.cols * M, CV_32FC2);
for(int i = 0; i < M; i++)
imgPts_cpp.copyTo(imgPts_cpp_all.colRange(imgPts_cpp.cols * i, imgPts_cpp.cols * (i + 1)));
imgPts_cpp = imgPts_cpp_all;
npoints_cpp = Mat_<int>(M, 1, corSize.width * corSize.height);
cameraMatrix_cpp.create(3, 3, CV_32F);
distCoeffs_cpp.create(5, 1, CV_32F);
rvecs_cpp.create(M, 1, CV_32FC3);
tvecs_cpp.create(M, 1, CV_32FC3);
newObjPts_cpp.create(corSize.width * corSize.height, 1, CV_32FC3);
caller.flags = 0;
//CV_CALIB_USE_INTRINSIC_GUESS; //CV_CALIB_FIX_ASPECT_RATIO
......@@ -144,6 +160,7 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
distCoeffs = cvMat(distCoeffs_cpp);
rvecs = cvMat(rvecs_cpp);
tvecs = cvMat(tvecs_cpp);
newObjPts = cvMat(newObjPts_cpp);
/* /*//*/ */
int errors = 0;
......@@ -197,6 +214,10 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
bad_caller.tvecs = (CvMat*)zeros.ptr();
errors += run_test_case( CV_StsBadArg, "Bad tvecs header", bad_caller );
bad_caller = caller;
bad_caller.newObjPts = (CvMat*)zeros.ptr();
errors += run_test_case( CV_StsBadArg, "Bad newObjPts header", bad_caller );
Mat bad_rvecs_cpp1(M+1, 1, CV_32FC3); CvMat bad_rvecs_c1 = cvMat(bad_rvecs_cpp1);
Mat bad_tvecs_cpp1(M+1, 1, CV_32FC3); CvMat bad_tvecs_c1 = cvMat(bad_tvecs_cpp1);
......@@ -207,11 +228,11 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
bad_caller = caller;
bad_caller.rvecs = &bad_rvecs_c1;
errors += run_test_case( CV_StsBadArg, "Bad tvecs header", bad_caller );
errors += run_test_case( CV_StsBadArg, "Bad rvecs header", bad_caller );
bad_caller = caller;
bad_caller.rvecs = &bad_rvecs_c2;
errors += run_test_case( CV_StsBadArg, "Bad tvecs header", bad_caller );
errors += run_test_case( CV_StsBadArg, "Bad rvecs header", bad_caller );
bad_caller = caller;
bad_caller.tvecs = &bad_tvecs_c1;
......@@ -221,6 +242,14 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
bad_caller.tvecs = &bad_tvecs_c2;
errors += run_test_case( CV_StsBadArg, "Bad tvecs header", bad_caller );
bad_caller = caller;
bad_caller.newObjPts = &bad_tvecs_c1;
errors += run_test_case( CV_StsBadArg, "Bad newObjPts header", bad_caller );
bad_caller = caller;
bad_caller.newObjPts = &bad_tvecs_c2;
errors += run_test_case( CV_StsBadArg, "Bad newObjPts header", bad_caller );
Mat bad_cameraMatrix_cpp1(3, 3, CV_32S); CvMat bad_cameraMatrix_c1 = cvMat(bad_cameraMatrix_cpp1);
Mat bad_cameraMatrix_cpp2(2, 3, CV_32F); CvMat bad_cameraMatrix_c2 = cvMat(bad_cameraMatrix_cpp2);
Mat bad_cameraMatrix_cpp3(3, 2, CV_64F); CvMat bad_cameraMatrix_c3 = cvMat(bad_cameraMatrix_cpp3);
......@@ -306,11 +335,30 @@ void CV_CameraCalibrationBadArgTest::run( int /* start_from */ )
bad_caller.objPts = &bad_objPts_c5;
cv::RNG& rng = theRNG();
for(int i = 0; i < bad_objPts_cpp5.rows; ++i)
for(int i = 0; i < bad_objPts_cpp5.cols; ++i)
bad_objPts_cpp5.at<Point3f>(0, i).z += ((float)rng - 0.5f);
errors += run_test_case( CV_StsBadArg, "Bad objPts data", bad_caller );
bad_objPts_cpp5 = objPts_cpp.clone(); bad_objPts_c5 = cvMat(bad_objPts_cpp5);
bad_caller.objPts = &bad_objPts_c5;
bad_caller.iFixedPoint = corSize.width - 1;
for(int i = 0; i < bad_objPts_cpp5.cols; ++i)
{
bad_objPts_cpp5.at<Point3f>(0, i).x += (float)rng;
bad_objPts_cpp5.at<Point3f>(0, i).y += (float)rng;
}
errors += run_test_case( CV_StsBadArg, "Bad objPts data", bad_caller );
bad_caller = caller;
Mat bad_npts_cpp3 = npoints_cpp.clone();
CvMat bad_npts_c3 = cvMat(bad_npts_cpp3);
bad_caller.npoints = &bad_npts_c3;
bad_caller.iFixedPoint = corSize.width - 1;
for(int i = 0; i < M; i++)
bad_npts_cpp3.at<int>(i) += i;
errors += run_test_case( CV_StsBadArg, "Bad npoints data", bad_caller );
if (errors)
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
else
......
This diff is collapsed.
......@@ -39,6 +39,8 @@
<Write_DetectedFeaturePoints>1</Write_DetectedFeaturePoints>
<!-- If true (non-zero) we write to the output file the extrinsic camera parameters.-->
<Write_extrinsicParameters>1</Write_extrinsicParameters>
<!-- If true (non-zero) we write to the output file the refined 3D target grid points.-->
<Write_gridPoints>1</Write_gridPoints>
<!-- If true (non-zero) we show after calibration the undistorted images.-->
<Show_UndistortedImage>1</Show_UndistortedImage>
<!-- If true (non-zero) will be used fisheye camera model.-->
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment