Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
@ -118,13 +121,13 @@ cv::calibrateCamera
:param distCoeffs:The output vector of distortion coefficients :math:`(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6]])` of 4, 5 or 8 elements
:param rvecs:The output vector of rotation vectors (see :ref:`Rodrigues2` ), estimated for each pattern view. That is, each k-th rotation vector together with the corresponding k-th translation vector (see the next output parameter description) brings the calibration pattern from the model coordinate space (in which object points are specified) to the world coordinate space, i.e. real position of the calibration pattern in the k-th pattern view (k=0.. *M* -1)
:param rvecs:The output vector of rotation vectors (see :ref:`Rodrigues` ), estimated for each pattern view. That is, each k-th rotation vector together with the corresponding k-th translation vector (see the next output parameter description) brings the calibration pattern from the model coordinate space (in which object points are specified) to the world coordinate space, i.e. real position of the calibration pattern in the k-th pattern view (k=0.. *M* -1)
:param tvecs:The output vector of translation vectors, estimated for each pattern view.
:param flags:Different flags, may be 0 or combination of the following values:
* **CV_CALIB_USE_INTRINSIC_GUESS** ``cameraMatrix`` contains the valid initial values of ``fx, fy, cx, cy`` that are optimized further. Otherwise, ``(cx, cy)`` is initially set to the image center ( ``imageSize`` is used here), and focal distances are computed in some least-squares fashion. Note, that if intrinsic parameters are known, there is no need to use this function just to estimate the extrinsic parameters. Use :ref:`FindExtrinsicCameraParams2` instead.
* **CV_CALIB_USE_INTRINSIC_GUESS** ``cameraMatrix`` contains the valid initial values of ``fx, fy, cx, cy`` that are optimized further. Otherwise, ``(cx, cy)`` is initially set to the image center ( ``imageSize`` is used here), and focal distances are computed in some least-squares fashion. Note, that if intrinsic parameters are known, there is no need to use this function just to estimate the extrinsic parameters. Use :ref:`solvePnP` instead.
* **CV_CALIB_FIX_PRINCIPAL_POINT** The principal point is not changed during the global optimization, it stays at the center or at the other location specified when ``CV_CALIB_USE_INTRINSIC_GUESS`` is set too.
@ -144,7 +147,7 @@ object with known geometry and easily detectable feature points.
Such an object is called a calibration rig or calibration pattern,
and OpenCV has built-in support for a chessboard as a calibration
of intrinsic parameters (when ``CV_CALIB_USE_INTRINSIC_GUESS`` is not set) is only implemented for planar calibration patterns
(where z-coordinates of the object points must be all 0's). 3D
calibration rigs can also be used as long as initial ``cameraMatrix`` is provided.
@ -156,10 +159,9 @@ The algorithm does the following:
#.
The initial camera pose is estimated as if the intrinsic parameters have been already known. This is done using
:ref:`FindExtrinsicCameraParams2`
:ref:`solvePnP`
#.
After that the global Levenberg-Marquardt optimization algorithm is run to minimize the reprojection error, i.e. the total sum of squared distances between the observed feature points ``imagePoints`` and the projected (using the current estimates for camera parameters and the poses) object points ``objectPoints`` ; see
:ref:`ProjectPoints2` .
After that the global Levenberg-Marquardt optimization algorithm is run to minimize the reprojection error, i.e. the total sum of squared distances between the observed feature points ``imagePoints`` and the projected (using the current estimates for camera parameters and the poses) object points ``objectPoints``; see :ref:`projectPoints` .
The function returns the final re-projection error.
Note: if you're using a non-square (=non-NxN) grid and
@ -172,16 +174,20 @@ bad values (i.e. zero distortion coefficients, an image center very far from
For points in one image of a stereo pair, computes the corresponding epilines in the other image.
@ -248,7 +258,7 @@ cv::computeCorrespondEpilines
:param whichImage:Index of the image (1 or 2) that contains the ``points``
:param F:The fundamental matrix that can be estimated using :ref:`FindFundamentalMat` or :ref:`StereoRectify` .
:param F:The fundamental matrix that can be estimated using :ref:`findFundamentalMat` or :ref:`StereoRectify` .
:param lines:The output vector of the corresponding to the points epipolar lines in the other image. Each line :math:`ax + by + c=0` is encoded by 3 numbers :math:`(a, b, c)`
@ -256,7 +266,7 @@ For every point in one of the two images of a stereo-pair the function finds the
corresponding epipolar line in the other image.
From the fundamental matrix definition (see
:ref:`FindFundamentalMat` ),
:ref:`findFundamentalMat` ),
line
:math:`l^{(2)}_i` in the second image for the point
:math:`p^{(1)}_i` in the first image (i.e. when ``whichImage=1`` ) is computed as:
@ -277,8 +287,11 @@ Line coefficients are defined up to a scale. They are normalized, such that
:param image:The destination image; it must be an 8-bit color image
:param patternSize:The number of inner corners per chessboard row and column. (patternSize = cv::Size(points_per_row,points_per_column) = cv::Size(rows,columns) )
:param patternSize:The number of inner corners per chessboard row and column. (patternSize = cv::Size(points_per_row,points_per_column) = cv::Size(rows,columns) )
:param corners:The array of corners detected, this should be the output from findChessboardCorners wrapped in a cv::Mat().
@ -351,16 +368,18 @@ The function draws the individual chessboard corners detected as red circles if
Finds the object pose from the 3D-2D point correspondences
@ -468,20 +490,23 @@ cv::solvePnP
:param cameraMatrix:The input camera matrix :math:`A = \vecthreethree{fx}{0}{cx}{0}{fy}{cy}{0}{0}{1}`
:param distCoeffs:The input vector of distortion coefficients :math:`(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6]])` of 4, 5 or 8 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
:param rvec:The output rotation vector (see :ref:`Rodrigues2` ) that (together with ``tvec`` ) brings points from the model coordinate system to the camera coordinate system
:param rvec:The output rotation vector (see :ref:`Rodrigues` ) that (together with ``tvec`` ) brings points from the model coordinate system to the camera coordinate system
:param tvec:The output translation vector
:param useExtrinsicGuess:If true (1), the function will use the provided ``rvec`` and ``tvec`` as the initial approximations of the rotation and translation vectors, respectively, and will further optimize them.
The function estimates the object pose given a set of object points, their corresponding image projections, as well as the camera matrix and the distortion coefficients. This function finds such a pose that minimizes reprojection error, i.e. the sum of squared distances between the observed projections ``imagePoints`` and the projected (using
Finds the object pose from the 3D-2D point correspondences
@ -490,9 +515,10 @@ cv::solvePnPRansac
:param imagePoints:The array of corresponding image points, 2xN or Nx2 1-channel or 1xN or Nx1 2-channel, where N is the number of points. Can also pass ``vector<Point2f>`` here.
:param cameraMatrix:The input camera matrix :math:`A = \vecthreethree{fx}{0}{cx}{0}{fy}{cy}{0}{0}{1}`
:param distCoeffs:The input vector of distortion coefficients :math:`(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6]])` of 4, 5 or 8 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
:param rvec:The output rotation vector (see :ref:`Rodrigues2` ) that (together with ``tvec`` ) brings points from the model coordinate system to the camera coordinate system
:param rvec:The output rotation vector (see :ref:`Rodrigues` ) that (together with ``tvec`` ) brings points from the model coordinate system to the camera coordinate system
:param tvec:The output translation vector
@ -507,15 +533,17 @@ cv::solvePnPRansac
:param inliers:The output vector that contained indices of inliers in objectPoints and imagePoints
The function estimates the object pose given a set of object points, their corresponding image projections, as well as the camera matrix and the distortion coefficients. This function finds such a pose that minimizes reprojection error, i.e. the sum of squared distances between the observed projections ``imagePoints`` and the projected (using
:ref:`ProjectPoints2` ) ``objectPoints``. Through the use of RANSAC function is resistant to outliers.
:ref:`projectPoints` ) ``objectPoints``. Through the use of RANSAC the function is resistant to outliers.
..index:: findFundamentalMat
cv::findFundamentalMat
.._findFundamentalMat:
findFundamentalMat
----------------------
..c:function:: Mat findFundamentalMat( const Mat& points1, const Mat& points2, vector<uchar>& status, int method=FM_RANSAC, double param1=3., double param2=0.99 )
..c:function:: Mat findFundamentalMat( const Mat& points1, const Mat& points2, vector<uchar>& status, int method=FM_RANSAC, double param1=3., double param2=0.99 )
..c:function:: Mat findFundamentalMat( const Mat& points1, const Mat& points2, int method=FM_RANSAC, double param1=3., double param2=0.99 )
..c:function:: Mat findFundamentalMat( const Mat& points1, const Mat& points2, int method=FM_RANSAC, double param1=3., double param2=0.99 )
Calculates the fundamental matrix from the corresponding points in two images.
@ -572,13 +600,15 @@ corresponding to the specified points. It can also be passed to
..index:: findHomography
cv::findHomography
.._findHomography:
findHomography
------------------
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, Mat& status, int method=0, double ransacReprojThreshold=3 )
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, Mat& status, int method=0, double ransacReprojThreshold=3 )
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, vector<uchar>& status, int method=0, double ransacReprojThreshold=3 )
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, vector<uchar>& status, int method=0, double ransacReprojThreshold=3 )
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, int method=0, double ransacReprojThreshold=3 )
..c:function:: Mat findHomography( const Mat& srcPoints, const Mat& dstPoints, int method=0, double ransacReprojThreshold=3 )
Finds the perspective transformation between two planes.
:param objectPoints:The array of object points, 3xN or Nx3 1-channel or 1xN or Nx1 3-channel (or ``vector<Point3f>`` ) , where N is the number of points in the view
:param rvec:The rotation vector, see :ref:`Rodrigues2`
:param rvec:The rotation vector, see :ref:`Rodrigues`
:param tvec:The translation vector
@ -841,8 +885,7 @@ of partial derivatives of image points coordinates (as functions of all the
input parameters) with respect to the particular parameters, intrinsic and/or
extrinsic. The jacobians are used during the global optimization
in
:ref:`CalibrateCamera2`,:ref:`FindExtrinsicCameraParams2` and
:ref:`StereoCalibrate` . The
:ref:`calibrateCamera`, :ref:`solvePnP` and :ref:`stereoCalibrate` . The
function itself can also used to compute re-projection error given the
current intrinsic and extrinsic parameters.
@ -850,10 +893,12 @@ Note, that by setting ``rvec=tvec=(0,0,0)`` , or by setting ``cameraMatrix`` to
:param Q:The :math:`4 \times 4` perspective transformation matrix that can be obtained with :ref:`StereoRectify`
:param handleMissingValues:If true, when the pixels with the minimal disparity (that corresponds to the outliers; see :ref:`FindStereoCorrespondenceBM` ) will be transformed to 3D points with some very large Z value (currently set to 10000)
:param handleMissingValues:If true, when the pixels with the minimal disparity (that corresponds to the outliers; see :ref:`StereoBM::operator ()` ) will be transformed to 3D points with some very large Z value (currently set to 10000)
The function transforms 1-channel disparity map to 3-channel image representing a 3D surface. That is, for each pixel ``(x,y)`` and the corresponding disparity ``d=disparity(x,y)`` it computes:
@ -879,11 +924,13 @@ The matrix ``Q`` can be arbitrary
Computes disparity using BM algorithm for a rectified stereo pair
:param left:The left image, 8-bit single-channel or 3-channel.
:param right:The right image of the same size and the same type as the left one.
:param disp:The output disparity map. It will have the same size as the input images. When ``disptype==CV_16S``, the map will be 16-bit signed single-channel image, containing scaled by 16 disparity values, so that to get the floating-point disparity map, you will need to divide each ``disp`` element by 16. Otherwise, it will be floating-point disparity map.
:param disptype:The type of the output disparity map, ``CV_16S`` (default) or ``CV_32F``.
The method executes BM algorithm on a rectified stereo pair. See ``stereo_match.cpp`` OpenCV sample on how to prepare the images and call the method. Note that the method is not constant, thus you should not use the same ``StereoBM`` instance from within different threads simultaneously.
..index:: StereoSGBM
@ -980,6 +1051,7 @@ The class is a C++ wrapper for and the associated functions. In particular, ``St
StereoSGBM
----------
..c:type:: StereoSGBM
The class for computing stereo correspondence using semi-global block matching algorithm. ::
@ -1010,34 +1082,25 @@ The class for computing stereo correspondence using semi-global block matching a
...
};
The class implements modified H. Hirschmuller algorithm
HH08
. The main differences between the implemented algorithm and the original one are:
The class implements modified H. Hirschmuller algorithm HH08. The main differences between the implemented algorithm and the original one are:
*
by default the algorithm is single-pass, i.e. instead of 8 directions we only consider 5. Set ``fullDP=true`` to run the full variant of the algorithm (which could consume
*a lot*
of memory)
* by default the algorithm is single-pass, i.e. instead of 8 directions we only consider 5. Set ``fullDP=true`` to run the full variant of the algorithm (which could consume *a lot* of memory)
*
the algorithm matches blocks, not individual pixels (though, by setting ``SADWindowSize=1`` the blocks are reduced to single pixels)
* the algorithm matches blocks, not individual pixels (though, by setting ``SADWindowSize=1`` the blocks are reduced to single pixels)
*
mutual information cost function is not implemented. Instead, we use a simpler Birchfield-Tomasi sub-pixel metric from
BT96
, though the color images are supported as well.
* mutual information cost function is not implemented. Instead, we use a simpler Birchfield-Tomasi sub-pixel metric from BT96, though the color images are supported as well.
*
we include some pre- and post- processing steps from K. Konolige algorithm
:ref:`FindStereoCorrespondceBM` , such as pre-filtering ( ``CV_STEREO_BM_XSOBEL`` type) and post-filtering (uniqueness check, quadratic interpolation and speckle filtering)
* we include some pre- and post- processing steps from K. Konolige algorithm :ref:`StereoBM::operator ()` , such as pre-filtering (``CV_STEREO_BM_XSOBEL`` type) and post-filtering (uniqueness check, quadratic interpolation and speckle filtering)
..index:: StereoSGBM::StereoSGBM
cv::StereoSGBM::StereoSGBM
.._StereoSGBM::StereoSGBM:
StereoSGBM::StereoSGBM
--------------------------
..c:function:: StereoSGBM::StereoSGBM()
..c:function:: StereoSGBM::StereoSGBM( int minDisparity, int numDisparities, int SADWindowSize, int P1=0, int P2=0, int disp12MaxDiff=0, int preFilterCap=0, int uniquenessRatio=0, int speckleWindowSize=0, int speckleRange=0, bool fullDP=false)
..c:function:: StereoSGBM::StereoSGBM( int minDisparity, int numDisparities, int SADWindowSize, int P1=0, int P2=0, int disp12MaxDiff=0, int preFilterCap=0, int uniquenessRatio=0, int speckleWindowSize=0, int speckleRange=0, bool fullDP=false)
StereoSGBM constructors
@ -1065,10 +1128,12 @@ The first constructor initializes ``StereoSGBM`` with all the default parameters
:param imagePoints2:The vector of vectors of the object point projections on the calibration pattern views from the 2nd camera, one vector per a view. The projections must be in the same order as the corresponding object points.
:param cameraMatrix1:The input/output first camera matrix: :math:`\vecthreethree{f_x^{(j)}}{0}{c_x^{(j)}}{0}{f_y^{(j)}}{c_y^{(j)}}{0}{0}{1}` , :math:`j = 0,\, 1` . If any of ``CV_CALIB_USE_INTRINSIC_GUESS`` , ``CV_CALIB_FIX_ASPECT_RATIO`` , ``CV_CALIB_FIX_INTRINSIC`` or ``CV_CALIB_FIX_FOCAL_LENGTH`` are specified, some or all of the matrices' components must be initialized; see the flags description
:param cameraMatrix1:The input/output first camera matrix: :math:`\vecthreethree{f_x^{(j)}}{0}{c_x^{(j)}}{0}{f_y^{(j)}}{c_y^{(j)}}{0}{0}{1}` , :math:`j = 0,\, 1` . If any of ``CV_CALIB_USE_INTRINSIC_GUESS`` , ``CV_CALIB_FIX_ASPECT_RATIO`` , ``CV_CALIB_FIX_INTRINSIC`` or ``CV_CALIB_FIX_FOCAL_LENGTH`` are specified, some or all of the matrices' components must be initialized; see the flags description
:param distCoeffs:The input/output vector of distortion coefficients :math:`(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6]])` of 4, 5 or 8 elements. On output vector length depends on the flags.
@ -1116,7 +1183,7 @@ cv::stereoCalibrate
:param flags:Different flags, may be 0 or combination of the following values:
* **CV_CALIB_FIX_INTRINSIC** If it is set, ``cameraMatrix?`` , as well as ``distCoeffs?`` are fixed, so that only ``R, T, E`` and ``F`` are estimated.
* **CV_CALIB_FIX_INTRINSIC** If it is set, ``cameraMatrix?`` , as well as ``distCoeffs?`` are fixed, so that only ``R, T, E`` and ``F`` are estimated.
* **CV_CALIB_USE_INTRINSIC_GUESS** The flag allows the function to optimize some or all of the intrinsic parameters, depending on the other flags, but the initial values are provided by the user.
@ -1134,7 +1201,7 @@ cv::stereoCalibrate
* **CV_CALIB_RATIONAL_MODEL** Enable coefficients k4, k5 and k6. To provide the backward compatibility, this extra flag should be explicitly specified to make the calibration function use the rational model and return 8 coefficients. If the flag is not set, the function will compute and return only 5 distortion coefficients.
The function estimates transformation between the 2 cameras making a stereo pair. If we have a stereo camera, where the relative position and orientation of the 2 cameras is fixed, and if we computed poses of an object relative to the fist camera and to the second camera, (R1, T1) and (R2, T2), respectively (that can be done with
:ref:`FindExtrinsicCameraParams2` ), obviously, those poses will relate to each other, i.e. given (
:ref:`solvePnP` ), obviously, those poses will relate to each other, i.e. given (
:math:`R_1`,:math:`T_1` ) it should be possible to compute (
:math:`R_2`,:math:`T_2` ) - we only need to know the position and orientation of the 2nd camera relative to the 1st camera. That's what the described function does. It computes (
:math:`R`,:math:`T` ) such that:
@ -1160,19 +1227,19 @@ where
F = cameraMatrix2^{-T} E cameraMatrix1^{-1}
Besides the stereo-related information, the function can also perform full calibration of each of the 2 cameras. However, because of the high dimensionality of the parameter space and noise in the input data the function can diverge from the correct solution. Thus, if intrinsic parameters can be estimated with high accuracy for each of the cameras individually (e.g. using
:ref:`CalibrateCamera2` ), it is recommended to do so and then pass ``CV_CALIB_FIX_INTRINSIC`` flag to the function along with the computed intrinsic parameters. Otherwise, if all the parameters are estimated at once, it makes sense to restrict some parameters, e.g. pass ``CV_CALIB_SAME_FOCAL_LENGTH`` and ``CV_CALIB_ZERO_TANGENT_DIST`` flags, which are usually reasonable assumptions.
:ref:`calibrateCamera` ), it is recommended to do so and then pass ``CV_CALIB_FIX_INTRINSIC`` flag to the function along with the computed intrinsic parameters. Otherwise, if all the parameters are estimated at once, it makes sense to restrict some parameters, e.g. pass ``CV_CALIB_SAME_FOCAL_LENGTH`` and ``CV_CALIB_ZERO_TANGENT_DIST`` flags, which are usually reasonable assumptions.
Similarly to
:ref:`CalibrateCamera2` , the function minimizes the total re-projection error for all the points in all the available views from both cameras.
The function returns the final value of the re-projection error.
Similarly to :ref:`calibrateCamera` , the function minimizes the total re-projection error for all the points in all the available views from both cameras. The function returns the final value of the re-projection error.
Computes rectification transform for uncalibrated stereo camera.
:param points1, points2:The 2 arrays of corresponding 2D points. The same formats as in :ref:`FindFundamentalMat` are supported
:param points1, points2:The 2 arrays of corresponding 2D points. The same formats as in :ref:`findFundamentalMat` are supported
:param F:The input fundamental matrix. It can be computed from the same set of point pairs using :ref:`FindFundamentalMat` .
:param F:The input fundamental matrix. It can be computed from the same set of point pairs using :ref:`findFundamentalMat` .
:param imageSize:Size of the image.
@ -1266,15 +1335,17 @@ Hartley99
.
Note that while the algorithm does not need to know the intrinsic parameters of the cameras, it heavily depends on the epipolar geometry. Therefore, if the camera lenses have significant distortion, it would better be corrected before computing the fundamental matrix and calling this function. For example, distortion coefficients can be estimated for each head of stereo camera separately by using
:ref:`CalibrateCamera2` and then the images can be corrected using
:ref:`Undistort2` , or just the point coordinates can be corrected with
:ref:`UndistortPoints` .
:ref:`calibrateCamera` and then the images can be corrected using
:ref:`undistort` , or just the point coordinates can be corrected with
:param P:The new camera matrix (3x3) or the new projection matrix (3x4). ``P1`` or ``P2`` , computed by :func:`StereoRectify` can be passed here. If the matrix is empty, the identity new camera matrix is used
The function is similar to
:ref:`Undistort2` and
:ref:`InitUndistortRectifyMap` , but it operates on a sparse set of points instead of a raster image. Also the function does some kind of reverse transformation to
:ref:`ProjectPoints2` (in the case of 3D object it will not reconstruct its 3D coordinates, of course; but for a planar object it will, up to a translation vector, if the proper ``R`` is specified). ::
:ref:`undistort` and
:ref:`initUndistortRectifyMap` , but it operates on a sparse set of points instead of a raster image. Also the function does some kind of reverse transformation to
:ref:`projectPoints` (in the case of 3D object it will not reconstruct its 3D coordinates, of course; but for a planar object it will, up to a translation vector, if the proper ``R`` is specified). ::
// (u,v) is the input point, (u', v') is the output point
@ -32,9 +34,8 @@ Template "traits" class for other OpenCV primitive data types ::
};
};
The template class ``DataType`` is descriptive class for OpenCV primitive data types and other types that comply with the following definition. A primitive OpenCV data type is one of ``unsigned char, bool, signed char, unsigned short, signed short, int, float, double`` or a tuple of values of one of these types, where all the values in the tuple have the same type. If you are familiar with OpenCV
:ref:`CvMat` 's type notation, CV_8U ... CV_32FC3, CV_64FC2 etc., then a primitive type can be defined as a type for which you can give a unique identifier in a form ``CV_<bit-depth>{U|S|F}C<number_of_channels>`` . A universal OpenCV structure able to store a single instance of such primitive data type is
:ref:`Vec` . Multiple instances of such a type can be stored to a ``std::vector``,``Mat``,``Mat_``,``SparseMat``,``SparseMat_`` or any other container that is able to store
The template class ``DataType`` is descriptive class for OpenCV primitive data types and other types that comply with the following definition. A primitive OpenCV data type is one of ``unsigned char``, ``bool``, ``signed char``, ``unsigned short``, ``signed short``, ``int``, ``float``, ``double`` or a tuple of values of one of these types, where all the values in the tuple have the same type. Any primitive type from the list can be defined by an identifier in a form ``CV_<bit-depth>{U|S|F}C<number_of_channels>``, for example, ``uchar`` ~ ``CV_8UC1``, 3-element floating-point tuple ~ ``CV_32FC3`` etc. A universal OpenCV structure, which is able to store a single instance of such primitive data type is
:ref:`Vec`. Multiple instances of such a type can be stored to a ``std::vector``,``Mat``,``Mat_``,``SparseMat``,``SparseMat_`` or any other container that is able to store
:ref:`Vec` instances.
The class ``DataType`` is basically used to provide some description of such primitive data types without adding any fields or methods to the corresponding classes (and it is actually impossible to add anything to primitive C/C++ data types). This technique is known in C++ as class traits. It's not ``DataType`` itself that is used, but its specialized versions, such as: ::
@ -205,8 +206,7 @@ Template class for specfying image or rectangle size. ::
The class ``Size_`` is similar to ``Point_`` , except that the two members are called ``width`` and ``height`` instead of ``x`` and ``y`` . The structure can be converted to and from the old OpenCV structures
:ref:`CvSize` and
:ref:`CvSize2D32f` . The same set of arithmetic and comparison operations as for ``Point_`` is available.
``CvSize`` and ``CvSize2D32f`` . The same set of arithmetic and comparison operations as for ``Point_`` is available.
OpenCV defines the following type aliases: ::
@ -267,7 +267,7 @@ Another assumption OpenCV usually makes is that the top and left boundary of the
y \leq pt.y < y+height
And virtually every loop over an image
:ref:`ROI` in OpenCV (where ROI is specified by ``Rect_<int>`` ) is implemented as:::
ROI in OpenCV (where ROI is specified by ``Rect_<int>`` ) is implemented as: ::
for(int y = roi.y; y < roi.y + rect.height; y++)
for(int x = roi.x; x < roi.x + rect.width; x++)
@ -309,6 +309,8 @@ For user convenience, the following type alias is available: ::
typedef Rect_<int> Rect;
.._RotatedRect:
RotatedRect
-----------
@ -336,8 +338,7 @@ Possibly rotated rectangle ::
};
The class ``RotatedRect`` replaces the old
:ref:`CvBox2D` and fully compatible with it.
The class ``RotatedRect`` replaces the old ``CvBox2D`` and fully compatible with it.
TermCriteria
------------
@ -368,8 +369,9 @@ Termination criteria for iterative algorithms ::
};
The class ``TermCriteria`` replaces the old
:ref:`CvTermCriteria` and fully compatible with it.
The class ``TermCriteria`` replaces the old ``CvTermCriteria`` and fully compatible with it.
.._Matx:
Matx
----
@ -419,6 +421,8 @@ The class represents small matrices, which type and size are known at compile ti
cout << sum(Mat(m*m.t())) << endl;
.._Vec:
Vec
---
@ -456,7 +460,7 @@ Template class for short numerical vectors ::
typedef Vec<double, 4> Vec4d;
typedef Vec<double, 6> Vec6d;
``Vec`` is a partial case of ``Matx`` . It is possible to convert ``Vec<T,2>`` to/from ``Point_``,``Vec<T,3>`` to/from ``Point3_`` , and ``Vec<T,4>`` to :ref:`CvScalar` or :ref:`Scalar`. The elements of ``Vec`` are accessed using ``operator[]``. All the expected vector operations are implemented too:
``Vec`` is a partial case of ``Matx`` . It is possible to convert ``Vec<T,2>`` to/from ``Point_``,``Vec<T,3>`` to/from ``Point3_`` , and ``Vec<T,4>`` to ``CvScalar`` or :ref:`Scalar`. The elements of ``Vec`` are accessed using ``operator[]``. All the expected vector operations are implemented too:
*
:math:`\texttt{v1} = \texttt{v2} \pm \texttt{v3}`, :math:`\texttt{v1} = \texttt{v2} * \alpha`, :math:`\texttt{v1} = \alpha * \texttt{v2}` (plus the corresponding augmenting operations; note that these operations apply
@ -466,6 +470,8 @@ Template class for short numerical vectors ::
The class ``Vec`` is commonly used to describe pixel types of multi-channel arrays, see ``Mat_`` description.
.._Scalar:
Scalar\_
--------
@ -491,7 +497,9 @@ Scalar\_
The template class ``Scalar_`` and it's double-precision instantiation ``Scalar`` represent 4-element vector. Being derived from ``Vec<_Tp, 4>`` , they can be used as typical 4-element vectors, but in addition they can be converted to/from ``CvScalar`` . The type ``Scalar`` is widely used in OpenCV for passing pixel values and it is a drop-in replacement for
:ref:`CvScalar` that was used for the same purpose in the earlier versions of OpenCV.
``CvScalar`` that was used for the same purpose in the earlier versions of OpenCV.
.._Range:
Range
-----
@ -530,6 +538,8 @@ The static method ``Range::all()`` returns some special variable that means "the
}
.._Ptr:
Ptr
---
@ -619,6 +629,8 @@ However, if the object is deallocated in a different way, then the specialized m
: The reference increment/decrement operations are implemented as atomic operations, and therefore it is normally safe to use the classes in multi-threaded applications. The same is true for
:ref:`Mat` and other C++ OpenCV classes that operate on the reference counters.
.._Mat:
Mat
---
@ -675,6 +687,7 @@ That is, the data layout in ``Mat`` is fully compatible with ``CvMat``,``IplImag
There are many different ways to create ``Mat`` object. Here are the some popular ones:
*
using ``create(nrows, ncols, type)`` method or
the similar constructor ``Mat(nrows, ncols, type[, fillValue])`` constructor.
A new array of the specified size and specifed type will be allocated. ``type`` has the same meaning as in
@ -695,6 +708,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
or type are different from the specified.
*
similarly to above, you can create a multi-dimensional array:
::
@ -708,6 +722,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
note that it is pass number of dimensions =1 to the ``Mat`` constructor, but the created array will be 2-dimensional, with the number of columns set to 1. That's why ``Mat::dims`` is always >= 2 (can also be 0 when the array is empty)
*
by using a copy constructor or assignment operator, where on the right side it can
be a array or expression, see below. Again, as noted in the introduction,
array assignment is O(1) operation because it only copies the header
@ -715,6 +730,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
(a.k.a. deep) copy of the array when you need it.
*
by constructing a header for a part of another array. It can be a single row, single column,
several rows, several columns, rectangular region in the array (called a minor in algebra) or
a diagonal. Such operations are also O(1), because the new header will reference the same data.
@ -760,6 +776,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
of the extracted sub-matrices.
*
by making a header for user-allocated-data. It can be useful for
#.
@ -787,7 +804,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
..
partial yet very common cases of this "user-allocated data" case are conversions from :ref:`CvMat` and :ref:`IplImage` to ``Mat``. For this purpose there are special constructors taking pointers to ``CvMat`` or ``IplImage`` and the optional flag indicating whether to copy the data or not.
partial yet very common cases of this "user-allocated data" case are conversions from ``CvMat`` and ``IplImage`` to ``Mat``. For this purpose there are special constructors taking pointers to ``CvMat`` or ``IplImage`` and the optional flag indicating whether to copy the data or not.
Backward conversion from ``Mat`` to ``CvMat`` or ``IplImage`` is provided via cast operators ``Mat::operator CvMat() const`` an ``Mat::operator IplImage()``. The operators do *not* copy the data.
@ -802,6 +819,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
..
*
by using MATLAB-style array initializers, ``zeros(), ones(), eye()`` , e.g.:
::
@ -812,6 +830,7 @@ There are many different ways to create ``Mat`` object. Here are the some popula
..
*
by using comma-separated initializer:
::
@ -878,6 +897,8 @@ Finally, there are STL-style iterators that are smart enough to skip gaps betwee
The matrix iterators are random-access iterators, so they can be passed to any STL algorithm, including ``std::sort()`` .
.._MatrixExpressions:
Matrix Expressions
------------------
@ -933,6 +954,8 @@ Below is the formal description of the ``Mat`` methods.
..index:: Mat::Mat
.._Mat::Mat:
Mat::Mat
------------
..c:function:: (1) Mat::Mat()
@ -941,39 +964,39 @@ Mat::Mat
..c:function:: (3) Mat::Mat(Size size, int type)
..c:function:: (4) Mat::Mat(int rows, int cols, int type, const Scalar\& s)
..c:function:: (4) Mat::Mat(int rows, int cols, int type, const Scalar& s)
..c:function:: (5) Mat::Mat(Size size, int type, const Scalar\& s)
..c:function:: (5) Mat::Mat(Size size, int type, const Scalar& s)
..c:function:: (6) Mat::Mat(const Mat\& m)
..c:function:: (6) Mat::Mat(const Mat& m)
..c:function:: (7) Mat::Mat(int rows, int cols, int type, void* data, size_t step=AUTO_STEP)
..c:function:: (8) Mat::Mat(Size size, int type, void* data, size_t step=AUTO_STEP)
..c:function:: (20) Mat::Mat(const Mat\& m, const Range* ranges)
..c:function:: (20) Mat::Mat(const Mat& m, const Range* ranges)
Various array constructors
@ -1013,7 +1036,7 @@ Mat::Mat
.
:param expr:Matrix expression. See :ref:`MatrixExpressions`.
:param expr:Matrix expression. See :ref:`MatrixExpressions`.
These are various constructors that form a matrix. As noticed in the
, often the default constructor is enough, and the proper matrix will be allocated by an OpenCV function. The constructed matrix can further be assigned to another matrix or matrix expression, in which case the old content is dereferenced, or be allocated with
@ -1021,9 +1044,9 @@ These are various constructors that form a matrix. As noticed in the
..index:: Mat::Mat
Mat::Mat
Mat::~Mat
------------
..c:function:: Mat::\textasciitilde Mat()
..cpp:function:: Mat::~Mat()
Matrix destructor
@ -1034,11 +1057,11 @@ The matrix destructor calls
Mat::operator =
-------------------
..c:function:: Mat\& Mat::operator = (const Mat\& m)
..cpp:function:: Mat& Mat::operator = (const Mat& m)
The class is used for implementation of unary, binary and, generally, n-ary element-wise operations on multi-dimensional arrays. Some of the arguments of n-ary function may be continuous arrays, some may be not. It is possible to use conventional
:ref:`MatIterator` 's for each array, but it can be a big overhead to increment all of the iterators after each small operations. That's where ``NAryMatIterator`` can be used. Using it, you can iterate though several matrices simultaneously as long as they have the same geometry (dimensionality and all the dimension sizes are the same). On each iteration ``it.planes[0]``,``it.planes[1]`` , ... will be the slices of the corresponding matrices.
``MatIterator`` 's for each array, but it can be a big overhead to increment all of the iterators after each small operations. That's where ``NAryMatIterator`` can be used. Using it, you can iterate though several matrices simultaneously as long as they have the same geometry (dimensionality and all the dimension sizes are the same). On each iteration ``it.planes[0]``,``it.planes[1]`` , ... will be the slices of the corresponding matrices.
Here is an example of how you can compute a normalized and thresholded 3D color histogram: ::
@ -2057,6 +2153,8 @@ Here is an example of how you can compute a normalized and thresholded 3D color
}
.._SparseMat:
SparseMat
---------
@ -2278,9 +2376,7 @@ The class ``SparseMat`` represents multi-dimensional sparse numerical arrays. Su
..
#.
sparse matrix iterators. Like
:ref:`Mat` iterators and unlike
:ref:`MatND` iterators, the sparse matrix iterators are STL-style, that is, the iteration loop is familiar to C++ users:
sparse matrix iterators. They are similar to ``MatIterator``, but different from :ref:`NAryMatIterator`. That is, the iteration loop is familiar to STL users:
::
@ -2362,7 +2458,6 @@ Template sparse n-dimensional array class derived from
SparseMat_& operator = (const SparseMat& m);
SparseMat_& operator = (const SparseMat_& m);
SparseMat_& operator = (const Mat& m);
SparseMat_& operator = (const MatND& m);
// equivalent to the correspoding parent class methods
OpenCV (Open Source Computer Vision Library: http://opencv.willowgarage.com/wiki/) is open-source BSD-licensed library that includes several hundreds computer vision algorithms. It is very popular in the Computer Vision community. Some people call it “de-facto standard” API. The document aims to specify the stable parts of the library, as well as some abstract interfaces for high-level interfaces, with the final goal to make it an official standard.
OpenCV (Open Source Computer Vision Library: http://opencv.willowgarage.com/wiki/) is open-source BSD-licensed library that includes several hundreds computer vision algorithms. The document describes the so-called OpenCV 2.x API, which is essentially a C++ API, as opposite to the C-based OpenCV 1.x API. The latter is described in opencv1x.pdf.
API specifications in the document use the standard C++ (http://www.open-std.org/jtc1/sc22/wg21/) and the standard C++ library.
The current OpenCV implementation has a modular structure (i.e. the binary package includes several shared or static libraries), where we have:
OpenCV has a modular structure (i.e. package includes several shared or static libraries). The modules are:
* **core** - the compact module defining basic data structures, including the dense multi-dimensional array ``Mat``, and basic functions, used by all other modules.
* **imgproc** - image processing module that includes linear and non-linear image filtering, geometrical image transformations (resize, affine and perspective warping, generic table-based remap), color space conversion, histograms etc.
@ -18,9 +16,7 @@ The current OpenCV implementation has a modular structure (i.e. the binary packa
* **gpu** - GPU-accelerated algorithms from different OpenCV modules.
* ... some other helper modules, such as FLANN and Google test wrappers, Python bindings etc.
Although the alternative implementations of the proposed standard may be structured differently, the proposed standard draft is organized by the functionality groups that reflect the decomposition of the library by modules.
Below are the other main concepts of the OpenCV API, implied everywhere in the document.
The further chapters of the document describe functionality of each module. But first, let's make an overview of the common API concepts, used thoroughly in the library.
@ -57,6 +57,8 @@ The following code is an example used to generate the figure. ::
..index:: setWindowProperty
.._setWindowProperty:
setWindowProperty
---------------------
..c:function:: void setWindowProperty(const string& name, int prop_id, double prop_value)
@ -115,6 +117,8 @@ The function `` getWindowProperty`` return window's properties.
..index:: fontQt
.._fontQt:
fontQt
----------
..c:function:: CvFont fontQt(const string& nameFont, int pointSize = -1, Scalar color = Scalar::all(0), int weight = CV_FONT_NORMAL, int style = CV_STYLE_NORMAL, int spacing = 0)
..c:function:: Mat imread( const string\& filename, int flags=1 )
@ -61,34 +67,19 @@ imread
The function ``imread`` loads an image from the specified file and returns it. If the image can not be read (because of missing file, improper permissions, unsupported or invalid format), the function returns empty matrix ( ``Mat::data==NULL`` ).Currently, the following file formats are supported:
*
Windows bitmaps - ``*.bmp, *.dib`` (always supported)
* Windows bitmaps - ``*.bmp, *.dib`` (always supported)
*
JPEG files - ``*.jpeg, *.jpg, *.jpe`` (see
**Note2**
)
* JPEG files - ``*.jpeg, *.jpg, *.jpe`` (see **Note2**)
*
JPEG 2000 files - ``*.jp2`` (see
**Note2**
)
* JPEG 2000 files - ``*.jp2`` (see **Note2**)
*
Portable Network Graphics - ``*.png`` (see
**Note2**
)
* Portable Network Graphics - ``*.png`` (see **Note2**)
*
Portable image format - ``*.pbm, *.pgm, *.ppm`` (always supported)
* Portable image format - ``*.pbm, *.pgm, *.ppm`` (always supported)
*
Sun rasters - ``*.sr, *.ras`` (always supported)
* Sun rasters - ``*.sr, *.ras`` (always supported)
*
TIFF files - ``*.tiff, *.tif`` (see
**Note2**
)
* TIFF files - ``*.tiff, *.tif`` (see **Note2**)
**Note1**
: The function determines type of the image by the content, not by the file extension.
@ -100,6 +91,8 @@ On Linux, BSD flavors and other Unix-like open-source operating systems OpenCV l
@ -84,9 +88,11 @@ The function ``imshow`` displays the image in the specified window. If the windo
..index:: namedWindow
.._namedWindow:
namedWindow
---------------
..c:function:: void namedWindow( const string\& winname, int flags )
..c:function:: void namedWindow( const string& winname, int flags )
Creates a window.
@ -104,27 +110,29 @@ qt-specific details:
* **flags** Flags of the window. Currently the supported flags are:
* **CV_WINDOW_NORMAL or CV_WINDOW_AUTOSIZE:** ``CV_WINDOW_NORMAL`` let the user resize the window, whereas ``CV_WINDOW_AUTOSIZE`` adjusts automatically the window's size to fit the displayed image (see :ref:`ShowImage` ), and the user can not change the window size manually.
* **CV_WINDOW_NORMAL or CV_WINDOW_AUTOSIZE:** ``CV_WINDOW_NORMAL`` let the user resize the window, whereas ``CV_WINDOW_AUTOSIZE`` adjusts automatically the window's size to fit the displayed image (see :ref:`imshow` ), and the user can not change the window size manually.
* **CV_WINDOW_FREERATIO or CV_WINDOW_KEEPRATIO:** ``CV_WINDOW_FREERATIO`` adjust the image without respect the its ration, whereas ``CV_WINDOW_KEEPRATIO`` keep the image's ratio.
* **CV_GUI_NORMAL or CV_GUI_EXPANDED:** ``CV_GUI_NORMAL`` is the old way to draw the window without statusbar and toolbar, whereas ``CV_GUI_EXPANDED`` is the new enhance GUI.
This parameter is optional. The default flags set for a new window are ``CV_WINDOW_AUTOSIZE`` , ``CV_WINDOW_KEEPRATIO`` , and ``CV_GUI_EXPANDED`` .
This parameter is optional. The default flags set for a new window are ``CV_WINDOW_AUTOSIZE`` , ``CV_WINDOW_KEEPRATIO`` , and ``CV_GUI_EXPANDED`` .
However, if you want to modify the flags, you can combine them using OR operator, ie:
Applies a generic geometrical transformation to an image.
:param src:Source image
:param dst:Destination image. It will have the same size as ``map1`` and the same type as ``src``
:param map1:The first map of either ``(x,y)`` points or just ``x`` values having type ``CV_16SC2`` , ``CV_32FC1`` or ``CV_32FC2`` . See :func:`convertMaps` for converting floating point representation to fixed-point for speed.
:param map1:The first map of either ``(x,y)`` points or just ``x`` values having type ``CV_16SC2`` , ``CV_32FC1`` or ``CV_32FC2`` . See :func:`convertMaps` for converting floating point representation to fixed-point for speed.
:param map2:The second map of ``y`` values having type ``CV_16UC1`` , ``CV_32FC1`` or none (empty map if map1 is ``(x,y)`` points), respectively
:param map2:The second map of ``y`` values having type ``CV_16UC1`` , ``CV_32FC1`` or none (empty map if map1 is ``(x,y)`` points), respectively
:param interpolation:The interpolation method, see :func:`resize` . The method ``INTER_AREA`` is not supported by this function
@ -252,9 +275,12 @@ This function can not operate in-place.
@ -7,7 +9,7 @@ A common machine learning task is supervised learning. In supervised learning, t
:math:`y` . Predicting the qualitative output is called classification, while predicting the quantitative output is called regression.
Boosting is a powerful learning concept, which provide a solution to the supervised classification learning task. It combines the performance of many "weak" classifiers to produce a powerful 'committee'
:ref:`HTF01` . A weak classifier is only required to be better than chance, and thus can be very simple and computationally inexpensive. Many of them smartly combined, however, results in a strong classifier, which often outperforms most 'monolithic' strong classifiers such as SVMs and Neural Networks.
:ref:`[HTF01] <HTF01>` . A weak classifier is only required to be better than chance, and thus can be very simple and computationally inexpensive. Many of them smartly combined, however, results in a strong classifier, which often outperforms most 'monolithic' strong classifiers such as SVMs and Neural Networks.
Decision trees are the most popular weak classifiers used in boosting schemes. Often the simplest decision trees with only a single split node per tree (called stumps) are sufficient.
@ -20,7 +22,7 @@ The boosted model is based on
:math:`K` -component vector. Each component encodes a feature relevant for the learning task at hand. The desired two-class output is encoded as -1 and +1.
Different variants of boosting are known such as Discrete Adaboost, Real AdaBoost, LogitBoost, and Gentle AdaBoost
:ref:`FHT98` . All of them are very similar in their overall structure. Therefore, we will look only at the standard two-class Discrete AdaBoost algorithm as shown in the box below. Each sample is initially assigned the same weight (step 2). Next a weak classifier
:ref:`[FHT98] <FHT98>` . All of them are very similar in their overall structure. Therefore, we will look only at the standard two-class Discrete AdaBoost algorithm as shown in the box below. Each sample is initially assigned the same weight (step 2). Next a weak classifier
:math:`f_{m(x)}` is trained on the weighted training data (step 3a). Its weighted training error and scaling factor
:math:`c_m` is computed (step 3b). The weights are increased for training samples, which have been misclassified (step 3c). All weights are then normalized, and the process of finding the next weak classifier continues for another
:math:`M` -1 times. The final classifier
@ -65,15 +67,20 @@ As well as the classical boosting methods, the current implementation supports 2
:math:`>` 2 classes there is the
**AdaBoost.MH**
algorithm, described in
:ref:`FHT98` , that reduces the problem to the 2-class problem, yet with a much larger training set.
:ref:`[FHT98] <FHT98>` , that reduces the problem to the 2-class problem, yet with a much larger training set.
In order to reduce computation time for boosted models without substantially losing accuracy, the influence trimming technique may be employed. As the training algorithm proceeds and the number of trees in the ensemble is increased, a larger number of the training samples are classified correctly and with increasing confidence, thereby those samples receive smaller weights on the subsequent iterations. Examples with very low relative weight have small impact on training of the weak classifier. Thus such examples may be excluded during the weak classifier training without having much effect on the induced classifier. This process is controlled with the weight_trim_rate parameter. Only examples with the summary fraction weight_trim_rate of the total weight mass are used in the weak classifier training. Note that the weights for
**all**
training examples are recomputed at each training iteration. Examples deleted at a particular iteration may be used again for learning some of the weak classifiers further
:ref:`FHT98` .
:ref:`[FHT98] <FHT98>` .
.._HTF01:
[HTF01] Hastie, T., Tibshirani, R., Friedman, J. H. The Elements of Statistical Learning: Data Mining, Inference, and Prediction. Springer Series in Statistics. 2001.**
.._FHT98:
**[HTF01] Hastie, T., Tibshirani, R., Friedman, J. H. The Elements of Statistical Learning: Data Mining, Inference, and Prediction. Springer Series in Statistics. 2001.**
**[FHT98] Friedman, J. H., Hastie, T. and Tibshirani, R. Additive Logistic Regression: a Statistical View of Boosting. Technical Report, Dept. of Statistics, Stanford University, 1998.**
[FHT98] Friedman, J. H., Hastie, T. and Tibshirani, R. Additive Logistic Regression: a Statistical View of Boosting. Technical Report, Dept. of Statistics, Stanford University, 1998.**
@ -57,7 +57,7 @@ Alternatively, the algorithm may start with the M-step when the initial values f
:math:`p_{i,k}` can be provided. Another alternative when
:math:`p_{i,k}` are unknown, is to use a simpler clustering algorithm to pre-cluster the input samples and thus obtain initial
:math:`p_{i,k}` . Often (and in ML) the
:ref:`KMeans2` algorithm is used for that purpose.
:ref:`kmeans` algorithm is used for that purpose.
One of the main that EM algorithm should deal with is the large number
of parameters to estimate. The majority of the parameters sits in
@ -197,12 +197,12 @@ CvEM::train
Estimates the Gaussian mixture parameters from the sample set.
Unlike many of the ML models, EM is an unsupervised learning algorithm and it does not take responses (class labels or the function values) on input. Instead, it computes the
:ref:`MLE` of the Gaussian mixture parameters from the input sample set, stores all the parameters inside the structure:
*Maximum Likelihood Estimate* of the Gaussian mixture parameters from the input sample set, stores all the parameters inside the structure:
:math:`p_{i,k}` in ``probs``,:math:`a_k` in ``means``:math:`S_k` in ``covs[k]``,:math:`\pi_k` in ``weights`` and optionally computes the output "class label" for each sample:
:math:`\texttt{labels}_i=\texttt{arg max}_k(p_{i,k}), i=1..N` (i.e. indices of the most-probable mixture for each sample).
The trained model can be used further for prediction, just like any other classifier. The model trained is similar to the
:ref:`Bayes classifier`.
:ref:`Bayes classifier`.
Example: Clustering random samples of multi-Gaussian distribution using EM ::
This is a simple classification model assuming that feature vectors from each class are normally distributed (though, not necessarily independently distributed), so the whole data distribution function is assumed to be a Gaussian mixture, one component per class. Using the training data the algorithm estimates mean vectors and covariance matrices for every class, and then it uses them for prediction.
**[Fukunaga90] K. Fukunaga. Introduction to Statistical Pattern Recognition. second ed., New York: Academic Press, 1990.**