44
#ifndef OPENCV_CALIB3D_HPP
45
#define OPENCV_CALIB3D_HPP
47
#include "opencv2/core.hpp"
48
#include "opencv2/features2d.hpp"
49
#include "opencv2/core/affine.hpp"
457
SOLVEPNP_ITERATIVE = 0,
480
enum
{ CALIB_CB_ADAPTIVE_THRESH = 1,
481
CALIB_CB_NORMALIZE_IMAGE = 2,
482
CALIB_CB_FILTER_QUADS = 4,
483
CALIB_CB_FAST_CHECK = 8,
484
CALIB_CB_EXHAUSTIVE = 16,
485
CALIB_CB_ACCURACY = 32,
486
CALIB_CB_LARGER = 64,
487
CALIB_CB_MARKER = 128
490
enum
{ CALIB_CB_SYMMETRIC_GRID = 1,
491
CALIB_CB_ASYMMETRIC_GRID = 2,
492
CALIB_CB_CLUSTERING = 4
495
enum
{ CALIB_NINTRINSIC = 18,
496
CALIB_USE_INTRINSIC_GUESS = 0x00001,
497
CALIB_FIX_ASPECT_RATIO = 0x00002,
498
CALIB_FIX_PRINCIPAL_POINT = 0x00004,
499
CALIB_ZERO_TANGENT_DIST = 0x00008,
500
CALIB_FIX_FOCAL_LENGTH = 0x00010,
501
CALIB_FIX_K1 = 0x00020,
502
CALIB_FIX_K2 = 0x00040,
503
CALIB_FIX_K3 = 0x00080,
504
CALIB_FIX_K4 = 0x00800,
505
CALIB_FIX_K5 = 0x01000,
506
CALIB_FIX_K6 = 0x02000,
507
CALIB_RATIONAL_MODEL = 0x04000,
508
CALIB_THIN_PRISM_MODEL = 0x08000,
509
CALIB_FIX_S1_S2_S3_S4 = 0x10000,
510
CALIB_TILTED_MODEL = 0x40000,
511
CALIB_FIX_TAUX_TAUY = 0x80000,
513
CALIB_FIX_TANGENT_DIST = 0x200000,
515
CALIB_FIX_INTRINSIC = 0x00100,
516
CALIB_SAME_FOCAL_LENGTH = 0x00200,
518
CALIB_ZERO_DISPARITY = 0x00400,
545
enum
SamplingMethod { SAMPLING_UNIFORM, SAMPLING_PROGRESSIVE_NAPSAC, SAMPLING_NAPSAC,
547
enum
LocalOptimMethod {LOCAL_OPTIM_NULL, LOCAL_OPTIM_INNER_LO, LOCAL_OPTIM_INNER_AND_ITER_LO,
548
LOCAL_OPTIM_GC, LOCAL_OPTIM_SIGMA};
549
enum
ScoreMethod {SCORE_METHOD_RANSAC, SCORE_METHOD_MSAC, SCORE_METHOD_MAGSAC, SCORE_METHOD_LMEDS};
550
enum
NeighborSearchMethod { NEIGH_FLANN_KNN, NEIGH_GRID, NEIGH_FLANN_RADIUS };
555
CV_PROP_RW
double
confidence;
556
CV_PROP_RW
bool
isParallel;
557
CV_PROP_RW
int
loIterations;
558
CV_PROP_RW LocalOptimMethod loMethod;
559
CV_PROP_RW
int
loSampleSize;
560
CV_PROP_RW
int
maxIterations;
561
CV_PROP_RW NeighborSearchMethod neighborsSearch;
562
CV_PROP_RW
int
randomGeneratorState;
563
CV_PROP_RW SamplingMethod sampler;
564
CV_PROP_RW ScoreMethod score;
729
int
method = 0,
double
ransacReprojThreshold = 3,
730
OutputArray
mask=noArray(),
const
int
maxIters = 2000,
731
const
double
confidence = 0.995);
735
OutputArray
mask,
int
method = 0,
double
ransacReprojThreshold = 3 );
838
CV_EXPORTS_W
void
composeRT( InputArray rvec1, InputArray tvec1,
839
InputArray rvec2, InputArray tvec2,
880
InputArray rvec, InputArray tvec,
881
InputArray cameraMatrix, InputArray distCoeffs,
884
double
aspectRatio = 0 );
1078
CV_EXPORTS_W
bool
solvePnP( InputArray objectPoints, InputArray imagePoints,
1079
InputArray cameraMatrix, InputArray distCoeffs,
1081
bool
useExtrinsicGuess =
false,
int
flags = SOLVEPNP_ITERATIVE );
1125
InputArray cameraMatrix, InputArray distCoeffs,
1127
bool
useExtrinsicGuess =
false,
int
iterationsCount = 100,
1128
float
reprojectionError = 8.0,
double
confidence = 0.99,
1129
OutputArray
inliers = noArray(),
int
flags = SOLVEPNP_ITERATIVE );
1136CV_EXPORTS_W
bool
solvePnPRansac( InputArray objectPoints, InputArray imagePoints,
1166
CV_EXPORTS_W
int
solveP3P( InputArray objectPoints, InputArray imagePoints,
1167
InputArray cameraMatrix, InputArray distCoeffs,
1194
InputArray cameraMatrix, InputArray distCoeffs,
1223
InputArray cameraMatrix, InputArray distCoeffs,
1226
double
VVSlambda = 1);
1419
InputArray cameraMatrix, InputArray distCoeffs,
1421
bool
useExtrinsicGuess =
false,
SolvePnPMethod
flags = SOLVEPNP_ITERATIVE,
1422
InputArray rvec = noArray(), InputArray tvec = noArray(),
1441
InputArrayOfArrays imagePoints,
1442
Size
imageSize,
double
aspectRatio = 1.0 );
1494
int
flags = CALIB_CB_ADAPTIVE_THRESH + CALIB_CB_NORMALIZE_IMAGE );
1500CV_EXPORTS_W
bool
checkChessboard(InputArray img,
Size
size);
1589
float
rise_distance=0.8F,
bool
vertical=
false,
1609
InputArray corners,
bool
patternWasFound );
1628
InputArray rvec, InputArray tvec,
float
length,
int
thickness=3);
1633
CV_PROP_RW
cv::Size2f
densityNeighborhoodSize;
1634
CV_PROP_RW
float
minDensity;
1635
CV_PROP_RW
int
kmeansAttempts;
1636
CV_PROP_RW
int
minDistanceToAddKeypoint;
1637
CV_PROP_RW
int
keypointScale;
1638
CV_PROP_RW
float
minGraphConfidence;
1639
CV_PROP_RW
float
vertexGain;
1640
CV_PROP_RW
float
vertexPenalty;
1641
CV_PROP_RW
float
existingVertexGain;
1642
CV_PROP_RW
float
edgeGain;
1643
CV_PROP_RW
float
edgePenalty;
1644
CV_PROP_RW
float
convexHullFactor;
1645
CV_PROP_RW
float
minRNGEdgeSwitchDist;
1649
SYMMETRIC_GRID, ASYMMETRIC_GRID
1653
CV_PROP_RW
float
squareSize;
1654
CV_PROP_RW
float
maxRectifiedDistance;
1657
#ifndef DISABLE_OPENCV_3_COMPATIBILITY
1701
OutputArray
centers,
int
flags = CALIB_CB_SYMMETRIC_GRID,
1821
InputArrayOfArrays imagePoints,
Size
imageSize,
1832
InputArrayOfArrays imagePoints,
Size
imageSize,
1896
InputArrayOfArrays imagePoints,
Size
imageSize,
int
iFixedPoint,
1909
InputArrayOfArrays imagePoints,
Size
imageSize,
int
iFixedPoint,
1937
double
apertureWidth,
double
apertureHeight,
1938
CV_OUT
double& fovx, CV_OUT
double& fovy,
1939
CV_OUT
double& focalLength, CV_OUT
Point2d& principalPoint,
1940
CV_OUT
double& aspectRatio );
2065
InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2,
2069
OutputArray
perViewErrors,
int
flags = CALIB_FIX_INTRINSIC,
2074
InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2,
2078
int
flags = CALIB_FIX_INTRINSIC,
2186
CV_EXPORTS_W
void
stereoRectify( InputArray cameraMatrix1, InputArray distCoeffs1,
2187
InputArray cameraMatrix2, InputArray distCoeffs2,
2188
Size
imageSize, InputArray R, InputArray T,
2192
double
alpha = -1,
Size
newImageSize =
Size(),
2193
CV_OUT
Rect* validPixROI1 = 0, CV_OUT
Rect* validPixROI2 = 0 );
2225
InputArray F,
Size
imgSize,
2231
InputArray cameraMatrix2, InputArray distCoeffs2,
2232
InputArray cameraMatrix3, InputArray distCoeffs3,
2233
InputArrayOfArrays imgpt1, InputArrayOfArrays imgpt3,
2234
Size
imageSize, InputArray R12, InputArray T12,
2235
InputArray R13, InputArray T13,
2239
CV_OUT
Rect* roi1, CV_OUT
Rect* roi2,
int
flags );
2268
Size
imageSize,
double
alpha,
Size
newImgSize =
Size(),
2269
CV_OUT
Rect* validPixROI = 0,
2270
bool
centerPrincipalPoint =
false);
2418
CV_EXPORTS_W
void
calibrateHandEye( InputArrayOfArrays R_gripper2base, InputArrayOfArrays t_gripper2base,
2419
InputArrayOfArrays R_target2cam, InputArrayOfArrays t_target2cam,
2562
InputArrayOfArrays R_base2gripper, InputArrayOfArrays t_base2gripper,
2652
int
method,
double
ransacReprojThreshold,
double
confidence,
2658
double
ransacReprojThreshold = 3.,
double
confidence = 0.99,
2664
double
ransacReprojThreshold = 3.,
double
confidence = 0.99 );
2705
InputArray points1, InputArray points2,
2706
InputArray cameraMatrix,
int
method =
RANSAC,
2707
double
prob = 0.999,
double
threshold
= 1.0,
2714
InputArray points1, InputArray points2,
2715
InputArray cameraMatrix,
int
method,
2752
InputArray points1, InputArray points2,
2754
int
method =
RANSAC,
double
prob = 0.999,
2755
double
threshold
= 1.0,
int
maxIters = 1000,
2762
InputArray points1, InputArray points2,
2764
int
method,
double
prob,
2813
InputArray cameraMatrix1, InputArray distCoeffs1,
2814
InputArray cameraMatrix2, InputArray distCoeffs2,
2816
double
prob = 0.999,
double
threshold
= 1.0,
2821
InputArray cameraMatrix1, InputArray cameraMatrix2,
2822
InputArray dist_coeff1, InputArray dist_coeff2,
OutputArray
mask,
2895
CV_EXPORTS_W
int
recoverPose( InputArray E, InputArray points1, InputArray points2,
2928
CV_EXPORTS_W
int
recoverPose( InputArray E, InputArray points1, InputArray points2,
2958
CV_EXPORTS_W
int
recoverPose( InputArray E, InputArray points1, InputArray points2,
3013
InputArray projPoints1, InputArray projPoints2,
3031
CV_EXPORTS_W
void
correctMatches( InputArray F, InputArray points1, InputArray points2,
3047
int
maxSpeckleSize,
double
maxDiff,
3052
int
minDisparity,
int
numberOfDisparities,
3057
int
minDisparity,
int
numberOfDisparities,
3058
int
disp12MaxDisp = 1 );
3101
bool
handleMissingValues =
false,
3173
double
ransacThreshold = 3,
double
confidence = 0.99);
3200
CV_OUT
double* scale =
nullptr,
bool
force_rotation =
true);
3247
double
ransacThreshold = 3,
double
confidence = 0.99);
3312
int
method =
RANSAC,
double
ransacReprojThreshold = 3,
3313
size_t
maxIters = 2000,
double
confidence = 0.99,
3314
size_t
refineIters = 10);
3364
int
method =
RANSAC,
double
ransacReprojThreshold = 3,
3365
size_t
maxIters = 2000,
double
confidence = 0.99,
3366
size_t
refineIters = 10);
3421
InputArrayOfArrays normals,
3422
InputArray beforePoints,
3423
InputArray afterPoints,
3425
InputArray pointsMask = noArray());
3432
enum
{ DISP_SHIFT = 4,
3433
DISP_SCALE = (1 << DISP_SHIFT)
3444
CV_WRAP
virtual
void
compute( InputArray left, InputArray right,
3447
CV_WRAP
virtual
int
getMinDisparity()
const
= 0;
3448
CV_WRAP
virtual
void
setMinDisparity(
int
minDisparity) = 0;
3450
CV_WRAP
virtual
int
getNumDisparities()
const
= 0;
3451
CV_WRAP
virtual
void
setNumDisparities(
int
numDisparities) = 0;
3453
CV_WRAP
virtual
int
getBlockSize()
const
= 0;
3454
CV_WRAP
virtual
void
setBlockSize(
int
blockSize) = 0;
3456
CV_WRAP
virtual
int
getSpeckleWindowSize()
const
= 0;
3457
CV_WRAP
virtual
void
setSpeckleWindowSize(
int
speckleWindowSize) = 0;
3459
CV_WRAP
virtual
int
getSpeckleRange()
const
= 0;
3460
CV_WRAP
virtual
void
setSpeckleRange(
int
speckleRange) = 0;
3462
CV_WRAP
virtual
int
getDisp12MaxDiff()
const
= 0;
3463
CV_WRAP
virtual
void
setDisp12MaxDiff(
int
disp12MaxDiff) = 0;
3473
enum
{ PREFILTER_NORMALIZED_RESPONSE = 0,
3474
PREFILTER_XSOBEL = 1
3477
CV_WRAP
virtual
int
getPreFilterType()
const
= 0;
3478
CV_WRAP
virtual
void
setPreFilterType(
int
preFilterType) = 0;
3480
CV_WRAP
virtual
int
getPreFilterSize()
const
= 0;
3481
CV_WRAP
virtual
void
setPreFilterSize(
int
preFilterSize) = 0;
3483
CV_WRAP
virtual
int
getPreFilterCap()
const
= 0;
3484
CV_WRAP
virtual
void
setPreFilterCap(
int
preFilterCap) = 0;
3486
CV_WRAP
virtual
int
getTextureThreshold()
const
= 0;
3487
CV_WRAP
virtual
void
setTextureThreshold(
int
textureThreshold) = 0;
3489
CV_WRAP
virtual
int
getUniquenessRatio()
const
= 0;
3490
CV_WRAP
virtual
void
setUniquenessRatio(
int
uniquenessRatio) = 0;
3492
CV_WRAP
virtual
int
getSmallerBlockSize()
const
= 0;
3493
CV_WRAP
virtual
void
setSmallerBlockSize(
int
blockSize) = 0;
3495
CV_WRAP
virtual
Rect
getROI1()
const
= 0;
3496
CV_WRAP
virtual
void
setROI1(
Rect
roi1) = 0;
3498
CV_WRAP
virtual
Rect
getROI2()
const
= 0;
3499
CV_WRAP
virtual
void
setROI2(
Rect
roi2) = 0;
3514
CV_WRAP
static
Ptr<StereoBM>
create(
int
numDisparities = 0,
int
blockSize = 21);
3546
CV_WRAP
virtual
int
getPreFilterCap()
const
= 0;
3547
CV_WRAP
virtual
void
setPreFilterCap(
int
preFilterCap) = 0;
3549
CV_WRAP
virtual
int
getUniquenessRatio()
const
= 0;
3550
CV_WRAP
virtual
void
setUniquenessRatio(
int
uniquenessRatio) = 0;
3552
CV_WRAP
virtual
int
getP1()
const
= 0;
3553
CV_WRAP
virtual
void
setP1(
int
P1) = 0;
3555
CV_WRAP
virtual
int
getP2()
const
= 0;
3556
CV_WRAP
virtual
void
setP2(
int
P2) = 0;
3558
CV_WRAP
virtual
int
getMode()
const
= 0;
3559
CV_WRAP
virtual
void
setMode(
int
mode) = 0;
3598
CV_WRAP
static
Ptr<StereoSGBM>
create(
int
minDisparity = 0,
int
numDisparities = 16,
int
blockSize = 3,
3599
int
P1 = 0,
int
P2 = 0,
int
disp12MaxDiff = 0,
3600
int
preFilterCap = 0,
int
uniquenessRatio = 0,
3601
int
speckleWindowSize = 0,
int
speckleRange = 0,
3602
int
mode = StereoSGBM::MODE_SGBM);
3609
PROJ_SPHERICAL_ORTHO = 0,
3610
PROJ_SPHERICAL_EQRECT = 1
3643
InputArray cameraMatrix,
3644
InputArray distCoeffs,
3645
InputArray newCameraMatrix = noArray() );
3711
InputArray R, InputArray newCameraMatrix,
3782
InputArray R, InputArray newCameraMatrix,
3788
Size
imageSize,
int
destImageWidth,
3790
enum
UndistortTypes
projType = PROJ_SPHERICAL_EQRECT,
double
alpha = 0);
3793
Size
imageSize,
int
destImageWidth,
3795
int
projType,
double
alpha = 0)
3825
bool
centerPrincipalPoint =
false);
3869
InputArray cameraMatrix, InputArray distCoeffs,
3870
InputArray R = noArray(), InputArray P = noArray());
3876
InputArray cameraMatrix, InputArray distCoeffs,
3890
CALIB_USE_INTRINSIC_GUESS = 1 << 0,
3891
CALIB_RECOMPUTE_EXTRINSIC = 1 << 1,
3892
CALIB_CHECK_COND = 1 << 2,
3893
CALIB_FIX_SKEW = 1 << 3,
3894
CALIB_FIX_K1 = 1 << 4,
3895
CALIB_FIX_K2 = 1 << 5,
3896
CALIB_FIX_K3 = 1 << 6,
3897
CALIB_FIX_K4 = 1 << 7,
3898
CALIB_FIX_INTRINSIC = 1 << 8,
3899
CALIB_FIX_PRINCIPAL_POINT = 1 << 9,
3900
CALIB_ZERO_DISPARITY = 1 << 10,
3901
CALIB_FIX_FOCAL_LENGTH = 1 << 11
3925
InputArray K, InputArray D,
double
alpha = 0,
OutputArray
jacobian = noArray());
3929
InputArray K, InputArray D,
double
alpha = 0,
OutputArray
jacobian = noArray());
3958
InputArray K, InputArray D, InputArray R = noArray(), InputArray P = noArray());
4006
InputArray K, InputArray D, InputArray Knew = cv::noArray(),
const
Size& new_size =
Size());
4022
OutputArray
P,
double
balance = 0.0,
const
Size& new_size =
Size(),
double
fov_scale = 1.0);
4059
CV_EXPORTS_W
double
calibrate(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints,
const
Size& image_size,
4093
CV_EXPORTS_W
void
stereoRectify(InputArray K1, InputArray D1, InputArray K2, InputArray D2,
const
Size
&imageSize, InputArray R, InputArray tvec,
4095
double
balance = 0.0,
double
fov_scale = 1.0);
4129
CV_EXPORTS_W
double
stereoCalibrate(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2,
4141
class CV_EXPORTS CvLevMarq
4146
cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
4147
bool
completeSymmFlag=
false
);
4150
cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
4151
bool
completeSymmFlag=
false
);
4153
bool
updateAlt(
const
CvMat*& param,
CvMat*& JtJ,
CvMat*& JtErr,
double*& errNorm );
4157
enum
{ DONE=0, STARTED=1, CALC_J=2, CHECK_ERR=3 };
4169
double
prevErrNorm, errNorm;
4174
bool
completeSymmFlag;
This type is very similar to InputArray except that it is used for input/output and output function p...
Definition:
mat.hpp:295
This is a base class for all more or less complex algorithms in OpenCV
Definition:
core.hpp:3091
Definition:
calib3d.hpp:608
virtual bool compute(InputArray param, OutputArray err, OutputArray J) const =0
Definition:
calib3d.hpp:605
virtual int getMaxIters() const =0
virtual void setMaxIters(int maxIters)=0
virtual int run(InputOutputArray param) const =0
static Ptr< LMSolver > create(const Ptr< LMSolver::Callback > &cb, int maxIters)
n-dimensional dense array class
Definition:
mat.hpp:802
Template class for 2D points specified by its coordinates x and y.
Definition:
core/types.hpp:158
Template class for 2D rectangles
Definition:
core/types.hpp:421
Template class for specifying the size of an image or rectangle.
Definition:
core/types.hpp:316
Class for computing stereo correspondence using the block matching algorithm, introduced and contribu...
Definition:
calib3d.hpp:3471
The base class for stereo correspondence algorithms.
Definition:
calib3d.hpp:3430
The class implements the modified H. Hirschmuller algorithm that differs from the original one as fo...
Definition:
calib3d.hpp:3536
The class defining termination criteria for iterative algorithms.
Definition:
core/types.hpp:853
@ EPS
the desired accuracy or change in parameters at which the iterative algorithm stops
Definition:
core/types.hpp:862
@ COUNT
the maximum number of iterations or elements to compute
Definition:
core/types.hpp:860
Template class for short numerical vectors, a partial case of Matx
Definition:
matx.hpp:342
CV_EXPORTS_W double calibrate(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, const Size &image_size, InputOutputArray K, InputOutputArray D, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 100, DBL_EPSILON))
Performs camera calibaration
CV_EXPORTS_W void distortPoints(InputArray undistorted, OutputArray distorted, InputArray K, InputArray D, double alpha=0)
Distorts 2D points using fisheye model.
CV_EXPORTS_W void undistortImage(InputArray distorted, OutputArray undistorted, InputArray K, InputArray D, InputArray Knew=cv::noArray(), const Size &new_size=Size())
Transforms an image to compensate for fisheye lens distortion.
CV_EXPORTS_W void estimateNewCameraMatrixForUndistortRectify(InputArray K, InputArray D, const Size &image_size, InputArray R, OutputArray P, double balance=0.0, const Size &new_size=Size(), double fov_scale=1.0)
Estimates new camera intrinsic matrix for undistortion or rectification.
CV_EXPORTS_W void solvePnPRefineVVS(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec, InputOutputArray tvec, TermCriteria criteria=TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON), double VVSlambda=1)
Refine a pose (the translation and the rotation that transform a 3D point expressed in the object coo...
CV_EXPORTS_W bool find4QuadCornerSubpix(InputArray img, InputOutputArray corners, Size region_size)
finds subpixel-accurate positions of the chessboard corners
CV_EXPORTS_W bool findChessboardCorners(InputArray image, Size patternSize, OutputArray corners, int flags=CALIB_CB_ADAPTIVE_THRESH+CALIB_CB_NORMALIZE_IMAGE)
Finds the positions of internal corners of the chessboard.
CV_EXPORTS_W int solvePnPGeneric(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, bool useExtrinsicGuess=false, SolvePnPMethod flags=SOLVEPNP_ITERATIVE, InputArray rvec=noArray(), InputArray tvec=noArray(), OutputArray reprojectionError=noArray())
Finds an object pose from 3D-2D point correspondences. This function returns a list of all the possib...
CV_EXPORTS_AS(calibrateCameraExtended) double calibrateCamera(InputArrayOfArrays objectPoints
Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
CV_EXPORTS_W void calibrateRobotWorldHandEye(InputArrayOfArrays R_world2cam, InputArrayOfArrays t_world2cam, InputArrayOfArrays R_base2gripper, InputArrayOfArrays t_base2gripper, OutputArray R_base2world, OutputArray t_base2world, OutputArray R_gripper2cam, OutputArray t_gripper2cam, RobotWorldHandEyeCalibrationMethod method=CALIB_ROBOT_WORLD_HAND_EYE_SHAH)
Computes Robot-World/Hand-Eye calibration: and
CV_EXPORTS_W int estimateTranslation3D(InputArray src, InputArray dst, OutputArray out, OutputArray inliers, double ransacThreshold=3, double confidence=0.99)
Computes an optimal translation between two 3D point sets.
CV_EXPORTS_W void validateDisparity(InputOutputArray disparity, InputArray cost, int minDisparity, int numberOfDisparities, int disp12MaxDisp=1)
validates disparity using the left-right check. The matrix "cost" should be computed by the stereo co...
CV_EXPORTS_W int solveP3P(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags)
Finds an object pose from 3 3D-2D point correspondences.
CV_EXPORTS_W Mat findEssentialMat(InputArray points1, InputArray points2, InputArray cameraMatrix, int method=RANSAC, double prob=0.999, double threshold=1.0, int maxIters=1000, OutputArray mask=noArray())
Calculates an essential matrix from the corresponding points in two images.
CV_EXPORTS_W Mat findFundamentalMat(InputArray points1, InputArray points2, int method, double ransacReprojThreshold, double confidence, int maxIters, OutputArray mask=noArray())
Calculates a fundamental matrix from the corresponding points in two images.
SolvePnPMethod
Definition:
calib3d.hpp:456
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))
CV_EXPORTS_W void filterHomographyDecompByVisibleRefpoints(InputArrayOfArrays rotations, InputArrayOfArrays normals, InputArray beforePoints, InputArray afterPoints, OutputArray possibleSolutions, InputArray pointsMask=noArray())
Filters homography decompositions based on additional information.
CV_EXPORTS_W void matMulDeriv(InputArray A, InputArray B, OutputArray dABdA, OutputArray dABdB)
Computes partial derivatives of the matrix product for each multiplied matrix.
CV_EXPORTS_W void convertPointsToHomogeneous(InputArray src, OutputArray dst)
Converts points from Euclidean to homogeneous space.
CV_EXPORTS_W bool stereoRectifyUncalibrated(InputArray points1, InputArray points2, InputArray F, Size imgSize, OutputArray H1, OutputArray H2, double threshold=5)
Computes a rectification transform for an uncalibrated stereo camera.
CV_EXPORTS_W void computeCorrespondEpilines(InputArray points, int whichImage, InputArray F, OutputArray lines)
For points in an image of a stereo pair, computes the corresponding epilines in the other image.
CV_EXPORTS_W void undistortPoints(InputArray src, OutputArray dst, InputArray cameraMatrix, InputArray distCoeffs, InputArray R=noArray(), InputArray P=noArray())
Computes the ideal point coordinates from the observed point coordinates.
CV_EXPORTS_W void triangulatePoints(InputArray projMatr1, InputArray projMatr2, InputArray projPoints1, InputArray projPoints2, OutputArray points4D)
This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observati...
CV_EXPORTS_W void projectPoints(InputArray objectPoints, InputArray rvec, InputArray tvec, InputArray cameraMatrix, InputArray distCoeffs, OutputArray imagePoints, OutputArray jacobian=noArray(), double aspectRatio=0)
Projects 3D points to an image plane.
CV_EXPORTS_W double calibrateCamera(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, DBL_EPSILON))
CV_EXPORTS_W int recoverPose(InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, InputOutputArray mask=noArray())
Recovers the relative camera rotation and the translation from an estimated essential matrix and the ...
CV_EXPORTS_W void initUndistortRectifyMap(InputArray cameraMatrix, InputArray distCoeffs, InputArray R, InputArray newCameraMatrix, Size size, int m1type, OutputArray map1, OutputArray map2)
Computes the undistortion and rectification transformation map.
CV_EXPORTS_W void initInverseRectificationMap(InputArray cameraMatrix, InputArray distCoeffs, InputArray R, InputArray newCameraMatrix, const Size &size, int m1type, OutputArray map1, OutputArray map2)
Computes the projection and inverse-rectification transformation map. In essense, this is the inverse...
CV_EXPORTS_W Mat getOptimalNewCameraMatrix(InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, double alpha, Size newImgSize=Size(), CV_OUT Rect *validPixROI=0, bool centerPrincipalPoint=false)
Returns the new camera intrinsic matrix based on the free scaling parameter.
CV_EXPORTS_W void Rodrigues(InputArray src, OutputArray dst, OutputArray jacobian=noArray())
Converts a rotation matrix to a rotation vector or vice versa.
CV_EXPORTS_W void filterSpeckles(InputOutputArray img, double newVal, int maxSpeckleSize, double maxDiff, InputOutputArray buf=noArray())
Filters off small noise blobs (speckles) in the disparity map
CV_EXPORTS void convertPointsHomogeneous(InputArray src, OutputArray dst)
Converts points to/from homogeneous coordinates.
CV_EXPORTS_W Mat initCameraMatrix2D(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, Size imageSize, double aspectRatio=1.0)
Finds an initial camera intrinsic matrix from 3D-2D point correspondences.
CV_EXPORTS_W cv::Mat estimateAffinePartial2D(InputArray from, InputArray to, OutputArray inliers=noArray(), int method=RANSAC, double ransacReprojThreshold=3, size_t maxIters=2000, double confidence=0.99, size_t refineIters=10)
Computes an optimal limited affine transformation with 4 degrees of freedom between two 2D point sets...
RobotWorldHandEyeCalibrationMethod
Definition:
calib3d.hpp:540
CV_EXPORTS_W bool solvePnPRansac(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int iterationsCount=100, float reprojectionError=8.0, double confidence=0.99, OutputArray inliers=noArray(), int flags=SOLVEPNP_ITERATIVE)
Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
CV_EXPORTS_W Mat findHomography(InputArray srcPoints, InputArray dstPoints, int method=0, double ransacReprojThreshold=3, OutputArray mask=noArray(), const int maxIters=2000, const double confidence=0.995)
Finds a perspective transformation between two planes.
CV_EXPORTS_W void undistort(InputArray src, OutputArray dst, InputArray cameraMatrix, InputArray distCoeffs, InputArray newCameraMatrix=noArray())
Transforms an image to compensate for lens distortion.
CV_EXPORTS_W Scalar estimateChessboardSharpness(InputArray image, Size patternSize, InputArray corners, float rise_distance=0.8F, bool vertical=false, OutputArray sharpness=noArray())
Estimates the sharpness of a detected chessboard.
CV_EXPORTS_W void convertPointsFromHomogeneous(InputArray src, OutputArray dst)
Converts points from homogeneous to Euclidean space.
CV_EXPORTS_W int decomposeHomographyMat(InputArray H, InputArray K, OutputArrayOfArrays rotations, OutputArrayOfArrays translations, OutputArrayOfArrays normals)
Decompose a homography matrix to rotation(s), translation(s) and plane normal(s).
CV_EXPORTS_W void correctMatches(InputArray F, InputArray points1, InputArray points2, OutputArray newPoints1, OutputArray newPoints2)
Refines coordinates of corresponding points.
CV_EXPORTS_W int estimateAffine3D(InputArray src, InputArray dst, OutputArray out, OutputArray inliers, double ransacThreshold=3, double confidence=0.99)
Computes an optimal affine transformation between two 3D point sets.
CV_EXPORTS_W void calibrationMatrixValues(InputArray cameraMatrix, Size imageSize, double apertureWidth, double apertureHeight, CV_OUT double &fovx, CV_OUT double &fovy, CV_OUT double &focalLength, CV_OUT Point2d &principalPoint, CV_OUT double &aspectRatio)
Computes useful camera characteristics from the camera intrinsic matrix.
CV_EXPORTS float initWideAngleProjMap(InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, int destImageWidth, int m1type, OutputArray map1, OutputArray map2, enum UndistortTypes projType=PROJ_SPHERICAL_EQRECT, double alpha=0)
initializes maps for remap for wide-angle
CV_EXPORTS_W bool solvePnP(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int flags=SOLVEPNP_ITERATIVE)
Finds an object pose from 3D-2D point correspondences. This function returns the rotation and the tra...
CV_EXPORTS_W void solvePnPRefineLM(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec, InputOutputArray tvec, TermCriteria criteria=TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON))
Refine a pose (the translation and the rotation that transform a 3D point expressed in the object coo...
CV_EXPORTS_W void decomposeProjectionMatrix(InputArray projMatrix, OutputArray cameraMatrix, OutputArray rotMatrix, OutputArray transVect, OutputArray rotMatrixX=noArray(), OutputArray rotMatrixY=noArray(), OutputArray rotMatrixZ=noArray(), OutputArray eulerAngles=noArray())
Decomposes a projection matrix into a rotation matrix and a camera intrinsic matrix.
CV_EXPORTS_W Vec3d RQDecomp3x3(InputArray src, OutputArray mtxR, OutputArray mtxQ, OutputArray Qx=noArray(), OutputArray Qy=noArray(), OutputArray Qz=noArray())
Computes an RQ decomposition of 3x3 matrices.
CV_EXPORTS_W Rect getValidDisparityROI(Rect roi1, Rect roi2, int minDisparity, int numberOfDisparities, int blockSize)
computes valid disparity ROI from the valid ROIs of the rectified images (that are returned by stereo...
UndistortTypes
cv::undistort mode
Definition:
calib3d.hpp:3608
HandEyeCalibrationMethod
Definition:
calib3d.hpp:531
CV_EXPORTS_W cv::Mat estimateAffine2D(InputArray from, InputArray to, OutputArray inliers=noArray(), int method=RANSAC, double ransacReprojThreshold=3, size_t maxIters=2000, double confidence=0.99, size_t refineIters=10)
Computes an optimal affine transformation between two 2D point sets.
CV_EXPORTS_W void reprojectImageTo3D(InputArray disparity, OutputArray _3dImage, InputArray Q, bool handleMissingValues=false, int ddepth=-1)
Reprojects a disparity image to 3D space.
CV_EXPORTS_W void drawFrameAxes(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length, int thickness=3)
Draw axes of the world/object coordinate system from pose estimation.
bool findChessboardCornersSB(InputArray image, Size patternSize, OutputArray corners, int flags, OutputArray meta)
Finds the positions of internal corners of the chessboard using a sector based approach.
CV_EXPORTS_W void decomposeEssentialMat(InputArray E, OutputArray R1, OutputArray R2, OutputArray t)
Decompose an essential matrix to possible rotations and translation.
CV_EXPORTS_W float rectify3Collinear(InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, InputArray cameraMatrix3, InputArray distCoeffs3, InputArrayOfArrays imgpt1, InputArrayOfArrays imgpt3, Size imageSize, InputArray R12, InputArray T12, InputArray R13, InputArray T13, OutputArray R1, OutputArray R2, OutputArray R3, OutputArray P1, OutputArray P2, OutputArray P3, OutputArray Q, double alpha, Size newImgSize, CV_OUT Rect *roi1, CV_OUT Rect *roi2, int flags)
computes the rectification transformations for 3-head camera, where all the heads are on the same lin...
CV_EXPORTS_W void composeRT(InputArray rvec1, InputArray tvec1, InputArray rvec2, InputArray tvec2, OutputArray rvec3, OutputArray tvec3, OutputArray dr3dr1=noArray(), OutputArray dr3dt1=noArray(), OutputArray dr3dr2=noArray(), OutputArray dr3dt2=noArray(), OutputArray dt3dr1=noArray(), OutputArray dt3dt1=noArray(), OutputArray dt3dr2=noArray(), OutputArray dt3dt2=noArray())
Combines two rotation-and-shift transformations.
CV_EXPORTS_W void calibrateHandEye(InputArrayOfArrays R_gripper2base, InputArrayOfArrays t_gripper2base, InputArrayOfArrays R_target2cam, InputArrayOfArrays t_target2cam, OutputArray R_cam2gripper, OutputArray t_cam2gripper, HandEyeCalibrationMethod method=CALIB_HAND_EYE_TSAI)
Computes Hand-Eye calibration:
CV_EXPORTS_W double sampsonDistance(InputArray pt1, InputArray pt2, InputArray F)
Calculates the Sampson Distance between two points.
CV_EXPORTS_W void stereoRectify(InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, Size imageSize, InputArray R, InputArray T, OutputArray R1, OutputArray R2, OutputArray P1, OutputArray P2, OutputArray Q, int flags=CALIB_ZERO_DISPARITY, double alpha=-1, Size newImageSize=Size(), CV_OUT Rect *validPixROI1=0, CV_OUT Rect *validPixROI2=0)
Computes rectification transforms for each head of a calibrated stereo camera.
CV_EXPORTS_W double stereoCalibrate(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2, InputOutputArray cameraMatrix1, InputOutputArray distCoeffs1, InputOutputArray cameraMatrix2, InputOutputArray distCoeffs2, Size imageSize, OutputArray R, OutputArray T, OutputArray E, OutputArray F, int flags=CALIB_FIX_INTRINSIC, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, 1e-6))
これはオーバーロードされたメンバ関数です。利便性のために用意されています。元の関数との違いは引き数のみです。
CV_EXPORTS_W Mat getDefaultNewCameraMatrix(InputArray cameraMatrix, Size imgsize=Size(), bool centerPrincipalPoint=false)
Returns the default new camera matrix.
CV_EXPORTS_W void drawChessboardCorners(InputOutputArray image, Size patternSize, InputArray corners, bool patternWasFound)
Renders the detected chessboard corners.
CV_EXPORTS_W bool findCirclesGrid(InputArray image, Size patternSize, OutputArray centers, int flags, const Ptr< FeatureDetector > &blobDetector, const CirclesGridFinderParameters ¶meters)
Finds centers in the grid of circles.
@ SOLVEPNP_UPNP
Definition:
calib3d.hpp:462
@ SOLVEPNP_MAX_COUNT
Used for count
Definition:
calib3d.hpp:476
@ SOLVEPNP_AP3P
An Efficient Algebraic Solution to the Perspective-Three-Point Problem
Definition:
calib3d.hpp:464
@ SOLVEPNP_SQPNP
SQPnP: A Consistently Fast and Globally OptimalSolution to the Perspective-n-Point Problem
Definition:
calib3d.hpp:474
@ SOLVEPNP_DLS
Definition:
calib3d.hpp:460
@ SOLVEPNP_IPPE_SQUARE
Definition:
calib3d.hpp:467
@ SOLVEPNP_IPPE
Definition:
calib3d.hpp:465
@ SOLVEPNP_EPNP
EPnP: Efficient Perspective-n-Point Camera Pose Estimation
Definition:
calib3d.hpp:458
@ SOLVEPNP_P3P
Complete Solution Classification for the Perspective-Three-Point Problem
Definition:
calib3d.hpp:459
@ CALIB_USE_LU
use LU instead of SVD decomposition for solving. much faster but potentially less precise
Definition:
calib3d.hpp:519
@ CALIB_USE_QR
use QR instead of SVD decomposition for solving. Faster but potentially less precise
Definition:
calib3d.hpp:512
@ CALIB_USE_EXTRINSIC_GUESS
for stereoCalibrate
Definition:
calib3d.hpp:520
@ CALIB_ROBOT_WORLD_HAND_EYE_SHAH
Solving the robot-world/hand-eye calibration problem using the kronecker product
Definition:
calib3d.hpp:541
@ CALIB_ROBOT_WORLD_HAND_EYE_LI
Simultaneous robot-world and hand-eye calibration using dual-quaternions and kronecker product
Definition:
calib3d.hpp:542
@ USAC_FM_8PTS
USAC, fundamental matrix 8 points
Definition:
calib3d.hpp:449
@ USAC_PROSAC
USAC, sorted points, runs PROSAC
Definition:
calib3d.hpp:452
@ USAC_MAGSAC
USAC, runs MAGSAC++
Definition:
calib3d.hpp:453
@ USAC_DEFAULT
USAC algorithm, default settings
Definition:
calib3d.hpp:447
@ RHO
RHO algorithm
Definition:
calib3d.hpp:446
@ RANSAC
RANSAC algorithm
Definition:
calib3d.hpp:445
@ USAC_ACCURATE
USAC, accurate settings
Definition:
calib3d.hpp:451
@ USAC_PARALLEL
USAC, parallel version
Definition:
calib3d.hpp:448
@ USAC_FAST
USAC, fast settings
Definition:
calib3d.hpp:450
@ LMEDS
least-median of squares algorithm
Definition:
calib3d.hpp:444
@ CALIB_HAND_EYE_TSAI
A New Technique for Fully Autonomous and Efficient 3D Robotics Hand/Eye Calibration
Definition:
calib3d.hpp:532
@ CALIB_HAND_EYE_ANDREFF
On-line Hand-Eye Calibration
Definition:
calib3d.hpp:535
@ CALIB_HAND_EYE_PARK
Robot Sensor Calibration: Solving AX = XB on the Euclidean Group
Definition:
calib3d.hpp:533
@ CALIB_HAND_EYE_HORAUD
Hand-eye Calibration
Definition:
calib3d.hpp:534
@ CALIB_HAND_EYE_DANIILIDIS
Hand-Eye Calibration Using Dual Quaternions
Definition:
calib3d.hpp:536
@ FM_8POINT
8-point algorithm
Definition:
calib3d.hpp:525
@ FM_LMEDS
least-median algorithm. 7-point algorithm is used.
Definition:
calib3d.hpp:526
@ FM_7POINT
7-point algorithm
Definition:
calib3d.hpp:524
@ FM_RANSAC
RANSAC algorithm. It needs at least 15 points. 7-point algorithm is used.
Definition:
calib3d.hpp:527
CV_EXPORTS_W double threshold(InputArray src, OutputArray dst, double thresh, double maxval, int type)
Applies a fixed-level threshold to each array element.
"black box" representation of the file storage associated with a file on disk.
Definition:
aruco.hpp:75
Definition:
core/types_c.h:469
Definition:
core/types_c.h:918
Definition:
calib3d.hpp:1631
Definition:
cvstd_wrapper.hpp:74
Definition:
calib3d.hpp:553