Unverified Commit 8f15a609 authored by Vadim Pisarevsky's avatar Vadim Pisarevsky Committed by GitHub

mostly removed obsolete C API from calib3d (at least at the interface level) (#13081)

parent 8cdf7bb8
......@@ -255,7 +255,8 @@ enum { CALIB_CB_SYMMETRIC_GRID = 1,
CALIB_CB_CLUSTERING = 4
};
enum { CALIB_USE_INTRINSIC_GUESS = 0x00001,
enum { CALIB_NINTRINSIC = 18,
CALIB_USE_INTRINSIC_GUESS = 0x00001,
CALIB_FIX_ASPECT_RATIO = 0x00002,
CALIB_FIX_PRINCIPAL_POINT = 0x00004,
CALIB_ZERO_TANGENT_DIST = 0x00008,
......@@ -316,6 +317,68 @@ An example program about pose estimation from coplanar points
Check @ref tutorial_homography "the corresponding tutorial" for more details
*/
/** Levenberg-Marquardt solver. Starting with the specified vector of parameters it
optimizes the target vector criteria "err"
(finds local minima of each target vector component absolute value).
When needed, it calls user-provided callback.
*/
class CV_EXPORTS LMSolver : public Algorithm
{
public:
class CV_EXPORTS Callback
{
public:
virtual ~Callback() {}
/**
computes error and Jacobian for the specified vector of parameters
@param param the current vector of parameters
@param err output vector of errors: err_i = actual_f_i - ideal_f_i
@param J output Jacobian: J_ij = d(err_i)/d(param_j)
when J=noArray(), it means that it does not need to be computed.
Dimensionality of error vector and param vector can be different.
The callback should explicitly allocate (with "create" method) each output array
(unless it's noArray()).
*/
virtual bool compute(InputArray param, OutputArray err, OutputArray J) const = 0;
};
/**
Runs Levenberg-Marquardt algorithm using the passed vector of parameters as the start point.
The final vector of parameters (whether the algorithm converged or not) is stored at the same
vector. The method returns the number of iterations used. If it's equal to the previously specified
maxIters, there is a big chance the algorithm did not converge.
@param param initial/final vector of parameters.
Note that the dimensionality of parameter space is defined by the size of param vector,
and the dimensionality of optimized criteria is defined by the size of err vector
computed by the callback.
*/
virtual int run(InputOutputArray param) const = 0;
/**
Sets the maximum number of iterations
@param maxIters the number of iterations
*/
virtual void setMaxIters(int maxIters) = 0;
/**
Retrieves the current maximum number of iterations
*/
virtual int getMaxIters() const = 0;
/**
Creates Levenberg-Marquard solver
@param cb callback
@param maxIters maximum number of iterations that can be further
modified using setMaxIters() method.
*/
static Ptr<LMSolver> create(const Ptr<LMSolver::Callback>& cb, int maxIters);
};
/** @brief Finds a perspective transformation between two planes.
@param srcPoints Coordinates of the points in the original plane, a matrix of the type CV_32FC2
......@@ -2779,4 +2842,44 @@ optimization. It stays at the center or at a different location specified when C
} //end namespace cv
#if 0 //def __cplusplus
//////////////////////////////////////////////////////////////////////////////////////////
class CV_EXPORTS CvLevMarq
{
public:
CvLevMarq();
CvLevMarq( int nparams, int nerrs, CvTermCriteria criteria=
cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
bool completeSymmFlag=false );
~CvLevMarq();
void init( int nparams, int nerrs, CvTermCriteria criteria=
cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
bool completeSymmFlag=false );
bool update( const CvMat*& param, CvMat*& J, CvMat*& err );
bool updateAlt( const CvMat*& param, CvMat*& JtJ, CvMat*& JtErr, double*& errNorm );
void clear();
void step();
enum { DONE=0, STARTED=1, CALC_J=2, CHECK_ERR=3 };
cv::Ptr<CvMat> mask;
cv::Ptr<CvMat> prevParam;
cv::Ptr<CvMat> param;
cv::Ptr<CvMat> J;
cv::Ptr<CvMat> err;
cv::Ptr<CvMat> JtJ;
cv::Ptr<CvMat> JtJN;
cv::Ptr<CvMat> JtErr;
cv::Ptr<CvMat> JtJV;
cv::Ptr<CvMat> JtJW;
double prevErrNorm, errNorm;
int lambdaLg10;
CvTermCriteria criteria;
int state;
int iters;
bool completeSymmFlag;
int solveMethod;
};
#endif
#endif
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
// This file contains wrappers for legacy OpenCV C API
#include "precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
using namespace cv;
CV_IMPL void
cvDrawChessboardCorners(CvArr* _image, CvSize pattern_size,
CvPoint2D32f* corners, int count, int found)
{
CV_Assert(corners != NULL); //CV_CheckNULL(corners, "NULL is not allowed for 'corners' parameter");
Mat image = cvarrToMat(_image);
CV_StaticAssert(sizeof(CvPoint2D32f) == sizeof(Point2f), "");
drawChessboardCorners(image, pattern_size, Mat(1, count, traits::Type<Point2f>::value, corners), found != 0);
}
CV_IMPL int
cvFindChessboardCorners(const void* arr, CvSize pattern_size,
CvPoint2D32f* out_corners_, int* out_corner_count,
int flags)
{
if (!out_corners_)
CV_Error( CV_StsNullPtr, "Null pointer to corners" );
Mat image = cvarrToMat(arr);
std::vector<Point2f> out_corners;
if (out_corner_count)
*out_corner_count = 0;
bool res = cv::findChessboardCorners(image, pattern_size, out_corners, flags);
int corner_count = (int)out_corners.size();
if (out_corner_count)
*out_corner_count = corner_count;
CV_CheckLE(corner_count, Size(pattern_size).area(), "Unexpected number of corners");
for (int i = 0; i < corner_count; ++i)
{
out_corners_[i] = cvPoint2D32f(out_corners[i]);
}
return res ? 1 : 0;
}
This diff is collapsed.
......@@ -43,7 +43,7 @@
#include "precomp.hpp"
#include "opencv2/imgproc/imgproc_c.h"
#include "distortion_model.hpp"
#include "opencv2/calib3d/calib3d_c.h"
#include "calib3d_c_api.h"
#include <stdio.h>
#include <iterator>
......@@ -3003,15 +3003,22 @@ void cv::reprojectImageTo3D( InputArray _disparity,
stype == CV_32SC1 || stype == CV_32FC1 );
CV_Assert( Q.size() == Size(4,4) );
if( dtype >= 0 )
dtype = CV_MAKETYPE(CV_MAT_DEPTH(dtype), 3);
if( __3dImage.fixedType() )
{
int dtype_ = __3dImage.type();
CV_Assert( dtype == -1 || dtype == dtype_ );
dtype = dtype_;
}
if( dtype < 0 )
dtype = CV_32FC3;
else
{
dtype = CV_MAKETYPE(CV_MAT_DEPTH(dtype), 3);
CV_Assert( dtype == CV_16SC3 || dtype == CV_32SC3 || dtype == CV_32FC3 );
}
__3dImage.create(disparity.size(), CV_MAKETYPE(dtype, 3));
__3dImage.create(disparity.size(), dtype);
Mat _3dImage = __3dImage.getMat();
const float bigZ = 10000.f;
......@@ -3423,11 +3430,13 @@ static void collectCalibrationData( InputArrayOfArrays objectPoints,
imgPtMat2, npoints );
}
static Mat prepareCameraMatrix(Mat& cameraMatrix0, int rtype)
static Mat prepareCameraMatrix(Mat& cameraMatrix0, int rtype, int flags)
{
Mat cameraMatrix = Mat::eye(3, 3, rtype);
if( cameraMatrix0.size() == cameraMatrix.size() )
cameraMatrix0.convertTo(cameraMatrix, rtype);
else if( flags & CALIB_USE_INTRINSIC_GUESS )
CV_Error(Error::StsBadArg, "CALIB_USE_INTRINSIC_GUESS flag is set, but the camera matrix is not 3x3");
return cameraMatrix;
}
......@@ -3544,6 +3553,8 @@ void cv::projectPoints( InputArray _opoints,
CvMat dpdrot, dpdt, dpdf, dpdc, dpddist;
CvMat *pdpdrot=0, *pdpdt=0, *pdpdf=0, *pdpdc=0, *pdpddist=0;
CV_Assert( _ipoints.needed() );
_ipoints.create(npoints, 1, CV_MAKETYPE(depth, 2), -1, true);
Mat imagePoints = _ipoints.getMat();
CvMat c_imagePoints = cvMat(imagePoints);
......@@ -3650,8 +3661,12 @@ double cv::calibrateCameraRO(InputArrayOfArrays _objectPoints,
CV_INSTRUMENT_REGION();
int rtype = CV_64F;
CV_Assert( _cameraMatrix.needed() );
CV_Assert( _distCoeffs.needed() );
Mat cameraMatrix = _cameraMatrix.getMat();
cameraMatrix = prepareCameraMatrix(cameraMatrix, rtype);
cameraMatrix = prepareCameraMatrix(cameraMatrix, rtype, flags);
Mat distCoeffs = _distCoeffs.getMat();
distCoeffs = (flags & CALIB_THIN_PRISM_MODEL) && !(flags & CALIB_TILTED_MODEL) ? prepareDistCoeffs(distCoeffs, rtype, 12) :
prepareDistCoeffs(distCoeffs, rtype);
......@@ -3864,8 +3879,8 @@ double cv::stereoCalibrate( InputArrayOfArrays _objectPoints,
Mat cameraMatrix2 = _cameraMatrix2.getMat();
Mat distCoeffs1 = _distCoeffs1.getMat();
Mat distCoeffs2 = _distCoeffs2.getMat();
cameraMatrix1 = prepareCameraMatrix(cameraMatrix1, rtype);
cameraMatrix2 = prepareCameraMatrix(cameraMatrix2, rtype);
cameraMatrix1 = prepareCameraMatrix(cameraMatrix1, rtype, flags);
cameraMatrix2 = prepareCameraMatrix(cameraMatrix2, rtype, flags);
distCoeffs1 = prepareDistCoeffs(distCoeffs1, rtype);
distCoeffs2 = prepareDistCoeffs(distCoeffs2, rtype);
......
......@@ -41,7 +41,7 @@
#include "precomp.hpp"
#include "opencv2/imgproc/imgproc_c.h"
#include "opencv2/calib3d/calib3d_c.h"
#include "calib3d_c_api.h"
#include <vector>
#include <algorithm>
......
......@@ -41,7 +41,8 @@
//M*/
#include "precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
#include "opencv2/core/core_c.h"
#include "calib3d_c_api.h"
/************************************************************************************\
Some backward compatibility stuff, to be moved to legacy or compat module
......@@ -321,7 +322,6 @@ void CvLevMarq::step()
param->data.db[i] = prevParam->data.db[i] - (mask->data.ptr[i] ? nonzero_param(j++) : 0);
}
CV_IMPL int cvRANSACUpdateNumIters( double p, double ep, int modelPoints, int maxIters )
{
return cv::RANSACUpdateNumIters(p, ep, modelPoints, maxIters);
......
//M*//////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// 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
//
// Copyright (C) 2000, Intel Corporation, all rights reserved.
// 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:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's 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.
//
// * The name of the copyright holders may not 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 the Intel Corporation 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.
//
//M*/
#include "precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
CvStereoBMState* cvCreateStereoBMState( int /*preset*/, int numberOfDisparities )
{
CvStereoBMState* state = (CvStereoBMState*)cvAlloc( sizeof(*state) );
if( !state )
return 0;
state->preFilterType = CV_STEREO_BM_XSOBEL; //CV_STEREO_BM_NORMALIZED_RESPONSE;
state->preFilterSize = 9;
state->preFilterCap = 31;
state->SADWindowSize = 15;
state->minDisparity = 0;
state->numberOfDisparities = numberOfDisparities > 0 ? numberOfDisparities : 64;
state->textureThreshold = 10;
state->uniquenessRatio = 15;
state->speckleRange = state->speckleWindowSize = 0;
state->trySmallerWindows = 0;
state->roi1 = state->roi2 = cvRect(0,0,0,0);
state->disp12MaxDiff = -1;
state->preFilteredImg0 = state->preFilteredImg1 = state->slidingSumBuf =
state->disp = state->cost = 0;
return state;
}
void cvReleaseStereoBMState( CvStereoBMState** state )
{
if( !state )
CV_Error( CV_StsNullPtr, "" );
if( !*state )
return;
cvReleaseMat( &(*state)->preFilteredImg0 );
cvReleaseMat( &(*state)->preFilteredImg1 );
cvReleaseMat( &(*state)->slidingSumBuf );
cvReleaseMat( &(*state)->disp );
cvReleaseMat( &(*state)->cost );
cvFree( state );
}
void cvFindStereoCorrespondenceBM( const CvArr* leftarr, const CvArr* rightarr,
CvArr* disparr, CvStereoBMState* state )
{
cv::Mat left = cv::cvarrToMat(leftarr), right = cv::cvarrToMat(rightarr);
const cv::Mat disp = cv::cvarrToMat(disparr);
CV_Assert( state != 0 );
cv::Ptr<cv::StereoBM> sm = cv::StereoBM::create(state->numberOfDisparities,
state->SADWindowSize);
sm->setPreFilterType(state->preFilterType);
sm->setPreFilterSize(state->preFilterSize);
sm->setPreFilterCap(state->preFilterCap);
sm->setBlockSize(state->SADWindowSize);
sm->setNumDisparities(state->numberOfDisparities > 0 ? state->numberOfDisparities : 64);
sm->setTextureThreshold(state->textureThreshold);
sm->setUniquenessRatio(state->uniquenessRatio);
sm->setSpeckleRange(state->speckleRange);
sm->setSpeckleWindowSize(state->speckleWindowSize);
sm->setDisp12MaxDiff(state->disp12MaxDiff);
sm->compute(left, right, disp);
}
CvRect cvGetValidDisparityROI( CvRect roi1, CvRect roi2, int minDisparity,
int numberOfDisparities, int SADWindowSize )
{
return cvRect(cv::getValidDisparityROI( roi1, roi2, minDisparity,
numberOfDisparities, SADWindowSize));
}
void cvValidateDisparity( CvArr* _disp, const CvArr* _cost, int minDisparity,
int numberOfDisparities, int disp12MaxDiff )
{
cv::Mat disp = cv::cvarrToMat(_disp), cost = cv::cvarrToMat(_cost);
cv::validateDisparity( disp, cost, minDisparity, numberOfDisparities, disp12MaxDiff );
}
......@@ -411,7 +411,7 @@ cv::Mat cv::findHomography( InputArray _points1, InputArray _points2,
if( method == RANSAC || method == LMEDS )
cb->runKernel( src, dst, H );
Mat H8(8, 1, CV_64F, H.ptr<double>());
createLMSolver(makePtr<HomographyRefineCallback>(src, dst), 10)->run(H8);
LMSolver::create(makePtr<HomographyRefineCallback>(src, dst), 10)->run(H8);
}
}
......
......@@ -198,7 +198,8 @@ public:
return iter;
}
void setCallback(const Ptr<LMSolver::Callback>& _cb) CV_OVERRIDE { cb = _cb; }
void setMaxIters(int iters) CV_OVERRIDE { CV_Assert(iters > 0); maxIters = iters; }
int getMaxIters() const CV_OVERRIDE { return maxIters; }
Ptr<LMSolver::Callback> cb;
......@@ -209,7 +210,7 @@ public:
};
Ptr<LMSolver> createLMSolver(const Ptr<LMSolver::Callback>& cb, int maxIters)
Ptr<LMSolver> LMSolver::create(const Ptr<LMSolver::Callback>& cb, int maxIters)
{
return makePtr<LMSolverImpl>(cb, maxIters);
}
......
......@@ -39,7 +39,7 @@
//
//M*/
#include "precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
#include "calib3d_c_api.h"
/* POSIT structure */
struct CvPOSITObject
......
......@@ -76,22 +76,6 @@ namespace cv
*/
int RANSACUpdateNumIters( double p, double ep, int modelPoints, int maxIters );
class CV_EXPORTS LMSolver : public Algorithm
{
public:
class CV_EXPORTS Callback
{
public:
virtual ~Callback() {}
virtual bool compute(InputArray param, OutputArray err, OutputArray J) const = 0;
};
virtual void setCallback(const Ptr<LMSolver::Callback>& cb) = 0;
virtual int run(InputOutputArray _param0) const = 0;
};
CV_EXPORTS Ptr<LMSolver> createLMSolver(const Ptr<LMSolver::Callback>& cb, int maxIters);
class CV_EXPORTS PointSetRegistrator : public Algorithm
{
public:
......
......@@ -863,7 +863,7 @@ Mat estimateAffine2D(InputArray _from, InputArray _to, OutputArray _inliers,
Mat src = from.rowRange(0, inliers_count);
Mat dst = to.rowRange(0, inliers_count);
Mat Hvec = H.reshape(1, 6);
createLMSolver(makePtr<Affine2DRefineCallback>(src, dst), static_cast<int>(refineIters))->run(Hvec);
LMSolver::create(makePtr<Affine2DRefineCallback>(src, dst), static_cast<int>(refineIters))->run(Hvec);
}
}
......@@ -937,7 +937,7 @@ Mat estimateAffinePartial2D(InputArray _from, InputArray _to, OutputArray _inlie
double *Hptr = H.ptr<double>();
double Hvec_buf[4] = {Hptr[0], Hptr[3], Hptr[2], Hptr[5]};
Mat Hvec (4, 1, CV_64F, Hvec_buf);
createLMSolver(makePtr<AffinePartial2DRefineCallback>(src, dst), static_cast<int>(refineIters))->run(Hvec);
LMSolver::create(makePtr<AffinePartial2DRefineCallback>(src, dst), static_cast<int>(refineIters))->run(Hvec);
// update H with refined parameters
Hptr[0] = Hptr[4] = Hvec_buf[0];
Hptr[1] = -Hvec_buf[1];
......
......@@ -46,7 +46,7 @@
#include "epnp.h"
#include "p3p.h"
#include "ap3p.h"
#include "opencv2/calib3d/calib3d_c.h"
#include "calib3d_c_api.h"
#include <iostream>
......
......@@ -40,7 +40,7 @@
//M*/
#include "precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
#include "opencv2/core/core_c.h"
// cvCorrectMatches function is Copyright (C) 2009, Jostein Austvik Jacobsen.
// cvTriangulatePoints function is derived from icvReconstructPointsFor3View, originally by Valery Mosyagin.
......@@ -50,8 +50,8 @@
// This method is the same as icvReconstructPointsFor3View, with only a few numbers adjusted for two-view geometry
CV_IMPL void
cvTriangulatePoints(CvMat* projMatr1, CvMat* projMatr2, CvMat* projPoints1, CvMat* projPoints2, CvMat* points4D)
static void
icvTriangulatePoints(CvMat* projMatr1, CvMat* projMatr2, CvMat* projPoints1, CvMat* projPoints2, CvMat* points4D)
{
if( projMatr1 == 0 || projMatr2 == 0 ||
projPoints1 == 0 || projPoints2 == 0 ||
......@@ -131,8 +131,8 @@ cvTriangulatePoints(CvMat* projMatr1, CvMat* projMatr2, CvMat* projPoints1, CvMa
* new_points1 : the optimized points1_. if this is NULL, the corrected points are placed back in points1_
* new_points2 : the optimized points2_. if this is NULL, the corrected points are placed back in points2_
*/
CV_IMPL void
cvCorrectMatches(CvMat *F_, CvMat *points1_, CvMat *points2_, CvMat *new_points1, CvMat *new_points2)
static void
icvCorrectMatches(CvMat *F_, CvMat *points1_, CvMat *points2_, CvMat *new_points1, CvMat *new_points2)
{
cv::Ptr<CvMat> tmp33;
cv::Ptr<CvMat> tmp31, tmp31_2;
......@@ -365,7 +365,7 @@ void cv::triangulatePoints( InputArray _projMatr1, InputArray _projMatr2,
Mat cvPoints4D_ = _points4D.getMat();
CvMat cvPoints4D = cvMat(cvPoints4D_);
cvTriangulatePoints(&cvMatr1, &cvMatr2, &cvPoints1, &cvPoints2, &cvPoints4D);
icvTriangulatePoints(&cvMatr1, &cvMatr2, &cvPoints1, &cvPoints2, &cvPoints4D);
}
void cv::correctMatches( InputArray _F, InputArray _points1, InputArray _points2,
......@@ -384,5 +384,5 @@ void cv::correctMatches( InputArray _F, InputArray _points1, InputArray _points2
Mat cvNewPoints1_ = _newPoints1.getMat(), cvNewPoints2_ = _newPoints2.getMat();
CvMat cvNewPoints1 = cvMat(cvNewPoints1_), cvNewPoints2 = cvMat(cvNewPoints2_);
cvCorrectMatches(&cvF, &cvPoints1, &cvPoints2, &cvNewPoints1, &cvNewPoints2);
icvCorrectMatches(&cvF, &cvPoints1, &cvPoints2, &cvNewPoints1, &cvNewPoints2);
}
......@@ -44,7 +44,7 @@
#include "distortion_model.hpp"
#include "undistort.hpp"
#include "opencv2/calib3d/calib3d_c.h"
#include "calib3d_c_api.h"
cv::Mat cv::getDefaultNewCameraMatrix( InputArray _cameraMatrix, Size imgsize,
bool centerPrincipalPoint )
......
......@@ -48,53 +48,32 @@ namespace opencv_test { namespace {
class CV_ChessboardDetectorBadArgTest : public cvtest::BadArgTest
{
public:
CV_ChessboardDetectorBadArgTest();
CV_ChessboardDetectorBadArgTest() { flags0 = 0; }
protected:
void run(int);
bool checkByGenerator();
bool cpp;
/* cpp interface */
Mat img;
Size pattern_size;
int flags;
Size pattern_size, pattern_size0;
int flags, flags0;
vector<Point2f> corners;
_InputArray img_arg;
_OutputArray corners_arg;
/* c interface */
CvMat arr;
CvPoint2D32f* out_corners;
int* out_corner_count;
/* c interface draw corners */
bool drawCorners;
CvMat drawCorImg;
bool was_found;
void initArgs()
{
img_arg = img;
corners_arg = corners;
pattern_size = pattern_size0;
flags = flags0;
}
void run_func()
{
if (cpp)
findChessboardCorners(img, pattern_size, corners, flags);
else
if (!drawCorners)
cvFindChessboardCorners( &arr, cvSize(pattern_size), out_corners, out_corner_count, flags );
else
cvDrawChessboardCorners( &drawCorImg, cvSize(pattern_size),
(CvPoint2D32f*)(corners.empty() ? 0 : &corners[0]),
(int)corners.size(), was_found);
findChessboardCorners(img_arg, pattern_size, corners_arg, flags);
}
};
CV_ChessboardDetectorBadArgTest::CV_ChessboardDetectorBadArgTest()
{
cpp = false;
flags = 0;
out_corners = NULL;
out_corner_count = NULL;
drawCorners = was_found = false;
}
/* ///////////////////// chess_corner_test ///////////////////////// */
void CV_ChessboardDetectorBadArgTest::run( int /*start_from */)
{
......@@ -111,34 +90,18 @@ void CV_ChessboardDetectorBadArgTest::run( int /*start_from */)
/* /*//*/ */
int errors = 0;
flags = CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_NORMALIZE_IMAGE;
cpp = true;
img = cb.clone();
initArgs();
pattern_size = Size(2,2);
errors += run_test_case( CV_StsOutOfRange, "Invlid pattern size" );
errors += run_test_case( Error::StsOutOfRange, "Invlid pattern size" );
pattern_size = cbg.cornersSize();
cb.convertTo(img, CV_32F);
errors += run_test_case( CV_StsUnsupportedFormat, "Not 8-bit image" );
errors += run_test_case( Error::StsUnsupportedFormat, "Not 8-bit image" );
cv::merge(vector<Mat>(2, cb), img);
errors += run_test_case( CV_StsUnsupportedFormat, "2 channel image" );
cpp = false;
drawCorners = false;
img = cb.clone();
arr = cvMat(img);
out_corner_count = 0;
out_corners = 0;
errors += run_test_case( CV_StsNullPtr, "Null pointer to corners" );
drawCorners = true;
Mat cvdrawCornImg(img.size(), CV_8UC2);
drawCorImg = cvMat(cvdrawCornImg);
was_found = true;
errors += run_test_case( CV_StsUnsupportedFormat, "2 channel image" );
errors += run_test_case( Error::StsUnsupportedFormat, "2 channel image" );
if (errors)
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
......
This diff is collapsed.
......@@ -40,7 +40,9 @@
//M*/
#include "test_precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
// POSIT is not exposed to C++ API yet, so the test is disabled
#if 0
namespace opencv_test { namespace {
......@@ -219,4 +221,7 @@ void CV_POSITTest::run( int start_from )
TEST(Calib3d_POSIT, accuracy) { CV_POSITTest test; test.safe_run(); }
}} // namespace
#endif
/* End of file. */
......@@ -41,7 +41,6 @@
//M*/
#include "test_precomp.hpp"
#include "opencv2/calib3d/calib3d_c.h"
namespace opencv_test { namespace {
......@@ -121,14 +120,9 @@ protected:
Mat_<double> Q(4, 4);
randu(Q, Scalar(-5), Scalar(5));
Mat_<out3d_t> _3dImg(disp.size());
CvMat cvdisp = cvMat(disp); CvMat cv_3dImg = cvMat(_3dImg); CvMat cvQ = cvMat(Q);
cvReprojectImageTo3D( &cvdisp, &cv_3dImg, &cvQ, handleMissingValues );
if (std::numeric_limits<OutT>::max() == std::numeric_limits<float>::max())
reprojectImageTo3D(disp, _3dImg, Q, handleMissingValues);
reprojectImageTo3D(disp, _3dImg, Q, handleMissingValues);
for(int y = 0; y < disp.rows; ++y)
for(int x = 0; x < disp.cols; ++x)
......
This diff is collapsed.
......@@ -796,7 +796,7 @@ int CV_RemapTest::prepare_test_case( int test_case_idx )
k[2] = cvtest::randReal(rng)*0.004 - 0.002;
k[3] = cvtest::randReal(rng)*0.004 - 0.002;
cvtest::initUndistortMap( _a, _k, test_mat[INPUT][1].size(), test_mat[INPUT][1], test_mat[INPUT][2] );
cvtest::initUndistortMap( _a, _k, Mat(), Mat(), test_mat[INPUT][1].size(), test_mat[INPUT][1], test_mat[INPUT][2], CV_32F );
return code;
}
......
......@@ -41,6 +41,7 @@
//M*/
#include "precomp.hpp"
#include "opencv2/core/core_c.h"
#include "opencv2/calib3d/calib3d_c.h"
#include "opencv2/core/cvdef.h"
......
......@@ -220,7 +220,7 @@ void copyMakeBorder(const Mat& src, Mat& dst, int top, int bottom, int left, int
Mat calcSobelKernel2D( int dx, int dy, int apertureSize, int origin=0 );
Mat calcLaplaceKernel2D( int aperture_size );
void initUndistortMap( const Mat& a, const Mat& k, Size sz, Mat& mapx, Mat& mapy );
void initUndistortMap( const Mat& a, const Mat& k, const Mat& R, const Mat& new_a, Size sz, Mat& mapx, Mat& mapy, int map_type );
void minMaxLoc(const Mat& src, double* minval, double* maxval,
vector<int>* minloc, vector<int>* maxloc, const Mat& mask=Mat());
......@@ -594,7 +594,7 @@ protected:
catch(const cv::Exception& e)
{
thrown = true;
if( e.code != expected_code )
if( e.code != expected_code && e.code != cv::Error::StsAssert && e.code != cv::Error::StsError )
{
ts->printf(TS::LOG, "%s (test case #%d): the error code %d is different from the expected %d\n",
descr, test_case_idx, e.code, expected_code);
......
......@@ -2810,29 +2810,57 @@ Mat calcLaplaceKernel2D( int aperture_size )
}
void initUndistortMap( const Mat& _a0, const Mat& _k0, Size sz, Mat& _mapx, Mat& _mapy )
void initUndistortMap( const Mat& _a0, const Mat& _k0, const Mat& _R0, const Mat& _new_cam0, Size sz, Mat& __mapx, Mat& __mapy, int map_type )
{
_mapx.create(sz, CV_32F);
_mapy.create(sz, CV_32F);
Mat _mapx(sz, CV_32F), _mapy(sz, CV_32F);
double a[9], k[5]={0,0,0,0,0};
Mat _a(3, 3, CV_64F, a);
double a[9], k[5]={0,0,0,0,0}, iR[9]={1, 0, 0, 0, 1, 0, 0, 0, 1}, a1[9];
Mat _a(3, 3, CV_64F, a), _a1(3, 3, CV_64F, a1);
Mat _k(_k0.rows,_k0.cols, CV_MAKETYPE(CV_64F,_k0.channels()),k);
Mat _iR(3, 3, CV_64F, iR);
double fx, fy, cx, cy, ifx, ify, cxn, cyn;
CV_Assert(_k0.empty() ||
_k0.size() == Size(5, 1) ||
_k0.size() == Size(1, 5) ||
_k0.size() == Size(4, 1) ||
_k0.size() == Size(1, 4));
CV_Assert(_a0.size() == Size(3, 3));
_a0.convertTo(_a, CV_64F);
_k0.convertTo(_k, CV_64F);
if( !_k0.empty() )
_k0.convertTo(_k, CV_64F);
if( !_R0.empty() )
{
CV_Assert(_R0.size() == Size(3, 3));
Mat tmp;
_R0.convertTo(tmp, CV_64F);
invert(tmp, _iR, DECOMP_LU);
}
if( !_new_cam0.empty() )
{
CV_Assert(_new_cam0.size() == Size(3, 3));
_new_cam0.convertTo(_a1, CV_64F);
}
else
_a.copyTo(_a1);
fx = a[0]; fy = a[4]; cx = a[2]; cy = a[5];
ifx = 1./fx; ify = 1./fy;
cxn = cx;
cyn = cy;
ifx = 1./a1[0]; ify = 1./a1[4];
cxn = a1[2];
cyn = a1[5];
for( int v = 0; v < sz.height; v++ )
{
for( int u = 0; u < sz.width; u++ )
{
double x = (u - cxn)*ifx;
double y = (v - cyn)*ify;
double x_ = (u - cxn)*ifx;
double y_ = (v - cyn)*ify;
double X = iR[0]*x_ + iR[1]*y_ + iR[2];
double Y = iR[3]*x_ + iR[4]*y_ + iR[5];
double Z = iR[6]*x_ + iR[7]*y_ + iR[8];
double x = X/Z;
double y = Y/Z;
double x2 = x*x, y2 = y*y;
double r2 = x2 + y2;
double cdist = 1 + (k[0] + (k[1] + k[4]*r2)*r2)*r2;
......@@ -2843,8 +2871,10 @@ void initUndistortMap( const Mat& _a0, const Mat& _k0, Size sz, Mat& _mapx, Mat&
_mapx.at<float>(v, u) = (float)(x1*fx + cx);
}
}
}
_mapx.convertTo(__mapx, map_type);
_mapy.convertTo(__mapy, map_type);
}
std::ostream& operator << (std::ostream& out, const MatInfo& m)
{
......
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