further docs cleanup
authorVadim Pisarevsky <no@email>
Tue, 8 Mar 2011 22:22:24 +0000 (22:22 +0000)
committerVadim Pisarevsky <no@email>
Tue, 8 Mar 2011 22:22:24 +0000 (22:22 +0000)
23 files changed:
modules/calib3d/doc/camera_calibration_and_3d_reconstruction.rst
modules/core/doc/basic_structures.rst
modules/core/doc/clustering.rst
modules/core/doc/dynamic_structures.rst [deleted file]
modules/core/doc/intro.rst
modules/core/doc/operations_on_arrays.rst
modules/gpu/doc/data_structures.rst
modules/gpu/doc/matrix_reductions.rst
modules/gpu/doc/per_element_operations..rst [deleted file]
modules/gpu/doc/per_element_operations.rst
modules/highgui/doc/qt_new_functions.rst
modules/highgui/doc/reading_and_writing_images_and_video.rst
modules/highgui/doc/user_interface.rst
modules/imgproc/doc/feature_detection.rst
modules/imgproc/doc/geometric_transformations.rst
modules/imgproc/doc/histograms.rst
modules/imgproc/doc/miscellaneous_transformations.rst
modules/imgproc/doc/planar_subdivisions.rst [deleted file]
modules/ml/doc/boosting.rst
modules/ml/doc/expectation_maximization.rst
modules/ml/doc/neural_networks.rst
modules/ml/doc/normal_bayes_classifier.rst
modules/ml/doc/random_trees.rst

index 3a7a88f..47c5881 100644 (file)
@@ -102,9 +102,12 @@ The functions below use the above model to
 
 .. index:: calibrateCamera
 
-cv::calibrateCamera
--------------------
-.. c:function:: double calibrateCamera( const vector<vector<Point3f> >& objectPoints, const vector<vector<Point2f> >& imagePoints,                      Size imageSize, Mat& cameraMatrix, Mat& distCoeffs, vector<Mat>& rvecs, vector<Mat>& tvecs, int flags=0 )
+.. _calibrateCamera:
+
+calibrateCamera
+---------------
+
+.. c:function:: double calibrateCamera( const vector<vector<Point3f> >& objectPoints, const vector<vector<Point2f> >& imagePoints, Size imageSize, Mat& cameraMatrix, Mat& distCoeffs, vector<Mat>& rvecs, vector<Mat>& tvecs, int flags=0 )
 
     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
 rig (see
-:ref:`FindChessboardCorners` ). Currently, initialization
+:ref:`findChessboardCorners` ). Currently, initialization
 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
 :ref:`FindChessboardCorners` .
 
 See also:
-:ref:`FindChessboardCorners`,:ref:`FindExtrinsicCameraParams2`,:func:`initCameraMatrix2D`,:ref:`StereoCalibrate`,:ref:`Undistort2`
+:ref:`FindChessboardCorners`,:ref:`solvePnP`,:func:`initCameraMatrix2D`,:ref:`stereoCalibrate`,:ref:`undistort`
+
 .. index:: calibrationMatrixValues
 
-cv::calibrationMatrixValues
----------------------------
-.. c:function:: void calibrationMatrixValues( const Mat& cameraMatrix,                              Size imageSize,                              double apertureWidth,                              double apertureHeight,                              double& fovx,                              double& fovy,                              double& focalLength,                              Point2d& principalPoint,                              double& aspectRatio )
+.. _calibrationMatrixValues:
+
+calibrationMatrixValues
+-----------------------
+.. c:function:: void calibrationMatrixValues( const Mat& cameraMatrix, Size imageSize, double apertureWidth, double apertureHeight, double& fovx, double& fovy, double& focalLength, Point2d& principalPoint, double& aspectRatio )
 
     Computes some useful camera characteristics from the camera matrix
 
     :param cameraMatrix: The input camera matrix that can be estimated by  :func:`calibrateCamera`  or  :func:`stereoCalibrate`
+    
     :param imageSize: The input image size in pixels
 
     :param apertureWidth: Physical width of the sensor
@@ -202,11 +208,13 @@ The function computes various useful camera characteristics from the previously
 
 .. index:: composeRT
 
-cv::composeRT
+.. _composeRT:
+
+composeRT
 -------------
 .. c:function:: void composeRT( const Mat& rvec1, const Mat& tvec1, const Mat& rvec2, const Mat& tvec2, Mat& rvec3, Mat& tvec3 )
 
-.. c:function:: void composeRT( const Mat& rvec1, const Mat& tvec1, const Mat& rvec2, const Mat& tvec2, Mat& rvec3, Mat& tvec3,                Mat& dr3dr1, Mat& dr3dt1, Mat& dr3dr2, Mat& dr3dt2, Mat& dt3dr1, Mat& dt3dt1, Mat& dt3dr2, Mat& dt3dt2 )
+.. c:function:: void composeRT( const Mat& rvec1, const Mat& tvec1, const Mat& rvec2, const Mat& tvec2, Mat& rvec3, Mat& tvec3, Mat& dr3dr1, Mat& dr3dt1, Mat& dr3dr2, Mat& dr3dt2, Mat& dt3dr1, Mat& dt3dt1, Mat& dt3dr2, Mat& dt3dt2 )
 
     Combines two rotation-and-shift transformations
 
@@ -238,9 +246,11 @@ The functions are used inside :func:`stereoCalibrate` but can also be used in yo
 
 .. index:: computeCorrespondEpilines
 
-cv::computeCorrespondEpilines
+.. _computeCorrespondEpilines:
+
+computeCorrespondEpilines
 -----------------------------
-.. c:function:: void computeCorrespondEpilines( const Mat& points, int whichImage, const Mat& F,                                vector<Vec3f>& lines )
+.. c:function:: void computeCorrespondEpilines( const Mat& points, int whichImage, const Mat& F, vector<Vec3f>& lines )
 
     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
 
 .. index:: convertPointsHomogeneous
 
-cv::convertPointsHomogeneous
-----------------------------
+.. _convertPointsHomogeneous:
+
+convertPointsHomogeneous
+------------------------
+
 .. c:function:: void convertPointsHomogeneous( const Mat& src, vector<Point3f>& dst )
 
 .. c:function:: void convertPointsHomogeneous( const Mat& src, vector<Point2f>& dst )
@@ -300,11 +313,13 @@ If the output array dimensionality is larger, an extra 1 is appended to each poi
 
 .. index:: decomposeProjectionMatrix
 
-cv::decomposeProjectionMatrix
+.. _decomposeProjectionMatrix:
+
+decomposeProjectionMatrix
 -----------------------------
-.. c:function:: void decomposeProjectionMatrix( const Mat& projMatrix,                                Mat& cameraMatrix,                                Mat& rotMatrix, Mat& transVect )
+.. c:function:: void decomposeProjectionMatrix( const Mat& projMatrix, Mat& cameraMatrix, Mat& rotMatrix, Mat& transVect )
 
-.. c:function:: void decomposeProjectionMatrix( const Mat& projMatrix,                                 Mat& cameraMatrix,                                Mat& rotMatrix, Mat& transVect,                                Mat& rotMatrixX, Mat& rotMatrixY,                                Mat& rotMatrixZ, Vec3d& eulerAngles )
+.. c:function:: void decomposeProjectionMatrix( const Mat& projMatrix, Mat& cameraMatrix, Mat& rotMatrix, Mat& transVect, Mat& rotMatrixX, Mat& rotMatrixY, Mat& rotMatrixZ, Vec3d& eulerAngles )
 
     Decomposes the projection matrix into a rotation matrix and a camera matrix.
 
@@ -333,15 +348,17 @@ The function is based on
 
 .. index:: drawChessboardCorners
 
-cv::drawChessboardCorners
+.. _drawChessboardCorners:
+
+drawChessboardCorners
 -------------------------
-.. c:function:: void drawChessboardCorners( Mat& image, Size patternSize,                            const Mat& corners,                            bool patternWasFound )
+.. c:function:: void drawChessboardCorners( Mat& image, Size patternSize, const Mat& corners, bool patternWasFound )
 
     Renders the detected chessboard corners.
 
     :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
 
 .. index:: findChessboardCorners
 
-cv::findChessboardCorners
+.. _findChessboardCorners:
+
+findChessboardCorners
 -------------------------
-.. c:function:: bool findChessboardCorners( const Mat& image, Size patternSize,                            vector<Point2f>& corners,                            int flags=CV_CALIB_CB_ADAPTIVE_THRESH+                                 CV_CALIB_CB_NORMALIZE_IMAGE )
+.. c:function:: bool findChessboardCorners( const Mat& image, Size patternSize, vector<Point2f>& corners, int flags=CV_CALIB_CB_ADAPTIVE_THRESH+CV_CALIB_CB_NORMALIZE_IMAGE )
 
     Finds the positions of the internal corners of the chessboard.
 
     :param image: Source chessboard view; it must be an 8-bit grayscale or color image
 
     :param patternSize: The number of inner corners per chessboard row and column
-        ( patternSize = cvSize(points _ per _ row,points _ per _ colum) = cvSize(columns,rows) )
+        ( patternSize = cvSize(points_per_row,points_per_colum) = cvSize(columns,rows) )
 
     :param corners: The output array of corners detected
 
@@ -386,7 +405,7 @@ squares and 7 x 7 internal corners, that is, points, where the black
 squares touch each other. The coordinates detected are approximate,
 and to determine their position more accurately, the user may use
 the function
-:ref:`FindCornerSubPix` .
+:ref:`cornerSubPix`.
 
 Sample usage of detecting and drawing chessboard corners: ::
 
@@ -411,9 +430,11 @@ the function requires some white space (like a square-thick border, the wider th
 
 .. index:: findCirclesGrid
 
-cv::findCirclesGrid
+.. _findCirclesGrid:
+
+findCirclesGrid
 -------------------
-.. c:function:: bool findCirclesGrid( const Mat& image, Size patternSize,                            vector<Point2f>& centers,                            int flags=CALIB_CB_SYMMETRIC_GRID )
+.. c:function:: bool findCirclesGrid( const Mat& image, Size patternSize, vector<Point2f>& centers, int flags=CALIB_CB_SYMMETRIC_GRID )
 
     Finds the centers of the cirlces' grid.
 
@@ -421,8 +442,7 @@ cv::findCirclesGrid
         image
 
     :param patternSize: The number of circles per grid row and column
-        ( patternSize = Size( points _ per _ row, points _ per _ colum ) =
-        Size( columns, rows ) )
+        ( patternSize = Size(points_per_row, points_per_colum) )
 
     :param centers: The output array of centers detected
 
@@ -455,9 +475,11 @@ the function requires some white space (like a square-thick border, the wider th
 
 .. index:: solvePnP
 
-cv::solvePnP
+.. _solvePnP:
+
+solvePnP
 ------------
-.. c:function:: void solvePnP( const Mat& objectPoints,               const Mat& imagePoints,               const Mat& cameraMatrix,               const Mat& distCoeffs,               Mat& rvec, Mat& tvec,               bool useExtrinsicGuess=false )
+.. c:function:: void solvePnP( const Mat& objectPoints, const Mat& imagePoints, const Mat& cameraMatrix, const Mat& distCoeffs, Mat& rvec, Mat& tvec, bool useExtrinsicGuess=false )
 
     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
-:ref:`ProjectPoints2` ) ``objectPoints`` .
+:ref:`projectPoints` ) ``objectPoints`` .
 
 .. index:: solvePnPRansac
 
-cv::solvePnPRansac
-------------
-.. c:function:: void solvePnPRansac( const Mat& objectPoints,               const Mat& imagePoints,               const Mat& cameraMatrix,               const Mat& distCoeffs,               Mat& rvec,               Mat& tvec,               bool useExtrinsicGuess=false,               int iterationsCount = 100,               float reprojectionError = 8.0,               int minInliersCount = 100,               vector<int>* inliers = NULL  )
+.. _solvePnPRansac:
+
+solvePnPRansac
+------------------
+
+.. c:function:: void solvePnPRansac( const Mat& objectPoints, const Mat& imagePoints, const Mat& cameraMatrix, const Mat& distCoeffs, Mat& rvec, Mat& tvec, bool useExtrinsicGuess=false, int iterationsCount = 100, float reprojectionError = 8.0, int minInliersCount = 100, vector<int>* inliers = NULL  )
 
     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.
 
@@ -653,9 +683,13 @@ See also:
 :ref:`GetAffineTransform`,:ref:`GetPerspectiveTransform`,:ref:`EstimateRigidMotion`,:ref:`WarpPerspective`,:ref:`PerspectiveTransform`
 .. index:: getDefaultNewCameraMatrix
 
-cv::getDefaultNewCameraMatrix
+.. index:: getDefaultNewCameraMatrix
+
+.. _getDefaultNewCameraMatrix:
+
+getDefaultNewCameraMatrix
 -----------------------------
-.. c:function:: Mat getDefaultNewCameraMatrix(                               const Mat& cameraMatrix,                               Size imgSize=Size(),                               bool centerPrincipalPoint=false )
+.. c:function:: Mat getDefaultNewCameraMatrix(                               const Mat& cameraMatrix, Size imgSize=Size(), bool centerPrincipalPoint=false )
 
     Returns the default new camera matrix
 
@@ -683,7 +717,9 @@ By default, the undistortion functions in OpenCV (see ``initUndistortRectifyMap`
 
 .. index:: getOptimalNewCameraMatrix
 
-cv::getOptimalNewCameraMatrix
+.. _getOptimalNewCameraMatrix:
+
+getOptimalNewCameraMatrix
 -----------------------------
 .. c:function:: Mat getOptimalNewCameraMatrix( const Mat& cameraMatrix, const Mat& distCoeffs, Size imageSize, double alpha, Size newImageSize=Size(), Rect* validPixROI=0)
 
@@ -709,7 +745,9 @@ the optimal new camera matrix based on the free scaling parameter. By varying  t
 
 .. index:: initCameraMatrix2D
 
-cv::initCameraMatrix2D
+.. _initCameraMatrix2D:
+
+initCameraMatrix2D
 ----------------------
 .. c:function:: Mat initCameraMatrix2D( const vector<vector<Point3f> >& objectPoints, const vector<vector<Point2f> >& imagePoints, Size imageSize, double aspectRatio=1.)
 
@@ -728,10 +766,12 @@ Currently, the function only supports planar calibration patterns, i.e. patterns
 
 .. index:: initUndistortRectifyMap
 
-cv::initUndistortRectifyMap
+.. _initUndistortRectifyMap:
+
+initUndistortRectifyMap
 ---------------------------
 
-.. c:function:: void initUndistortRectifyMap( const Mat& cameraMatrix,                           const Mat& distCoeffs, const Mat& R,                           const Mat& newCameraMatrix,                           Size size, int m1type,                           Mat& map1, Mat& map2 )
+.. c:function:: void initUndistortRectifyMap( const Mat& cameraMatrix, const Mat& distCoeffs, const Mat& R, const Mat& newCameraMatrix, Size size, int m1type, Mat& map1, Mat& map2 )
 
     Computes the undistortion and rectification transformation map.
 
@@ -782,7 +822,9 @@ where the ``cameraMatrix`` can be chosen arbitrarily.
 
 .. index:: matMulDeriv
 
-cv::matMulDeriv
+.. _matMulDeriv:
+
+matMulDeriv
 ---------------
 
 .. c:function:: void matMulDeriv( const Mat& A, const Mat& B, Mat& dABdA, Mat& dABdB )
@@ -803,18 +845,20 @@ The function computes the partial derivatives of the elements of the matrix prod
 
 .. index:: projectPoints
 
-cv::projectPoints
+.. _projectPoints:
+
+projectPoints
 -----------------
 
-.. c:function:: void projectPoints( const Mat& objectPoints, const Mat& rvec, const Mat& tvec, const Mat& cameraMatrix,                    const Mat& distCoeffs, vector<Point2f>& imagePoints )
+.. c:function:: void projectPoints( const Mat& objectPoints, const Mat& rvec, const Mat& tvec, const Mat& cameraMatrix, const Mat& distCoeffs, vector<Point2f>& imagePoints )
 
-.. c:function:: void projectPoints( const Mat& objectPoints, const Mat& rvec, const Mat& tvec, const Mat& cameraMatrix,                    const Mat& distCoeffs, vector<Point2f>& imagePoints, Mat& dpdrot, Mat& dpdt, Mat& dpdf, Mat& dpdc, Mat& dpddist, double aspectRatio=0 )
+.. c:function:: void projectPoints( const Mat& objectPoints, const Mat& rvec, const Mat& tvec, const Mat& cameraMatrix, const Mat& distCoeffs, vector<Point2f>& imagePoints, Mat& dpdrot, Mat& dpdt, Mat& dpdf, Mat& dpdc, Mat& dpddist, double aspectRatio=0 )
 
     Project 3D points on to an image plane.
 
     :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
 
 .. index:: reprojectImageTo3D
 
-cv::reprojectImageTo3D
+.. _reprojectImageTo3D:
+
+reprojectImageTo3D
 ----------------------
 
-.. c:function:: void reprojectImageTo3D( const Mat& disparity,                         Mat& _3dImage, const Mat& Q,                         bool handleMissingValues=false )
+.. c:function:: void reprojectImageTo3D( const Mat& disparity, Mat& _3dImage, const Mat& Q, bool handleMissingValues=false )
 
     Reprojects disparity image to 3D space.
 
@@ -864,7 +909,7 @@ cv::reprojectImageTo3D
 
     :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
 
 .. index:: RQDecomp3x3
 
-cv::RQDecomp3x3
+.. _RQDecomp3x3:
+
+RQDecomp3x3
 ---------------
 .. c:function:: void RQDecomp3x3( const Mat& M, Mat& R, Mat& Q )
 
-.. c:function:: Vec3d RQDecomp3x3( const Mat& M, Mat& R, Mat& Q,                   Mat& Qx, Mat& Qy, Mat& Qz )
+.. c:function:: Vec3d RQDecomp3x3( const Mat& M, Mat& R, Mat& Q, Mat& Qx, Mat& Qy, Mat& Qz )
 
     Computes the 'RQ' decomposition of 3x3 matrices.
 
@@ -908,7 +955,9 @@ that could be used in OpenGL.
 
 .. index:: Rodrigues
 
-cv::Rodrigues
+.. _Rodrigues:
+
+Rodrigues
 -------------
 .. c:function:: void Rodrigues(const Mat& src, Mat& dst)
 
@@ -935,8 +984,7 @@ Inverse transformation can also be done easily, since
 A rotation vector is a convenient and most-compact representation of a rotation matrix
 (since any rotation matrix has just 3 degrees of freedom). The representation is
 used in the global 3D geometry optimization procedures like
-:ref:`CalibrateCamera2`,:ref:`StereoCalibrate` or
-:ref:`FindExtrinsicCameraParams2` .
+:ref:`calibrateCamera`,:ref:`stereoCalibrate` or :ref:`solvePnP` .
 
 .. index:: StereoBM
 
@@ -972,7 +1020,30 @@ The class for computing stereo correspondence using block matching algorithm. ::
     };
 
 The class is a C++ wrapper for and the associated functions. In particular, ``StereoBM::operator ()`` is the wrapper for
-:ref:`FindStereoCorrespondceBM`. See the respective descriptions.
+:ref:`StereoBM::operator ()`. See the respective descriptions.
+
+
+.. index:: StereoBM::operator ()
+
+.. _StereoBM::operator ():
+
+StereoBM::operator ()
+-----------------------
+
+.. c:function:: void StereoBM::operator()(const Mat& left, const Mat& right, Mat& disp, , int disptype=CV_16S )
+
+    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
 
 .. index:: StereoSGBM::operator ()
 
-cv::StereoSGBM::operator ()
----------------------------
+.. _StereoSGBM::operator ():
+
+StereoSGBM::operator ()
+-----------------------
 
-.. c:function:: void SGBM::operator()(const Mat& left, const Mat& right, Mat& disp)
+.. c:function:: void StereoSGBM::operator()(const Mat& left, const Mat& right, Mat& disp)
 
     Computes disparity using SGBM algorithm for a rectified stereo pair
 
@@ -1082,9 +1147,11 @@ The method executes SGBM algorithm on a rectified stereo pair. See ``stereo_matc
 
 .. index:: stereoCalibrate
 
-cv::stereoCalibrate
+.. _stereoCalibrate:
+
+stereoCalibrate
 -------------------
-.. c:function:: double stereoCalibrate( const vector<vector<Point3f> >& objectPoints, const vector<vector<Point2f> >& imagePoints1,                      const vector<vector<Point2f> >& imagePoints2, Mat& cameraMatrix1, Mat& distCoeffs1, Mat& cameraMatrix2, Mat& distCoeffs2,                      Size imageSize, Mat& R, Mat& T, Mat& E, Mat& F, TermCriteria term_crit = TermCriteria(TermCriteria::COUNT+                         TermCriteria::EPS, 30, 1e-6), int flags=CALIB_FIX_INTRINSIC )
+.. c:function:: double stereoCalibrate( const vector<vector<Point3f> >& objectPoints, const vector<vector<Point2f> >& imagePoints1, const vector<vector<Point2f> >& imagePoints2, Mat& cameraMatrix1, Mat& distCoeffs1, Mat& cameraMatrix2, Mat& distCoeffs2, Size imageSize, Mat& R, Mat& T, Mat& E, Mat& F, TermCriteria term_crit = TermCriteria(TermCriteria::COUNT+                         TermCriteria::EPS, 30, 1e-6), int flags=CALIB_FIX_INTRINSIC )
 
     Calibrates stereo camera.
 
@@ -1094,7 +1161,7 @@ cv::stereoCalibrate
 
     :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.
 
 .. index:: stereoRectify
 
-cv::stereoRectify
+.. _stereoRectify:
+
+stereoRectify
 -----------------
-.. c:function:: void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1, const Mat& cameraMatrix2, const Mat& distCoeffs2,                    Size imageSize, const Mat& R, const Mat& T, Mat& R1, Mat& R2, Mat& P1, Mat& P2, Mat& Q, int flags=CALIB_ZERO_DISPARITY )
+.. c:function:: void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1, const Mat& cameraMatrix2, const Mat& distCoeffs2, Size imageSize, const Mat& R, const Mat& T, Mat& R1, Mat& R2, Mat& P1, Mat& P2, Mat& Q, int flags=CALIB_ZERO_DISPARITY )
 
-.. c:function:: void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1, const Mat& cameraMatrix2, const Mat& distCoeffs2,                    Size imageSize, const Mat& R, const Mat& T, Mat& R1, Mat& R2, Mat& P1, Mat& P2, Mat& Q, double alpha, Size newImageSize=Size(),                    Rect* roi1=0, Rect* roi2=0, int flags=CALIB_ZERO_DISPARITY )
+.. c:function:: void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1, const Mat& cameraMatrix2, const Mat& distCoeffs2, Size imageSize, const Mat& R, const Mat& T, Mat& R1, Mat& R2, Mat& P1, Mat& P2, Mat& Q, double alpha, Size newImageSize=Size(), Rect* roi1=0, Rect* roi2=0, int flags=CALIB_ZERO_DISPARITY )
 
     Computes rectification transforms for each head of a calibrated stereo camera.
 
@@ -1243,15 +1310,17 @@ Below is the screenshot from ``stereo_calib.cpp`` sample. Some red horizontal li
 
 .. index:: stereoRectifyUncalibrated
 
-cv::stereoRectifyUncalibrated
+.. _stereoRectifyUncalibrated:
+
+stereoRectifyUncalibrated
 -----------------------------
-.. c:function:: bool stereoRectifyUncalibrated( const Mat& points1, const Mat& points2, const Mat& F, Size imgSize,                                Mat& H1, Mat& H2, double threshold=5 )
+.. c:function:: bool stereoRectifyUncalibrated( const Mat& points1, const Mat& points2, const Mat& F, Size imgSize, Mat& H1, Mat& H2, double threshold=5 )
 
     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
+:ref:`undistortPoints` .
 
 .. index:: undistort
 
-cv::undistort
+.. _undistort:
+
+undistort
 -------------
-.. c:function:: void undistort( const Mat& src, Mat& dst, const Mat& cameraMatrix,                const Mat& distCoeffs, const Mat& newCameraMatrix=Mat() )
+.. c:function:: void undistort( const Mat& src, Mat& dst, const Mat& cameraMatrix, const Mat& distCoeffs, const Mat& newCameraMatrix=Mat() )
 
     Transforms an image to compensate for lens distortion.
 
@@ -1300,15 +1371,17 @@ The particular subset of the source image that will be visible in the corrected
 :ref:`GetOptimalNewCameraMatrix` to compute the appropriate ``newCameraMatrix`` , depending on your requirements.
 
 The camera matrix and the distortion parameters can be determined using
-:ref:`CalibrateCamera2` . If the resolution of images is different from the used at the calibration stage,
+:ref:`calibrateCamera` . If the resolution of images is different from the used at the calibration stage,
 :math:`f_x, f_y, c_x` and
 :math:`c_y` need to be scaled accordingly, while the distortion coefficients remain the same.
 
 .. index:: undistortPoints
 
-cv::undistortPoints
+.. _undistortPoints:
+
+undistortPoints
 -------------------
-.. c:function:: void undistortPoints( const Mat& src, vector<Point2f>& dst, const Mat& cameraMatrix, const Mat& distCoeffs,                      const Mat& R=Mat(), const Mat& P=Mat())
+.. c:function:: void undistortPoints( const Mat& src, vector<Point2f>& dst, const Mat& cameraMatrix, const Mat& distCoeffs, const Mat& R=Mat(), const Mat& P=Mat())
 
 .. c:function:: void undistortPoints( const Mat& src, Mat& dst, const Mat& cameraMatrix, const Mat& distCoeffs, const Mat& R=Mat(), const Mat& P=Mat())
 
@@ -1327,9 +1400,9 @@ cv::undistortPoints
     :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
     // camera_matrix=[fx 0 cx; 0 fy cy; 0 0 1]
index 603e0ff..0c4ca2c 100644 (file)
@@ -3,6 +3,8 @@ Basic Structures
 
 .. highlight:: cpp
 
+.. _DataType:
+
 DataType
 --------
 
@@ -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:: (9) Mat::Mat(const Mat\& m, const Range\& rowRange, const Range\& colRange)
+.. c:function:: (9) Mat::Mat(const Mat& m, const Range& rowRange, const Range& colRange)
 
-.. c:function:: (10) Mat::Mat(const Mat\& m, const Rect\& roi)
+.. c:function:: (10) Mat::Mat(const Mat& m, const Rect& roi)
 
 .. c:function:: (11) Mat::Mat(const CvMat* m, bool copyData=false)
 
 .. c:function:: (12) Mat::Mat(const IplImage* img, bool copyData=false)
 
-.. c:function:: (13) template<typename T, int n> explicit Mat::Mat(const Vec<T, n>\& vec, bool copyData=true)
+.. c:function:: (13) template<typename T, int n> explicit Mat::Mat(const Vec<T, n>& vec, bool copyData=true)
 
-.. c:function:: (14) template<typename T, int m, int n> explicit Mat::Mat(const Matx<T, m, n>\& vec, bool copyData=true)
+.. c:function:: (14) template<typename T, int m, int n> explicit Mat::Mat(const Matx<T, m, n>& vec, bool copyData=true)
 
-.. c:function:: (15) template<typename T> explicit Mat::Mat(const vector<T>\& vec, bool copyData=false)
+.. c:function:: (15) template<typename T> explicit Mat::Mat(const vector<T>& vec, bool copyData=false)
 
-.. c:function:: (16) Mat::Mat(const MatExpr\& expr)
+.. c:function:: (16) Mat::Mat(const MatExpr& expr)
 
 .. c:function:: (17) Mat::Mat(int ndims, const int* sizes, int type)
 
-.. c:function:: (18) Mat::Mat(int ndims, const int* sizes, int type, const Scalar\& s)
+.. c:function:: (18) Mat::Mat(int ndims, const int* sizes, int type, const Scalar& s)
 
 .. c:function:: (19) Mat::Mat(int ndims, const int* sizes, int type, void* data, const size_t* steps=0)
 
-.. 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:`Matrix Expressions` .
+    :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)
 
-.. c:function:: Mat\& Mat::operator = (const MatExpr_Base\& expr)
+.. cpp:function:: Mat& Mat::operator = (const MatExpr_Base& expr)
 
-.. c:function:: Mat\& operator = (const Scalar\& s)
+.. cpp:function:: Mat& operator = (const Scalar& s)
 
     Matrix assignment operators
 
@@ -1054,18 +1077,20 @@ These are the available assignment operators, and they all are very different, s
 
 Mat::operator MatExpr
 -------------------------
-.. c:function:: Mat::operator MatExpr_<Mat, Mat>() const
+.. cpp:function:: Mat::operator MatExpr_<Mat, Mat>() const
 
     Mat-to-MatExpr cast operator
 
 The cast operator should not be called explicitly. It is used internally by the
-:ref:`Matrix Expressions` engine.
+:ref:`MatrixExpressions` engine.
 
 .. index:: Mat::row
 
+.. _Mat::row:
+
 Mat::row
 ------------
-.. c:function:: Mat Mat::row(int i) const
+.. cpp:function:: Mat Mat::row(int i) const
 
     Makes a matrix header for the specified matrix row
 
@@ -1101,9 +1126,11 @@ This is because ``A.row(i)`` forms a temporary header, which is further assigned
 
 .. index:: Mat::col
 
+.. _Mat::col:
+
 Mat::col
 ------------
-.. c:function:: Mat Mat::col(int j) const
+.. cpp:function:: Mat Mat::col(int j) const
 
     Makes a matrix header for the specified matrix column
 
@@ -1114,11 +1141,13 @@ The method makes a new header for the specified matrix column and returns it. Th
 
 .. index:: Mat::rowRange
 
+.. _Mat::rowRange:
+
 Mat::rowRange
 -----------------
-.. c:function:: Mat Mat::rowRange(int startrow, int endrow) const
+.. cpp:function:: Mat Mat::rowRange(int startrow, int endrow) const
 
-.. c:function:: Mat Mat::rowRange(const Range\& r) const
+.. cpp:function:: Mat Mat::rowRange(const Range& r) const
 
     Makes a matrix header for the specified row span
 
@@ -1134,11 +1163,13 @@ The method makes a new header for the specified row span of the matrix. Similarl
 
 .. index:: Mat::colRange
 
+.. _Mat::colRange:
+
 Mat::colRange
 -----------------
-.. c:function:: Mat Mat::colRange(int startcol, int endcol) const
+.. cpp:function:: Mat Mat::colRange(int startcol, int endcol) const
 
-.. c:function:: Mat Mat::colRange(const Range\& r) const
+.. cpp:function:: Mat Mat::colRange(const Range& r) const
 
     Makes a matrix header for the specified row span
 
@@ -1154,9 +1185,13 @@ The method makes a new header for the specified column span of the matrix. Simil
 
 .. index:: Mat::diag
 
+.. _Mat::diag:
+
 Mat::diag
 -------------
-.. c:function:: Mat Mat::diag(int d) const static Mat Mat::diag(const Mat\& matD)
+.. cpp:function:: Mat Mat::diag(int d) const
+
+.. cpp:function:: static Mat Mat::diag(const Mat& matD)
 
     Extracts diagonal from a matrix, or creates a diagonal matrix.
 
@@ -1176,9 +1211,11 @@ The method makes a new header for the specified matrix diagonal. The new matrix
 
 .. index:: Mat::clone
 
+.. _Mat::clone:
+
 Mat::clone
 --------------
-.. c:function:: Mat Mat::clone() const
+.. cpp:function:: Mat Mat::clone() const
 
     Creates full copy of the array and the underlying data.
 
@@ -1186,9 +1223,12 @@ The method creates full copy of the array. The original ``step[]`` are not taken
 
 .. index:: Mat::copyTo
 
+.. _Mat::copyTo:
+
 Mat::copyTo
 ---------------
-.. c:function:: void Mat::copyTo( Mat\& m ) const void Mat::copyTo( Mat\& m, const Mat\& mask ) const
+.. cpp:function:: void Mat::copyTo( Mat& m ) const
+.. cpp:function:: void Mat::copyTo( Mat& m, const Mat& mask ) const
 
     Copies the matrix to another one.
 
@@ -1207,9 +1247,11 @@ When the operation mask is specified, and the ``Mat::create`` call shown above r
 
 .. index:: Mat::convertTo
 
+.. _Mat::convertTo:
+
 Mat::convertTo
 ------------------
-.. c:function:: void Mat::convertTo( Mat\& m, int rtype, double alpha=1, double beta=0 ) const
+.. cpp:function:: void Mat::convertTo( Mat& m, int rtype, double alpha=1, double beta=0 ) const
 
     Converts array to another datatype with optional scaling.
 
@@ -1231,7 +1273,7 @@ The method converts source pixel values to the target datatype. ``saturate_cast<
 
 Mat::assignTo
 -----------------
-.. c:function:: void Mat::assignTo( Mat\& m, int type=-1 ) const
+.. cpp:function:: void Mat::assignTo( Mat& m, int type=-1 ) const
 
     Functional form of convertTo
 
@@ -1240,13 +1282,13 @@ Mat::assignTo
     :param type: The desired destination array depth (or -1 if it should be the same as the source one).
 
 This is internal-use method called by the
-:ref:`Matrix Expressions` engine.
+:ref:`MatrixExpressions` engine.
 
 .. index:: Mat::setTo
 
 Mat::setTo
 --------------
-.. c:function:: Mat\& Mat::setTo(const Scalar\& s, const Mat\& mask=Mat())
+.. c:function:: Mat& Mat::setTo(const Scalar& s, const Mat& mask=Mat())
 
     Sets all or some of the array elements to the specified value.
 
@@ -1258,7 +1300,7 @@ Mat::setTo
 
 Mat::reshape
 ----------------
-.. c:function:: Mat Mat::reshape(int cn, int rows=0) const
+.. cpp:function:: Mat Mat::reshape(int cn, int rows=0) const
 
     Changes the 2D matrix's shape and/or the number of channels without copying the data.
 
@@ -1292,7 +1334,7 @@ Here is some small example. Assuming, there is a set of 3D points that are store
 
 Mat::t
 ----------
-.. c:function:: MatExpr Mat::t() const
+.. cpp:function:: MatExpr Mat::t() const
 
     Transposes the matrix
 
@@ -1307,7 +1349,7 @@ It does not perform the actual transposition, but returns a temporary "matrix tr
 
 Mat::inv
 ------------
-.. c:function:: MatExpr Mat::inv(int method=DECOMP_LU) const
+.. cpp:function:: MatExpr Mat::inv(int method=DECOMP_LU) const
 
     Inverses the matrix
 
@@ -1325,9 +1367,9 @@ The method performs matrix inversion by means of matrix expressions, i.e. a temp
 
 Mat::mul
 ------------
-.. c:function:: MatExpr Mat::mul(const Mat\& m, double scale=1) const
+.. cpp:function:: MatExpr Mat::mul(const Mat& m, double scale=1) const
 
-.. c:function:: MatExpr Mat::mul(const MatExpr\& m, double scale=1) const
+.. cpp:function:: MatExpr Mat::mul(const MatExpr& m, double scale=1) const
 
     Performs element-wise multiplication or division of the two matrices
 
@@ -1346,7 +1388,7 @@ Here is a example: ::
 
 Mat::cross
 --------------
-.. c:function:: Mat Mat::cross(const Mat\& m) const
+.. cpp:function:: Mat Mat::cross(const Mat& m) const
 
     Computes cross-product of two 3-element vectors
 
@@ -1358,7 +1400,7 @@ The method computes cross-product of the two 3-element vectors. The vectors must
 
 Mat::dot
 ------------
-.. c:function:: double Mat::dot(const Mat\& m) const
+.. cpp:function:: double Mat::dot(const Mat& m) const
 
     Computes dot-product of two vectors
 
@@ -1370,7 +1412,9 @@ The method computes dot-product of the two matrices. If the matrices are not sin
 
 Mat::zeros
 --------------
-.. c:function:: static MatExpr Mat::zeros(int rows, int cols, int type) static MatExpr Mat::zeros(Size size, int type) static MatExpr Mat::zeros(int ndims, const int* sizes, int type)
+.. cpp:function:: static MatExpr Mat::zeros(int rows, int cols, int type)
+.. cpp:function:: static MatExpr Mat::zeros(Size size, int type)
+.. cpp:function:: static MatExpr Mat::zeros(int ndims, const int* sizes, int type)
 
     Returns zero array of the specified size and type
 
@@ -1396,7 +1440,9 @@ Note that in the above sample a new matrix will be allocated only if ``A`` is no
 
 Mat::ones
 -------------
-.. c:function:: static MatExpr Mat::ones(int rows, int cols, int type) static MatExpr Mat::ones(Size size, int type) static MatExpr Mat::ones(int ndims, const int* sizes, int type)
+.. cpp:function:: static MatExpr Mat::ones(int rows, int cols, int type)
+.. cpp:function:: static MatExpr Mat::ones(Size size, int type)
+.. cpp:function:: static MatExpr Mat::ones(int ndims, const int* sizes, int type)
 
     Returns array of all 1's of the specified size and type
 
@@ -1422,7 +1468,8 @@ The above operation will not form 100x100 matrix of ones and then multiply it by
 
 Mat::eye
 ------------
-.. c:function:: static MatExpr Mat::eye(int rows, int cols, int type) static MatExpr Mat::eye(Size size, int type)
+.. cpp:function:: static MatExpr Mat::eye(int rows, int cols, int type)
+.. cpp:function:: static MatExpr Mat::eye(Size size, int type)
 
     Returns identity matrix of the specified size and type
 
@@ -1441,9 +1488,13 @@ The method returns Matlab-style identity matrix initializer, similarly to
 
 .. index:: Mat::create
 
+.. _Mat::create:
+
 Mat::create
 ---------------
-.. c:function:: void Mat::create(int rows, int cols, int type) void Mat::create(Size size, int type) void Mat::create(int ndims, const int* sizes, int type)
+.. cpp:function:: void Mat::create(int rows, int cols, int type)
+.. cpp:function:: void Mat::create(Size size, int type)
+.. cpp:function:: void Mat::create(int ndims, const int* sizes, int type)
 
     Allocates new array data if needed.
 
@@ -1493,9 +1544,11 @@ because ``cvtColor`` , as well as most of OpenCV functions, calls Mat::create()
 
 .. index:: Mat::addref
 
+.. _Mat::addref:
+
 Mat::addref
 ---------------
-.. c:function:: void Mat::addref()
+.. cpp:function:: void Mat::addref()
 
     Increments the reference counter
 
@@ -1504,9 +1557,11 @@ The method increments the reference counter, associated with the matrix data. If
 
 .. index:: Mat::release
 
+.. _Mat::release:
+
 Mat::release
 ----------------
-.. c:function:: void Mat::release()
+.. cpp:function:: void Mat::release()
 
     Decrements the reference counter and deallocates the matrix if needed
 
@@ -1517,9 +1572,11 @@ This method can be called manually to force the matrix data deallocation. But si
 
 .. index:: Mat::resize
 
+.. _Mat::resize:
+
 Mat::resize
 ---------------
-.. c:function:: void Mat::resize( size_t sz ) const
+.. cpp:function:: void Mat::resize( size_t sz ) const
 
     Changes the number of matrix rows
 
@@ -1533,7 +1590,8 @@ The method changes the number of matrix rows. If the matrix is reallocated, the
 
 Mat::push_back
 --------------
-.. c:function:: template<typename T> void Mat::push_back(const T\& elem) template<typename T> void Mat::push_back(const Mat_<T>\& elem)
+.. c:function:: template<typename T> void Mat::push_back(const T& elem)
+.. c:function:: template<typename T> void Mat::push_back(const Mat_<T>& elem)
 
     Adds elements to the bottom of the matrix
 
@@ -1557,9 +1615,11 @@ The method removes one or more rows from the bottom of the matrix.
 
 .. index:: Mat::locateROI
 
+.. _Mat::locateROI:
+
 Mat::locateROI
 ------------------
-.. c:function:: void Mat::locateROI( Size\& wholeSize, Point\& ofs ) const
+.. cpp:function:: void Mat::locateROI( Size& wholeSize, Point& ofs ) const
 
     Locates matrix header within a parent matrix
 
@@ -1572,9 +1632,11 @@ After you extracted a submatrix from a matrix using
 
 .. index:: Mat::adjustROI
 
+.. _Mat::adjustROI:
+
 Mat::adjustROI
 ------------------
-.. c:function:: Mat\& Mat::adjustROI( int dtop, int dbottom, int dleft, int dright )
+.. cpp:function:: Mat& Mat::adjustROI( int dtop, int dbottom, int dleft, int dright )
 
     Adjust submatrix size and position within the parent matrix
 
@@ -1604,11 +1666,15 @@ See also
 
 .. index:: Mat::operator()
 
+.. _Mat::operator ():
+
 Mat::operator()
 -------------------
-.. c:function:: Mat Mat::operator()( Range rowRange, Range colRange ) const
+.. cpp:function:: Mat Mat::operator()( Range rowRange, Range colRange ) const
+
+.. cpp:function:: Mat Mat::operator()( const Rect& roi ) const
 
-.. c:function:: Mat Mat::operator()( const Rect\& roi ) const Mat Mat::operator()( const Ranges* ranges ) const
+.. cpp:function:: Mat Mat::operator()( const Ranges* ranges ) const
 
     Extracts a rectangular submatrix
 
@@ -1624,7 +1690,7 @@ The operators make a new header for the specified sub-array of ``*this`` . They
 
 Mat::operator CvMat
 -----------------------
-.. c:function:: Mat::operator CvMat() const
+.. cpp:function:: Mat::operator CvMat(void) const
 
     Creates CvMat header for the matrix
 
@@ -1643,7 +1709,7 @@ where ``mycvOldFunc`` is some function written to work with OpenCV 1.x data stru
 
 Mat::operator IplImage
 --------------------------
-.. c:function:: Mat::operator IplImage() const
+.. cpp:function:: Mat::operator IplImage(void) const
 
     Creates IplImage header for the matrix
 
@@ -1651,9 +1717,11 @@ The operator makes IplImage header for the matrix without copying the underlying
 
 .. index:: Mat::total
 
+.. _Mat::total:
+
 Mat::total
 --------------
-.. c:function:: size_t Mat::total() const
+.. cpp:function:: size_t Mat::total(void) const
 
     Returns the total number of array elements.
 
@@ -1661,9 +1729,11 @@ The method returns the number of array elements (e.g. number of pixels if the ar
 
 .. index:: Mat::isContinuous
 
+.. _Mat::isContinuous:
+
 Mat::isContinuous
 ---------------------
-.. c:function:: bool Mat::isContinuous() const
+.. cpp:function:: bool Mat::isContinuous(void) const
 
     Reports whether the matrix is continuous or not
 
@@ -1733,9 +1803,11 @@ Also, note that we use another OpenCV idiom in this function - we call
 
 .. index:: Mat::elemSize
 
+.. _Mat::elemSize:
+
 Mat::elemSize
 -----------------
-.. c:function:: size_t Mat::elemSize() const
+.. cpp:function:: size_t Mat::elemSize(void) const
 
     Returns matrix element size in bytes
 
@@ -1743,9 +1815,11 @@ The method returns the matrix element size in bytes. For example, if the matrix
 
 .. index:: Mat::elemSize1
 
+.. _Mat::elemSize1:
+
 Mat::elemSize1
 ------------------
-.. c:function:: size_t Mat::elemSize1() const
+.. cpp:function:: size_t Mat::elemSize1(void) const
 
     Returns size of each matrix element channel in bytes
 
@@ -1753,9 +1827,11 @@ The method returns the matrix element channel size in bytes, that is, it ignores
 
 .. index:: Mat::type
 
+.. _Mat::type:
+
 Mat::type
 -------------
-.. c:function:: int Mat::type() const
+.. cpp:function:: int Mat::type(void) const
 
     Returns matrix element type
 
@@ -1763,9 +1839,11 @@ The method returns the matrix element type, an id, compatible with the ``CvMat``
 
 .. index:: Mat::depth
 
+.. _Mat::depth:
+
 Mat::depth
 --------------
-.. c:function:: int Mat::depth() const
+.. cpp:function:: int Mat::depth(void) const
 
     Returns matrix element depth
 
@@ -1787,9 +1865,11 @@ The method returns the matrix element depth id, i.e. the type of each individual
 
 .. index:: Mat::channels
 
+.. _Mat::channels:
+
 Mat::channels
 -----------------
-.. c:function:: int Mat::channels() const
+.. cpp:function:: int Mat::channels(void) const
 
     Returns matrix element depth
 
@@ -1797,9 +1877,11 @@ The method returns the number of matrix channels.
 
 .. index:: Mat::step1
 
+.. _Mat::step1:
+
 Mat::step1
 --------------
-.. c:function:: size_t Mat::step1() const
+.. cpp:function:: size_t Mat::step1(void) const
 
     Returns normalized step
 
@@ -1808,9 +1890,11 @@ The method returns the matrix step, divided by
 
 .. index:: Mat::size
 
+.. _Mat::size:
+
 Mat::size
 -------------
-.. c:function:: Size Mat::size() const
+.. cpp:function:: Size Mat::size(void) const
 
     Returns the matrix size
 
@@ -1818,9 +1902,11 @@ The method returns the matrix size: ``Size(cols, rows)`` .
 
 .. index:: Mat::empty
 
+.. _Mat::empty:
+
 Mat::empty
 --------------
-.. c:function:: bool Mat::empty() const
+.. cpp:function:: bool Mat::empty(void) const
 
     Returns true if the array has no elemens
 
@@ -1828,6 +1914,8 @@ The method returns true if ``Mat::total()`` is 0 or if ``Mat::data`` is NULL. Be
 
 .. index:: Mat::ptr
 
+.. _Mat::ptr:
+
 Mat::ptr
 ------------
 .. c:function:: uchar* Mat::ptr(int i=0)
@@ -1847,27 +1935,29 @@ The methods return ``uchar*`` or typed pointer to the specified matrix row. See
 
 .. index:: Mat::at
 
+.. _Mat::at:
+
 Mat::at
 -----------
-.. c:function:: template<typename T> T\& Mat::at(int i) const
+.. c:function:: template<typename T> T& Mat::at(int i) const
 
-.. c:function:: template<typename T> const T\& Mat::at(int i) const
+.. c:function:: template<typename T> const T& Mat::at(int i) const
 
-.. c:function:: template<typename T> T\& Mat::at(int i, int j)
+.. c:function:: template<typename T> T& Mat::at(int i, int j)
 
-.. c:function:: template<typename T> const T\& Mat::at(int i, int j) const
+.. c:function:: template<typename T> const T& Mat::at(int i, int j) const
 
-.. c:function:: template<typename T> T\& Mat::at(Point pt)
+.. c:function:: template<typename T> T& Mat::at(Point pt)
 
-.. c:function:: template<typename T> const T\& Mat::at(Point pt) const
+.. c:function:: template<typename T> const T& Mat::at(Point pt) const
 
-.. c:function:: template<typename T> T\& Mat::at(int i, int j, int k)
+.. c:function:: template<typename T> T& Mat::at(int i, int j, int k)
 
-.. c:function:: template<typename T> const T\& Mat::at(int i, int j, int k) const
+.. c:function:: template<typename T> const T& Mat::at(int i, int j, int k) const
 
-.. c:function:: template<typename T> T\& Mat::at(const int* idx)
+.. c:function:: template<typename T> T& Mat::at(const int* idx)
 
-.. c:function:: template<typename T> const T\& Mat::at(const int* idx) const
+.. c:function:: template<typename T> const T& Mat::at(const int* idx) const
 
     Return reference to the specified array element
 
@@ -1889,6 +1979,8 @@ Here is an example of initialization of a Hilbert matrix: ::
 
 .. index:: Mat::begin
 
+.. _Mat::begin:
+
 Mat::begin
 --------------
 .. c:function:: template<typename _Tp> MatIterator_<_Tp> Mat::begin() template<typename _Tp> MatConstIterator_<_Tp> Mat::begin() const
@@ -1929,6 +2021,8 @@ The methods return the matrix read-only or read-write iterators. The use of matr
 
 .. index:: Mat::end
 
+.. _Mat::end:
+
 Mat::end
 ------------
 .. c:function:: template<typename _Tp> MatIterator_<_Tp> Mat::end() template<typename _Tp> MatConstIterator_<_Tp> Mat::end() const
@@ -1987,6 +2081,8 @@ This is simple - just pass ``Vec`` as ``Mat_`` parameter: ::
             img(i,j)[2] ^= (uchar)(i ^ j);
 
 
+.. _NAryMatIterator:
+
 NAryMatIterator
 ---------------
 
@@ -2013,7 +2109,7 @@ n-ary multi-dimensional array iterator ::
 
 
 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
         SparseMat_ clone() const;
index aff2fa9..c668705 100644 (file)
@@ -1,12 +1,13 @@
 Clustering
 ==========
 
-.. highlight:: cpp
-
 .. index:: kmeans
 
+.. _kmeans:
+
 kmeans
-----------
+------
+
 .. c:function:: double kmeans( const Mat\& samples, int clusterCount, Mat\& labels,               TermCriteria termcrit, int attempts,               int flags, Mat* centers )
 
     Finds the centers of clusters and groups the input samples around the clusters.
diff --git a/modules/core/doc/dynamic_structures.rst b/modules/core/doc/dynamic_structures.rst
deleted file mode 100644 (file)
index f79f031..0000000
+++ /dev/null
@@ -1,5 +0,0 @@
-Dynamic Structures
-==================
-
-.. highlight:: cpp
-
index 569fe50..f5486b8 100644 (file)
@@ -2,11 +2,9 @@
 Introduction
 ************
 
-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.
 
 The API Concepts
 ================
index 0725a43..cd3348e 100644 (file)
@@ -5,11 +5,13 @@ Operations on Arrays
 
 .. index:: abs
 
+.. _abs:
+
 abs
 -------
-.. c:function:: MatExpr<...> abs(const Mat\& src)
+.. c:function:: MatExpr<...> abs(const Mat& src)
 
-.. c:function:: MatExpr<...> abs(const MatExpr<...>\& src)
+.. c:function:: MatExpr<...> abs(const MatExpr<...>& src)
 
     Computes absolute value of each matrix element
 
@@ -26,17 +28,17 @@ abs
 The output matrix will have the same size and the same type as the input one
 (except for the last case, where ``C`` will be ``depth=CV_8U`` ).
 
-See also: :ref:`Matrix Expressions`, :func:`absdiff`
+See also: :ref:`MatrixExpressions`, :func:`absdiff`
 
 .. index:: absdiff
 
+.. _absdiff:
+
 absdiff
 -----------
 
-.. c:function:: void absdiff(const Mat\& src1, const Mat\& src2, Mat\& dst)
-.. c:function:: void absdiff(const Mat\& src1, const Scalar\& sc, Mat\& dst)
-.. c:function:: void absdiff(const MatND\& src1, const MatND\& src2, MatND\& dst)
-.. c:function:: void absdiff(const MatND\& src1, const Scalar\& sc, MatND\& dst)
+.. c:function:: void absdiff(const Mat& src1, const Mat& src2, Mat& dst)
+.. c:function:: void absdiff(const Mat& src1, const Scalar& sc, Mat& dst)
 
     Computes per-element absolute difference between 2 arrays or between array and a scalar.
 
@@ -66,19 +68,15 @@ See also: :func:`abs`
 
 .. index:: add
 
+.. _add:
+
 add
 -------
-.. c:function:: void add(const Mat\& src1, const Mat\& src2, Mat\& dst)
-
-.. c:function:: void add(const Mat\& src1, const Mat\& src2,  Mat\& dst, const Mat\& mask)
-
-.. c:function:: void add(const Mat\& src1, const Scalar\& sc,  Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void add(const Mat& src1, const Mat& src2, Mat& dst)
 
-.. c:function:: void add(const MatND\& src1, const MatND\& src2, MatND\& dst)
+.. c:function:: void add(const Mat& src1, const Mat& src2, Mat& dst, const Mat& mask)
 
-.. c:function:: void add(const MatND\& src1, const MatND\& src2,  MatND\& dst, const MatND\& mask)
-
-.. c:function:: void add(const MatND\& src1, const Scalar\& sc,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void add(const Mat& src1, const Scalar& sc, Mat& dst, const Mat& mask=Mat())
 
     Computes the per-element sum of two arrays or an array and a scalar.
 
@@ -119,15 +117,15 @@ The first function in the above list can be replaced with matrix expressions: ::
 in the case of multi-channel arrays each channel is processed independently.
 
 See also:
-:func:`subtract`,:func:`addWeighted`,:func:`scaleAdd`,:func:`convertScale`,:ref:`Matrix Expressions`,.
+:func:`subtract`,:func:`addWeighted`,:func:`scaleAdd`,:func:`convertScale`,:ref:`MatrixExpressions`
 
 .. index:: addWeighted
 
+.. _addWeighted:
+
 addWeighted
 ---------------
-.. c:function:: void addWeighted(const Mat\& src1, double alpha, const Mat\& src2,                 double beta, double gamma, Mat\& dst)
-
-.. c:function:: void addWeighted(const MatND\& src1, double alpha, const MatND\& src2,                 double beta, double gamma, MatND\& dst)
+.. c:function:: void addWeighted(const Mat& src1, double alpha, const Mat& src2, double beta, double gamma, Mat& dst)
 
     Computes the weighted sum of two arrays.
 
@@ -159,19 +157,17 @@ The first function can be replaced with a matrix expression: ::
 In the case of multi-channel arrays each channel is processed independently.
 
 See also:
-:func:`add`,:func:`subtract`,:func:`scaleAdd`,:func:`convertScale`,:ref:`Matrix Expressions`,.
+:func:`add`,:func:`subtract`,:func:`scaleAdd`,:func:`convertScale`,:ref:`MatrixExpressions`
 
 .. index:: bitwise_and
 
+.. _bitwise_and_:
+
 bitwise_and
 -----------
-.. c:function:: void bitwise_and(const Mat\& src1, const Mat\& src2, Mat\& dst, const Mat\& mask=Mat())
-
-.. c:function:: void bitwise_and(const Mat\& src1, const Scalar\& sc,  Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void bitwise_and(const Mat& src1, const Mat& src2, Mat& dst, const Mat& mask=Mat())
 
-.. c:function:: void bitwise_and(const MatND\& src1, const MatND\& src2,  MatND\& dst, const MatND\& mask=MatND())
-
-.. c:function:: void bitwise_and(const MatND\& src1, const Scalar\& sc,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void bitwise_and(const Mat& src1, const Scalar& sc, Mat& dst, const Mat& mask=Mat())
 
     Calculates per-element bit-wise conjunction of two arrays and an array and a scalar.
 
@@ -207,11 +203,11 @@ See also:,,
 
 .. index:: bitwise_not
 
+.. _bitwise_not_:
+
 bitwise_not
 -----------
-.. c:function:: void bitwise_not(const Mat\& src, Mat\& dst)
-
-.. c:function:: void bitwise_not(const MatND\& src, MatND\& dst)
+.. c:function:: void bitwise_not(const Mat& src, Mat& dst)
 
     Inverts every bit of array
 
@@ -231,15 +227,13 @@ In the case of floating-point source array its machine-specific bit representati
 
 .. index:: bitwise_or
 
+.. _bitwise_or_:
+
 bitwise_or
 ----------
-.. c:function:: void bitwise_or(const Mat\& src1, const Mat\& src2, Mat\& dst, const Mat\& mask=Mat())
-
-.. c:function:: void bitwise_or(const Mat\& src1, const Scalar\& sc,  Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void bitwise_or(const Mat& src1, const Mat& src2, Mat& dst, const Mat& mask=Mat())
 
-.. c:function:: void bitwise_or(const MatND\& src1, const MatND\& src2,  MatND\& dst, const MatND\& mask=MatND())
-
-.. c:function:: void bitwise_or(const MatND\& src1, const Scalar\& sc,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void bitwise_or(const Mat& src1, const Scalar& sc, Mat& dst, const Mat& mask=Mat())
 
     Calculates per-element bit-wise disjunction of two arrays and an array and a scalar.
 
@@ -271,19 +265,15 @@ The functions ``bitwise_or`` compute per-element bit-wise logical disjunction
 
 In the case of floating-point arrays their machine-specific bit representations (usually IEEE754-compliant) are used for the operation. in the case of multi-channel arrays each channel is processed independently.
 
-See also:,,
-
 .. index:: bitwise_xor
 
+.. _bitwise_xor_:
+
 bitwise_xor
 -----------
-.. c:function:: void bitwise_xor(const Mat\& src1, const Mat\& src2, Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void bitwise_xor(const Mat& src1, const Mat& src2, Mat& dst, const Mat& mask=Mat())
 
-.. c:function:: void bitwise_xor(const Mat\& src1, const Scalar\& sc,  Mat\& dst, const Mat\& mask=Mat())
-
-.. c:function:: void bitwise_xor(const MatND\& src1, const MatND\& src2,  MatND\& dst, const MatND\& mask=MatND())
-
-.. c:function:: void bitwise_xor(const MatND\& src1, const Scalar\& sc,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void bitwise_xor(const Mat& src1, const Scalar& sc, Mat& dst, const Mat& mask=Mat())
 
     Calculates per-element bit-wise "exclusive or" operation on two arrays and an array and a scalar.
 
@@ -299,15 +289,13 @@ bitwise_xor
 
 The functions ``bitwise_xor`` compute per-element bit-wise logical "exclusive or" operation
 
-*
-    on two arrays
+ * on two arrays
 
     .. math::
 
         \texttt{dst} (I) =  \texttt{src1} (I)  \oplus \texttt{src2} (I) \quad \texttt{if mask} (I) \ne0
 
-*
-    or array and a scalar:
+ * or array and a scalar:
 
     .. math::
 
@@ -315,15 +303,16 @@ The functions ``bitwise_xor`` compute per-element bit-wise logical "exclusive or
 
 In the case of floating-point arrays their machine-specific bit representations (usually IEEE754-compliant) are used for the operation. in the case of multi-channel arrays each channel is processed independently.
 
-See also:,,
-
 .. index:: calcCovarMatrix
 
+.. _calcCovarMatrix:
+
 calcCovarMatrix
--------------------
-.. c:function:: void calcCovarMatrix( const Mat* samples, int nsamples,                      Mat\& covar, Mat\& mean,                      int flags, int ctype=CV_64F)
+---------------
+
+.. c:function:: void calcCovarMatrix( const Mat* samples, int nsamples, Mat& covar, Mat& mean, int flags, int ctype=CV_64F)
 
-.. c:function:: void calcCovarMatrix( const Mat\& samples, Mat\& covar, Mat\& mean,                      int flags, int ctype=CV_64F)
+.. c:function:: void calcCovarMatrix( const Mat& samples, Mat& covar, Mat& mean, int flags, int ctype=CV_64F)
 
     Calculates covariation matrix of a set of vectors
 
@@ -351,9 +340,9 @@ calcCovarMatrix
 
                       \texttt{scale}   \cdot  [  \texttt{vects}  [0]-  \texttt{mean}  , \texttt{vects}  [1]-  \texttt{mean}  ,...]  \cdot  [ \texttt{vects}  [0]- \texttt{mean}  , \texttt{vects}  [1]- \texttt{mean}  ,...]^T,
                       
-                that is,  ``covar``  will be a square matrix of the same size as the total number of elements in each input vector. One and only one of  ``CV_COVAR_SCRAMBLED``  and ``CV_COVAR_NORMAL``  must be specified
+                that is, ``covar``  will be a square matrix of the same size as the total number of elements in each input vector. One and only one of  ``CV_COVAR_SCRAMBLED``  and ``CV_COVAR_NORMAL``  must be specified
 
-            * **CV_COVAR_USE_AVG** If the flag is specified, the function does not calculate  ``mean``  from the input vectors, but, instead, uses the passed  ``mean``  vector. This is useful if  ``mean``  has been pre-computed or known a-priori, or if the covariance matrix is calculated by parts - in this case,  ``mean``  is not a mean vector of the input sub-set of vectors, but rather the mean vector of the whole set.
+            * **CV_COVAR_USE_AVG** If the flag is specified, the function does not calculate  ``mean``  from the input vectors, but, instead, uses the passed  ``mean``  vector. This is useful if  ``mean``  has been pre-computed or known a-priori, or if the covariance matrix is calculated by parts - in this case, ``mean``  is not a mean vector of the input sub-set of vectors, but rather the mean vector of the whole set.
 
             * **CV_COVAR_SCALE** If the flag is specified, the covariance matrix is scaled. In the "normal" mode  ``scale``  is  ``1./nsamples`` ; in the "scrambled" mode  ``scale``  is the reciprocal of the total number of elements in each input vector. By default (if the flag is not specified) the covariance matrix is not scaled (i.e.  ``scale=1`` ).
 
@@ -369,9 +358,12 @@ See also:
 
 .. index:: cartToPolar
 
+.. _cartToPolar:
+
 cartToPolar
----------------
-.. c:function:: void cartToPolar(const Mat\& x, const Mat\& y,                 Mat\& magnitude, Mat\& angle,                 bool angleInDegrees=false)
+-----------
+
+.. c:function:: void cartToPolar(const Mat& x, const Mat& y, Mat& magnitude, Mat& angle, bool angleInDegrees=false)
 
     Calculates the magnitude and angle of 2d vectors.
 
@@ -389,18 +381,19 @@ The function ``cartToPolar`` calculates either the magnitude, angle, or both of
 
 .. math::
 
-    \begin{array}{l} \texttt{magnitude} (I)= \sqrt{\texttt{x}(I)^2+\texttt{y}(I)^2} , \\ \texttt{angle} (I)= \texttt{atan2} ( \texttt{y} (I),  \texttt{x} (I))[ \cdot180 / \pi ] \end{array}
+    \begin{array}{l} \texttt{magnitude} (I)= \sqrt{\texttt{x}(I)^2+\texttt{y}(I)^2} , \\ \texttt{angle} (I)= \texttt{atan2} ( \texttt{y} (I), \texttt{x} (I))[ \cdot180 / \pi ] \end{array}
 
 The angles are calculated with
 :math:`\sim\,0.3^\circ` accuracy. For the (0,0) point, the angle is set to 0.
 
 .. index:: checkRange
 
+.. _checkRange:
+
 checkRange
---------------
-.. c:function:: bool checkRange(const Mat\& src, bool quiet=true, Point* pos=0,                double minVal=-DBL_MAX, double maxVal=DBL_MAX)
+----------
 
-.. c:function:: bool checkRange(const MatND\& src, bool quiet=true, int* pos=0,                double minVal=-DBL_MAX, double maxVal=DBL_MAX)
+.. c:function:: bool checkRange(const Mat& src, bool quiet=true, Point* pos=0, double minVal=-DBL_MAX, double maxVal=DBL_MAX)
 
     Checks every element of an input array for invalid values.
 
@@ -423,15 +416,14 @@ If some values are out of range, position of the first outlier is stored in ``po
 
 .. index:: compare
 
-compare
------------
-.. c:function:: void compare(const Mat\& src1, const Mat\& src2, Mat\& dst, int cmpop)
+.. _compare:
 
-.. c:function:: void compare(const Mat\& src1, double value,  Mat\& dst, int cmpop)
+compare
+-------
 
-.. c:function:: void compare(const MatND\& src1, const MatND\& src2,  MatND\& dst, int cmpop)
+.. c:function:: void compare(const Mat& src1, const Mat& src2, Mat& dst, int cmpop)
 
-.. c:function:: void compare(const MatND\& src1, double value,  MatND\& dst, int cmpop)
+.. c:function:: void compare(const Mat& src1, double value, Mat& dst, int cmpop)
 
     Performs per-element comparison of two arrays or an array and scalar value.
 
@@ -465,13 +457,16 @@ The comparison operations can be replaced with the equivalent matrix expressions
 
 
 See also:
-:func:`checkRange`,:func:`min`,:func:`max`,:func:`threshold`,:ref:`Matrix Expressions`
+:func:`checkRange`,:func:`min`,:func:`max`,:func:`threshold`,:ref:`MatrixExpressions`
 
 .. index:: completeSymm
 
+.. _completeSymm:
+
 completeSymm
-----------------
-.. c:function:: void completeSymm(Mat\& mtx, bool lowerToUpper=false)
+------------
+
+.. c:function:: void completeSymm(Mat& mtx, bool lowerToUpper=false)
 
     Copies the lower or the upper half of a square matrix to another half.
 
@@ -493,9 +488,12 @@ See also: :func:`flip`,:func:`transpose`
 
 .. index:: convertScaleAbs
 
+.. _convertScaleAbs:
+
 convertScaleAbs
--------------------
-.. c:function:: void convertScaleAbs(const Mat\& src, Mat\& dst, double alpha=1, double beta=0)
+---------------
+
+.. c:function:: void convertScaleAbs(const Mat& src, Mat& dst, double alpha=1, double beta=0)
 
     Scales, computes absolute values and converts the result to 8-bit.
 
@@ -528,11 +526,12 @@ See also:
 
 .. index:: countNonZero
 
+.. _countNonZero:
+
 countNonZero
-----------------
-.. c:function:: int countNonZero( const Mat\& mtx )
+------------
 
-.. c:function:: int countNonZero( const MatND\& mtx )
+.. c:function:: int countNonZero( const Mat& mtx )
 
     Counts non-zero array elements.
 
@@ -549,8 +548,11 @@ See also:
 
 .. index:: cubeRoot
 
+.. _cubeRoot:
+
 cubeRoot
-------------
+--------
+
 .. c:function:: float cubeRoot(float val)
 
     Computes cube root of the argument
@@ -562,13 +564,16 @@ and :math:`\pm\infty` are not handled. The accuracy approaches the maximum possi
 
 .. index:: cvarrToMat
 
+.. _cvarrToMat:
+
 cvarrToMat
---------------
+----------
+
 .. c:function:: Mat cvarrToMat(const CvArr* src, bool copyData=false, bool allowND=true, int coiMode=0)
 
-    Converts CvMat, IplImage or CvMatND to Mat.
+    Converts ``CvMat``, ``IplImage`` or ``CvMatND`` to ``Mat``.
 
-    :param src: The source  ``CvMat`` ,  ``IplImage``  or  ``CvMatND``
+    :param src: The source ``CvMat``, ``IplImage``  or  ``CvMatND``
     
     :param copyData: When it is false (default value), no data is copied, only the new header is created. In this case the original array should not be deallocated while the new matrix header is used. The the parameter is true, all the data is copied, then user may deallocate the original array right after the conversion
 
@@ -580,16 +585,14 @@ cvarrToMat
 
         *  If  ``coiMode=1`` , the function will never report an error; instead it returns the header to the whole original image and user will have to check and process COI manually, see  :func:`extractImageCOI` .
 
-The function ``cvarrToMat`` converts
-:ref:`CvMat`,:ref:`IplImage` or
-:ref:`CvMatND` header to
+The function ``cvarrToMat`` converts ``CvMat``, ``IplImage`` or ``CvMatND`` header to
 :func:`Mat` header, and optionally duplicates the underlying data. The constructed header is returned by the function.
 
 When ``copyData=false`` , the conversion is done really fast (in O(1) time) and the newly created matrix header will have ``refcount=0`` , which means that no reference counting is done for the matrix data, and user has to preserve the data until the new header is destructed. Otherwise, when ``copyData=true`` , the new buffer will be allocated and managed as if you created a new matrix from scratch and copy the data there. That is, ``cvarrToMat(src, true) :math:`\sim` cvarrToMat(src, false).clone()`` (assuming that COI is not set). The function provides uniform way of supporting
-:ref:`CvArr` paradigm in the code that is migrated to use new-style data structures internally. The reverse transformation, from
+``CvArr`` paradigm in the code that is migrated to use new-style data structures internally. The reverse transformation, from
 :func:`Mat` to
-:ref:`CvMat` or
-:ref:`IplImage` can be done by simple assignment: ::
+``CvMat`` or
+``IplImage`` can be done by simple assignment: ::
 
     CvMat* A = cvCreateMat(10, 10, CV_32F);
     cvSetIdentity(A);
@@ -606,12 +609,12 @@ When ``copyData=false`` , the conversion is done really fast (in O(1) time) and
 
 
 Normally, the function is used to convert an old-style 2D array (
-:ref:`CvMat` or
-:ref:`IplImage` ) to ``Mat`` , however, the function can also take
-:ref:`CvMatND` on input and create
+``CvMat`` or
+``IplImage`` ) to ``Mat`` , however, the function can also take
+``CvMatND`` on input and create
 :func:`Mat` for it, if it's possible. And for ``CvMatND A`` it is possible if and only if ``A.dim[i].size*A.dim.step[i] == A.dim.step[i-1]`` for all or for all but one ``i, 0 < i < A.dims`` . That is, the matrix data should be continuous or it should be representable as a sequence of continuous matrices. By using this function in this way, you can process
-:ref:`CvMatND` using arbitrary element-wise function. But for more complex operations, such as filtering functions, it will not work, and you need to convert
-:ref:`CvMatND` to
+``CvMatND`` using arbitrary element-wise function. But for more complex operations, such as filtering functions, it will not work, and you need to convert
+``CvMatND`` to
 :func:`MatND` using the corresponding constructor of the latter.
 
 The last parameter, ``coiMode`` , specifies how to react on an image with COI set: by default it's 0, and then the function reports an error when an image with COI comes in. And ``coiMode=1`` means that no error is signaled - user has to check COI presence and handle it manually. The modern structures, such as
@@ -627,9 +630,11 @@ See also:
 
 .. index:: dct
 
+.. _dct:
+
 dct
 -------
-.. c:function:: void dct(const Mat\& src, Mat\& dst, int flags=0)
+.. c:function:: void dct(const Mat& src, Mat& dst, int flags=0)
 
     Performs a forward or inverse discrete cosine transform of 1D or 2D array
 
@@ -715,9 +720,12 @@ See also:
 
 .. index:: dft
 
+.. _dft:
+
 dft
--------
-.. c:function:: void dft(const Mat\& src, Mat\& dst, int flags=0, int nonzeroRows=0)
+---
+
+.. c:function:: void dft(const Mat& src, Mat& dst, int flags=0, int nonzeroRows=0)
 
     Performs a forward or inverse Discrete Fourier transform of 1D or 2D floating-point array.
 
@@ -779,23 +787,17 @@ in the case of 1D transform of real vector, the output will look as the first ro
 
 So, the function chooses the operation mode depending on the flags and size of the input array:
 
-*
-    if ``DFT_ROWS``     is set or the input array has single row or single column then the function performs 1D forward or inverse transform (of each row of a matrix when ``DFT_ROWS``     is set, otherwise it will be 2D transform.
+ * if ``DFT_ROWS`` is set or the input array has single row or single column then the function performs 1D forward or inverse transform (of each row of a matrix when ``DFT_ROWS`` is set, otherwise it will be 2D transform.
 
-*
-    if input array is real and ``DFT_INVERSE``     is not set, the function does forward 1D or 2D transform:
+ * if input array is real and ``DFT_INVERSE`` is not set, the function does forward 1D or 2D transform:
 
-    *
-        when ``DFT_COMPLEX_OUTPUT``         is set then the output will be complex matrix of the same size as input.
+    * when ``DFT_COMPLEX_OUTPUT`` is set then the output will be complex matrix of the same size as input.
 
-    *
-        otherwise the output will be a real matrix of the same size as input. in the case of 2D transform it will use the packed format as shown above; in the case of single 1D transform it will look as the first row of the above matrix; in the case of multiple 1D transforms (when using ``DCT_ROWS``         flag) each row of the output matrix will look like the first row of the above matrix.
+    * otherwise the output will be a real matrix of the same size as input. in the case of 2D transform it will use the packed format as shown above; in the case of single 1D transform it will look as the first row of the above matrix; in the case of multiple 1D transforms (when using ``DCT_ROWS``         flag) each row of the output matrix will look like the first row of the above matrix.
 
-*
-    otherwise, if the input array is complex and either ``DFT_INVERSE``     or ``DFT_REAL_OUTPUT``     are not set then the output will be a complex array of the same size as input and the function will perform the forward or inverse 1D or 2D transform of the whole input array or each row of the input array independently, depending on the flags ``DFT_INVERSE``     and ``DFT_ROWS``     .
+ * otherwise, if the input array is complex and either ``DFT_INVERSE``     or ``DFT_REAL_OUTPUT``     are not set then the output will be a complex array of the same size as input and the function will perform the forward or inverse 1D or 2D transform of the whole input array or each row of the input array independently, depending on the flags ``DFT_INVERSE`` and ``DFT_ROWS``.
 
-*
-    otherwise, i.e. when ``DFT_INVERSE``     is set, the input array is real, or it is complex but ``DFT_REAL_OUTPUT``     is set, the output will be a real array of the same size as input, and the function will perform 1D or 2D inverse transformation of the whole input array or each individual row, depending on the flags ``DFT_INVERSE``     and ``DFT_ROWS``     .
+ * otherwise, i.e. when ``DFT_INVERSE`` is set, the input array is real, or it is complex but ``DFT_REAL_OUTPUT``     is set, the output will be a real array of the same size as input, and the function will perform 1D or 2D inverse transformation of the whole input array or each individual row, depending on the flags ``DFT_INVERSE`` and ``DFT_ROWS``.
 
 The scaling is done after the transformation if ``DFT_SCALE`` is set.
 
@@ -863,15 +865,17 @@ See also:
 
 .. index:: divide
 
+.. _divide:
+
 divide
 ----------
-.. c:function:: void divide(const Mat\& src1, const Mat\& src2,  Mat\& dst, double scale=1)
+.. c:function:: void divide(const Mat& src1, const Mat& src2, Mat& dst, double scale=1)
 
-.. c:function:: void divide(double scale, const Mat\& src2, Mat\& dst)
+.. c:function:: void divide(double scale, const Mat& src2, Mat& dst)
 
-.. c:function:: void divide(const MatND\& src1, const MatND\& src2,  MatND\& dst, double scale=1)
+.. c:function:: void divide(const MatND& src1, const MatND& src2, MatND& dst, double scale=1)
 
-.. c:function:: void divide(double scale, const MatND\& src2, MatND\& dst)
+.. c:function:: void divide(double scale, const MatND& src2, MatND& dst)
 
     Performs per-element division of two arrays or a scalar by an array.
 
@@ -898,13 +902,16 @@ or a scalar by array, when there is no ``src1`` :
 The result will have the same type as ``src1`` . When ``src2(I)=0``,``dst(I)=0`` too.
 
 See also:
-:func:`multiply`,:func:`add`,:func:`subtract`,:ref:`Matrix Expressions`
+:func:`multiply`,:func:`add`,:func:`subtract`,:ref:`MatrixExpressions`
 
 .. index:: determinant
 
+.. _determinant:
+
 determinant
----------------
-.. c:function:: double determinant(const Mat\& mtx)
+-----------
+
+.. c:function:: double determinant(const Mat& mtx)
 
     Returns determinant of a square floating-point matrix.
 
@@ -919,15 +926,18 @@ For symmetric positive-determined matrices, it is also possible to compute
 :math:`W` .
 
 See also:
-:func:`SVD`,:func:`trace`,:func:`invert`,:func:`solve`,:ref:`Matrix Expressions`
+:func:`SVD`,:func:`trace`,:func:`invert`,:func:`solve`,:ref:`MatrixExpressions`
 
 .. index:: eigen
 
+.. _eigen:
+
 eigen
----------
-.. c:function:: bool eigen(const Mat\& src, Mat\& eigenvalues,  int lowindex=-1, int highindex=-1)
+-----
+
+.. c:function:: bool eigen(const Mat& src, Mat& eigenvalues, int lowindex=-1, int highindex=-1)
 
-.. c:function:: bool eigen(const Mat\& src, Mat\& eigenvalues,  Mat\& eigenvectors, int lowindex=-1,int highindex=-1)
+.. c:function:: bool eigen(const Mat& src, Mat& eigenvalues, Mat& eigenvectors, int lowindex=-1,int highindex=-1)
 
     Computes eigenvalues and eigenvectors of a symmetric matrix.
 
@@ -959,11 +969,14 @@ See also:
 
 .. index:: exp
 
+.. _exp:
+
 exp
--------
-.. c:function:: void exp(const Mat\& src, Mat\& dst)
+---
 
-.. c:function:: void exp(const MatND\& src, MatND\& dst)
+.. c:function:: void exp(const Mat& src, Mat& dst)
+
+.. c:function:: void exp(const MatND& src, MatND& dst)
 
     Calculates the exponent of every array element.
 
@@ -987,17 +1000,20 @@ See also:
 
 .. index:: extractImageCOI
 
+.. _extractImageCOI:
+
 extractImageCOI
--------------------
-.. c:function:: void extractImageCOI(const CvArr* src, Mat\& dst, int coi=-1)
+---------------
+
+.. c:function:: void extractImageCOI(const CvArr* src, Mat& dst, int coi=-1)
 
     Extract the selected image channel
 
-    :param src: The source array. It should be a pointer to  :ref:`CvMat`  or  :ref:`IplImage`
+    :param src: The source array. It should be a pointer to  ``CvMat``  or  ``IplImage``
     
     :param dst: The destination array; will have single-channel, and the same size and the same depth as  ``src``
     
-    :param coi: If the parameter is  ``>=0`` , it specifies the channel to extract; If it is  ``<0`` ,  ``src``  must be a pointer to  ``IplImage``  with valid COI set - then the selected COI is extracted.
+    :param coi: If the parameter is  ``>=0`` , it specifies the channel to extract; If it is  ``<0`` , ``src``  must be a pointer to  ``IplImage``  with valid COI set - then the selected COI is extracted.
 
 The function ``extractImageCOI`` is used to extract image COI from an old-style array and put the result to the new-style C++ matrix. As usual, the destination matrix is reallocated using ``Mat::create`` if needed.
 
@@ -1008,8 +1024,11 @@ To extract a channel from a new-style matrix, use
 
 .. index:: fastAtan2
 
+.. _fastAtan2:
+
 fastAtan2
--------------
+---------
+
 .. c:function:: float fastAtan2(float y, float x)
 
     Calculates the angle of a 2D vector in degrees
@@ -1028,7 +1047,7 @@ measured in degrees and varies from
 
 flip
 --------
-.. c:function:: void flip(const Mat\& src, Mat\& dst, int flipCode)
+.. c:function:: void flip(const Mat& src, Mat& dst, int flipCode)
 
     Flips a 2D array around vertical, horizontal or both axes.
 
@@ -1069,13 +1088,16 @@ See also: :func:`transpose`,:func:`repeat`,:func:`completeSymm`
 
 .. index:: gemm
 
+.. _gemm:
+
 gemm
---------
-.. c:function:: void gemm(const Mat\& src1, const Mat\& src2, double alpha,          const Mat\& src3, double beta, Mat\& dst, int flags=0)
+----
+
+.. c:function:: void gemm(const Mat& src1, const Mat& src2, double alpha, const Mat& src3, double beta, Mat& dst, int flags=0)
 
     Performs generalized matrix multiplication.
 
-    :param src1: The first multiplied input matrix; should have  ``CV_32FC1`` ,  ``CV_64FC1`` ,  ``CV_32FC2``  or  ``CV_64FC2``  type
+    :param src1: The first multiplied input matrix; should have  ``CV_32FC1`` , ``CV_64FC1`` , ``CV_32FC2``  or  ``CV_64FC2``  type
 
     :param src2: The second multiplied input matrix; should have the same type as  ``src1``
     
@@ -1105,19 +1127,22 @@ The function can be replaced with a matrix expression, e.g. the above call can b
 
 
 See also:
-:func:`mulTransposed`,:func:`transform`,:ref:`Matrix Expressions`
+:func:`mulTransposed`,:func:`transform`,:ref:`MatrixExpressions`
 
 .. index:: getConvertElem
 
+.. _getConvertItem:
+
 getConvertElem
-------------------
+--------------
+
 .. c:function:: ConvertData getConvertElem(int fromType, int toType)
 
 .. c:function:: ConvertScaleData getConvertScaleElem(int fromType, int toType)
 
 .. c:function:: typedef void (*ConvertData)(const void* from, void* to, int cn)
 
-.. c:function:: typedef void (*ConvertScaleData)(const void* from, void* to,                                 int cn, double alpha, double beta)
+.. c:function:: typedef void (*ConvertScaleData)(const void* from, void* to, int cn, double alpha, double beta)
 
     Returns conversion function for a single pixel
 
@@ -1142,8 +1167,11 @@ See also:
 
 .. index:: getOptimalDFTSize
 
+.. _getOptimalDFTSize:
+
 getOptimalDFTSize
----------------------
+-----------------
+
 .. c:function:: int getOptimalDFTSize(int vecsize)
 
     Returns optimal DFT size for a given vector size.
@@ -1167,9 +1195,12 @@ See also:
 
 .. index:: idct
 
+.. _idct:
+
 idct
---------
-.. c:function:: void idct(const Mat\& src, Mat\& dst, int flags=0)
+----
+
+.. c:function:: void idct(const Mat& src, Mat& dst, int flags=0)
 
     Computes inverse Discrete Cosine Transform of a 1D or 2D array
 
@@ -1185,8 +1216,11 @@ See also: :func:`dct`,:func:`dft`,:func:`idft`,:func:`getOptimalDFTSize`
 
 .. index:: idft
 
+.. _idft:
+
 idft
---------
+----
+
 .. c:function:: void idft(const Mat& src, Mat& dst, int flags=0, int outputRows=0)
 
     Computes inverse Discrete Fourier Transform of a 1D or 2D array
@@ -1209,15 +1243,18 @@ See also: :func:`dft`,:func:`dct`,:func:`idct`,:func:`mulSpectrums`,:func:`getOp
 
 .. index:: inRange
 
+.. _inRange:
+
 inRange
------------
-.. c:function:: void inRange(const Mat\& src, const Mat\& lowerb,             const Mat\& upperb, Mat\& dst)
+-------
 
-.. c:function:: void inRange(const Mat\& src, const Scalar\& lowerb,             const Scalar\& upperb, Mat\& dst)
+.. c:function:: void inRange(const Mat& src, const Mat& lowerb, const Mat& upperb, Mat& dst)
 
-.. c:function:: void inRange(const MatND\& src, const MatND\& lowerb,             const MatND\& upperb, MatND\& dst)
+.. c:function:: void inRange(const Mat& src, const Scalar& lowerb, const Scalar& upperb, Mat& dst)
 
-.. c:function:: void inRange(const MatND\& src, const Scalar\& lowerb,             const Scalar\& upperb, MatND\& dst)
+.. c:function:: void inRange(const MatND& src, const MatND& lowerb, const MatND& upperb, MatND& dst)
+
+.. c:function:: void inRange(const MatND& src, const Scalar& lowerb, const Scalar& upperb, MatND& dst)
 
     Checks if array elements lie between the elements of two other arrays.
 
@@ -1245,9 +1282,12 @@ for two-channel arrays and so forth. ``dst`` (I) is set to 255 (all ``1`` -bits)
 
 .. index:: invert
 
+.. _invert:
+
 invert
-----------
-.. c:function:: double invert(const Mat\& src, Mat\& dst, int method=DECOMP_LU)
+------
+
+.. c:function:: double invert(const Mat& src, Mat& dst, int method=DECOMP_LU)
 
     Finds the inverse or pseudo-inverse of a matrix
 
@@ -1278,11 +1318,14 @@ See also:
 
 .. index:: log
 
+.. _log:
+
 log
--------
-.. c:function:: void log(const Mat\& src, Mat\& dst)
+---
 
-.. c:function:: void log(const MatND\& src, MatND\& dst)
+.. c:function:: void log(const Mat& src, Mat& dst)
+
+.. c:function:: void log(const MatND& src, MatND& dst)
 
     Calculates the natural logarithm of every array element.
 
@@ -1307,9 +1350,12 @@ See also:
 
 .. index:: LUT
 
+.. _LUT:
+
 LUT
--------
-.. c:function:: void LUT(const Mat\& src, const Mat\& lut, Mat\& dst)
+---
+
+.. c:function:: void LUT(const Mat& src, const Mat& lut, Mat& dst)
 
     Performs a look-up table transform of an array.
 
@@ -1336,9 +1382,12 @@ See also:
 
 .. index:: magnitude
 
+.. _magnitude:
+
 magnitude
--------------
-.. c:function:: void magnitude(const Mat\& x, const Mat\& y, Mat\& magnitude)
+---------
+
+.. c:function:: void magnitude(const Mat& x, const Mat& y, Mat& magnitude)
 
     Calculates magnitude of 2D vectors.
 
@@ -1359,9 +1408,12 @@ See also:
 
 .. index:: Mahalanobis
 
+.. _Mahalanobis:
+
 Mahalanobis
----------------
-.. c:function:: double Mahalanobis(const Mat\& vec1, const Mat\& vec2,  const Mat\& icovar)
+-----------
+
+.. c:function:: double Mahalanobis(const Mat& vec1, const Mat& vec2, const Mat& icovar)
 
     Calculates the Mahalanobis distance between two vectors.
 
@@ -1383,21 +1435,24 @@ The covariance matrix may be calculated using the
 
 .. index:: max
 
+.. _max:
+
 max
--------
-.. c:function:: Mat_Expr<...> max(const Mat\& src1, const Mat\& src2)
+---
+
+.. c:function:: Mat_Expr<...> max(const Mat& src1, const Mat& src2)
 
-.. c:function:: Mat_Expr<...> max(const Mat\& src1, double value)
+.. c:function:: Mat_Expr<...> max(const Mat& src1, double value)
 
-.. c:function:: Mat_Expr<...> max(double value, const Mat\& src1)
+.. c:function:: Mat_Expr<...> max(double value, const Mat& src1)
 
-.. c:function:: void max(const Mat\& src1, const Mat\& src2, Mat\& dst)
+.. c:function:: void max(const Mat& src1, const Mat& src2, Mat& dst)
 
-.. c:function:: void max(const Mat\& src1, double value, Mat\& dst)
+.. c:function:: void max(const Mat& src1, double value, Mat& dst)
 
-.. c:function:: void max(const MatND\& src1, const MatND\& src2, MatND\& dst)
+.. c:function:: void max(const MatND& src1, const MatND& src2, MatND& dst)
 
-.. c:function:: void max(const MatND\& src1, double value, MatND\& dst)
+.. c:function:: void max(const MatND& src1, double value, MatND& dst)
 
     Calculates per-element maximum of two arrays or array and a scalar
 
@@ -1413,33 +1468,36 @@ The functions ``max`` compute per-element maximum of two arrays:
 
 .. math::
 
-    \texttt{dst} (I)= \max ( \texttt{src1} (I),  \texttt{src2} (I))
+    \texttt{dst} (I)= \max ( \texttt{src1} (I), \texttt{src2} (I))
 
 or array and a scalar:
 
 .. math::
 
-    \texttt{dst} (I)= \max ( \texttt{src1} (I),  \texttt{value} )
+    \texttt{dst} (I)= \max ( \texttt{src1} (I), \texttt{value} )
 
 In the second variant, when the source array is multi-channel, each channel is compared with ``value`` independently.
 
 The first 3 variants of the function listed above are actually a part of
-:ref:`Matrix Expressions` , they return the expression object that can be further transformed, or assigned to a matrix, or passed to a function etc.
+:ref:`MatrixExpressions` , they return the expression object that can be further transformed, or assigned to a matrix, or passed to a function etc.
 
 See also:
-:func:`min`,:func:`compare`,:func:`inRange`,:func:`minMaxLoc`,:ref:`Matrix Expressions`
+:func:`min`,:func:`compare`,:func:`inRange`,:func:`minMaxLoc`,:ref:`MatrixExpressions`
 
 .. index:: mean
 
+.. _mean:
+
 mean
---------
-.. c:function:: Scalar mean(const Mat\& mtx)
+----
 
-.. c:function:: Scalar mean(const Mat\& mtx, const Mat\& mask)
+.. c:function:: Scalar mean(const Mat& mtx)
 
-.. c:function:: Scalar mean(const MatND\& mtx)
+.. c:function:: Scalar mean(const Mat& mtx, const Mat& mask)
 
-.. c:function:: Scalar mean(const MatND\& mtx, const MatND\& mask)
+.. c:function:: Scalar mean(const MatND& mtx)
+
+.. c:function:: Scalar mean(const MatND& mtx, const MatND& mask)
 
     Calculates average (mean) of array elements
 
@@ -1460,11 +1518,14 @@ See also:
 
 .. index:: meanStdDev
 
+.. _meanStdDev:
+
 meanStdDev
---------------
-.. c:function:: void meanStdDev(const Mat\& mtx, Scalar\& mean,  Scalar\& stddev, const Mat\& mask=Mat())
+----------
+
+.. c:function:: void meanStdDev(const Mat& mtx, Scalar& mean, Scalar& stddev, const Mat& mask=Mat())
 
-.. c:function:: void meanStdDev(const MatND\& mtx, Scalar\& mean,  Scalar\& stddev, const MatND\& mask=MatND())
+.. c:function:: void meanStdDev(const MatND& mtx, Scalar& mean, Scalar& stddev, const MatND& mask=MatND())
 
     Calculates mean and standard deviation of array elements
 
@@ -1480,7 +1541,7 @@ The functions ``meanStdDev`` compute the mean and the standard deviation ``M`` o
 
 .. math::
 
-    \begin{array}{l} N =  \sum _{I,  \texttt{mask} (I)  \ne 0} 1 \\ \texttt{mean} _c =  \frac{\sum_{ I: \; \texttt{mask}(I) \ne 0} \texttt{src} (I)_c}{N} \\ \texttt{stddev} _c =  \sqrt{\sum_{ I: \; \texttt{mask}(I) \ne 0} \left ( \texttt{src} (I)_c -  \texttt{mean} _c \right )^2} \end{array}
+    \begin{array}{l} N =  \sum _{I, \texttt{mask} (I)  \ne 0} 1 \\ \texttt{mean} _c =  \frac{\sum_{ I: \; \texttt{mask}(I) \ne 0} \texttt{src} (I)_c}{N} \\ \texttt{stddev} _c =  \sqrt{\sum_{ I: \; \texttt{mask}(I) \ne 0} \left ( \texttt{src} (I)_c -  \texttt{mean} _c \right )^2} \end{array}
 
 When all the mask elements are 0's, the functions return ``mean=stddev=Scalar::all(0)`` .
 Note that the computed standard deviation is only the diagonal of the complete normalized covariance matrix. If the full matrix is needed, you can reshape the multi-channel array
@@ -1493,15 +1554,18 @@ See also:
 
 .. index:: merge
 
+.. _merge:
+
 merge
----------
-.. c:function:: void merge(const Mat* mv, size_t count, Mat\& dst)
+-----
 
-.. c:function:: void merge(const vector<Mat>\& mv, Mat\& dst)
+.. c:function:: void merge(const Mat* mv, size_t count, Mat& dst)
 
-.. c:function:: void merge(const MatND* mv, size_t count, MatND\& dst)
+.. c:function:: void merge(const vector<Mat>& mv, Mat& dst)
 
-.. c:function:: void merge(const vector<MatND>\& mv, MatND\& dst)
+.. c:function:: void merge(const MatND* mv, size_t count, MatND& dst)
+
+.. c:function:: void merge(const vector<MatND>& mv, MatND& dst)
 
     Composes a multi-channel array from several single-channel arrays.
 
@@ -1524,21 +1588,24 @@ The function
 
 .. index:: min
 
+.. _min:
+
 min
--------
-.. c:function:: Mat_Expr<...> min(const Mat\& src1, const Mat\& src2)
+---
 
-.. c:function:: Mat_Expr<...> min(const Mat\& src1, double value)
+.. c:function:: Mat_Expr<...> min(const Mat& src1, const Mat& src2)
 
-.. c:function:: Mat_Expr<...> min(double value, const Mat\& src1)
+.. c:function:: Mat_Expr<...> min(const Mat& src1, double value)
 
-.. c:function:: void min(const Mat\& src1, const Mat\& src2, Mat\& dst)
+.. c:function:: Mat_Expr<...> min(double value, const Mat& src1)
 
-.. c:function:: void min(const Mat\& src1, double value, Mat\& dst)
+.. c:function:: void min(const Mat& src1, const Mat& src2, Mat& dst)
 
-.. c:function:: void min(const MatND\& src1, const MatND\& src2, MatND\& dst)
+.. c:function:: void min(const Mat& src1, double value, Mat& dst)
 
-.. c:function:: void min(const MatND\& src1, double value, MatND\& dst)
+.. c:function:: void min(const MatND& src1, const MatND& src2, MatND& dst)
+
+.. c:function:: void min(const MatND& src1, double value, MatND& dst)
 
     Calculates per-element minimum of two arrays or array and a scalar
 
@@ -1554,31 +1621,34 @@ The functions ``min`` compute per-element minimum of two arrays:
 
 .. math::
 
-    \texttt{dst} (I)= \min ( \texttt{src1} (I),  \texttt{src2} (I))
+    \texttt{dst} (I)= \min ( \texttt{src1} (I), \texttt{src2} (I))
 
 or array and a scalar:
 
 .. math::
 
-    \texttt{dst} (I)= \min ( \texttt{src1} (I),  \texttt{value} )
+    \texttt{dst} (I)= \min ( \texttt{src1} (I), \texttt{value} )
 
 In the second variant, when the source array is multi-channel, each channel is compared with ``value`` independently.
 
 The first 3 variants of the function listed above are actually a part of
-:ref:`Matrix Expressions` , they return the expression object that can be further transformed, or assigned to a matrix, or passed to a function etc.
+:ref:`MatrixExpressions` , they return the expression object that can be further transformed, or assigned to a matrix, or passed to a function etc.
 
 See also:
-:func:`max`,:func:`compare`,:func:`inRange`,:func:`minMaxLoc`,:ref:`Matrix Expressions`
+:func:`max`,:func:`compare`,:func:`inRange`,:func:`minMaxLoc`,:ref:`MatrixExpressions`
 
 .. index:: minMaxLoc
 
+.. _minMaxLoc:
+
 minMaxLoc
--------------
-.. c:function:: void minMaxLoc(const Mat\& src, double* minVal,               double* maxVal=0, Point* minLoc=0,               Point* maxLoc=0, const Mat\& mask=Mat())
+---------
+
+.. c:function:: void minMaxLoc(const Mat& src, double* minVal, double* maxVal=0, Point* minLoc=0, Point* maxLoc=0, const Mat& mask=Mat())
 
-.. c:function:: void minMaxLoc(const MatND\& src, double* minVal,               double* maxVal, int* minIdx=0, int* maxIdx=0,               const MatND\& mask=MatND())
+.. c:function:: void minMaxLoc(const MatND& src, double* minVal, double* maxVal, int* minIdx=0, int* maxIdx=0, const MatND& mask=MatND())
 
-.. c:function:: void minMaxLoc(const SparseMat\& src, double* minVal,               double* maxVal, int* minIdx=0, int* maxIdx=0)
+.. c:function:: void minMaxLoc(const SparseMat& src, double* minVal, double* maxVal, int* minIdx=0, int* maxIdx=0)
 
     Finds global minimum and maximum in a whole array or sub-array
 
@@ -1615,15 +1685,18 @@ See also:
 
 .. index:: mixChannels
 
+.. _mixChannels:
+
 mixChannels
----------------
-.. c:function:: void mixChannels(const Mat* srcv, int nsrc, Mat* dstv, int ndst,                 const int* fromTo, size_t npairs)
+-----------
+
+.. c:function:: void mixChannels(const Mat* srcv, int nsrc, Mat* dstv, int ndst, const int* fromTo, size_t npairs)
 
-.. c:function:: void mixChannels(const MatND* srcv, int nsrc, MatND* dstv, int ndst,                 const int* fromTo, size_t npairs)
+.. c:function:: void mixChannels(const MatND* srcv, int nsrc, MatND* dstv, int ndst, const int* fromTo, size_t npairs)
 
-.. c:function:: void mixChannels(const vector<Mat>\& srcv, vector<Mat>\& dstv,                 const int* fromTo, int npairs)
+.. c:function:: void mixChannels(const vector<Mat>& srcv, vector<Mat>& dstv, const int* fromTo, int npairs)
 
-.. c:function:: void mixChannels(const vector<MatND>\& srcv, vector<MatND>\& dstv,                 const int* fromTo, int npairs)
+.. c:function:: void mixChannels(const vector<MatND>& srcv, vector<MatND>& dstv, const int* fromTo, int npairs)
 
     Copies specified channels from input arrays to the specified channels of output arrays
 
@@ -1656,7 +1729,7 @@ BGR (i.e. with R and B channels swapped) and separate alpha channel image: ::
     Mat out[] = { bgr, alpha };
     // rgba[0] -> bgr[2], rgba[1] -> bgr[1],
     // rgba[2] -> bgr[0], rgba[3] -> alpha[0]
-    int from_to[] = { 0,2,  1,1,  2,0,  3,3 };
+    int from_to[] = { 0,2, 1,1, 2,0, 3,3 };
     mixChannels( &rgba, 1, out, 2, from_to, 4 );
 
 
@@ -1668,9 +1741,12 @@ See also:
 
 .. index:: mulSpectrums
 
+.. _mulSpectrums:
+
 mulSpectrums
-----------------
-.. c:function:: void mulSpectrums(const Mat\& src1, const Mat\& src2, Mat\& dst,                  int flags, bool conj=false)
+------------
+
+.. c:function:: void mulSpectrums(const Mat& src1, const Mat& src2, Mat& dst, int flags, bool conj=false)
 
     Performs per-element multiplication of two Fourier spectrums.
 
@@ -1693,11 +1769,14 @@ The function, together with
 
 .. index:: multiply
 
+.. _multiply:
+
 multiply
-------------
-.. c:function:: void multiply(const Mat\& src1, const Mat\& src2,  Mat\& dst, double scale=1)
+--------
+
+.. c:function:: void multiply(const Mat& src1, const Mat& src2, Mat& dst, double scale=1)
 
-.. c:function:: void multiply(const MatND\& src1, const MatND\& src2,  MatND\& dst, double scale=1)
+.. c:function:: void multiply(const MatND& src1, const MatND& src2, MatND& dst, double scale=1)
 
     Calculates the per-element scaled product of two arrays
 
@@ -1716,20 +1795,23 @@ The function ``multiply`` calculates the per-element product of two arrays:
     \texttt{dst} (I)= \texttt{saturate} ( \texttt{scale} \cdot \texttt{src1} (I)  \cdot \texttt{src2} (I))
 
 There is also
-:ref:`Matrix Expressions` -friendly variant of the first function, see
+:ref:`MatrixExpressions` -friendly variant of the first function, see
 :func:`Mat::mul` .
 
 If you are looking for a matrix product, not per-element product, see
 :func:`gemm` .
 
 See also:
-:func:`add`,:func:`substract`,:func:`divide`,:ref:`Matrix Expressions`,:func:`scaleAdd`,:func:`addWeighted`,:func:`accumulate`,:func:`accumulateProduct`,:func:`accumulateSquare`,:func:`Mat::convertTo`
+:func:`add`,:func:`substract`,:func:`divide`,:ref:`MatrixExpressions`,:func:`scaleAdd`,:func:`addWeighted`,:func:`accumulate`,:func:`accumulateProduct`,:func:`accumulateSquare`,:func:`Mat::convertTo`
 
 .. index:: mulTransposed
 
+.. mulTransposed:
+
 mulTransposed
------------------
-.. c:function:: void mulTransposed( const Mat\& src, Mat\& dst, bool aTa,                    const Mat\& delta=Mat(),                    double scale=1, int rtype=-1 )
+-------------
+
+.. c:function:: void mulTransposed( const Mat& src, Mat& dst, bool aTa, const Mat& delta=Mat(), double scale=1, int rtype=-1 )
 
     Calculates the product of a matrix and its transposition.
 
@@ -1766,21 +1848,24 @@ See also:
 
 .. index:: norm
 
+.. _norm:
+
 norm
---------
-.. c:function:: double norm(const Mat\& src1, int normType=NORM_L2)
+----
+
+.. c:function:: double norm(const Mat& src1, int normType=NORM_L2)
 
-.. c:function:: double norm(const Mat\& src1, const Mat\& src2, int normType=NORM_L2)
+.. c:function:: double norm(const Mat& src1, const Mat& src2, int normType=NORM_L2)
 
-.. c:function:: double norm(const Mat\& src1, int normType, const Mat\& mask)
+.. c:function:: double norm(const Mat& src1, int normType, const Mat& mask)
 
-.. c:function:: double norm(const Mat\& src1, const Mat\& src2,  int normType, const Mat\& mask)
+.. c:function:: double norm(const Mat& src1, const Mat& src2, int normType, const Mat& mask)
 
-.. c:function:: double norm(const MatND\& src1, int normType=NORM_L2,  const MatND\& mask=MatND())
+.. c:function:: double norm(const MatND& src1, int normType=NORM_L2, const MatND& mask=MatND())
 
-.. c:function:: double norm(const MatND\& src1, const MatND\& src2,            int normType=NORM_L2, const MatND\& mask=MatND())
+.. c:function:: double norm(const MatND& src1, const MatND& src2, int normType=NORM_L2, const MatND& mask=MatND())
 
-.. c:function:: double norm( const SparseMat\& src, int normType )
+.. c:function:: double norm( const SparseMat& src, int normType )
 
     Calculates absolute array norm, absolute difference norm, or relative difference norm.
 
@@ -1824,13 +1909,16 @@ A multiple-channel source arrays are treated as a single-channel, that is, the r
 
 .. index:: normalize
 
+.. _normalize:
+
 normalize
--------------
-.. c:function:: void normalize( const Mat\& src, Mat\& dst,  double alpha=1, double beta=0,                int normType=NORM_L2, int rtype=-1,  const Mat\& mask=Mat())
+---------
+
+.. c:function:: void normalize( const Mat& src, Mat& dst, double alpha=1, double beta=0, int normType=NORM_L2, int rtype=-1, const Mat& mask=Mat())
 
-.. c:function:: void normalize( const MatND\& src, MatND\& dst,  double alpha=1, double beta=0,                int normType=NORM_L2, int rtype=-1,  const MatND\& mask=MatND())
+.. c:function:: void normalize( const MatND& src, MatND& dst, double alpha=1, double beta=0, int normType=NORM_L2, int rtype=-1, const MatND& mask=MatND())
 
-.. c:function:: void normalize( const SparseMat\& src, SparseMat\& dst,  double alpha, int normType )
+.. c:function:: void normalize( const SparseMat& src, SparseMat& dst, double alpha, int normType )
 
     Normalizes array's norm or the range
 
@@ -1875,6 +1963,8 @@ See also:
 
 .. index:: PCA
 
+.. _PCA:
+
 PCA
 ---
 .. c:type:: PCA
@@ -1951,11 +2041,13 @@ See also:
 
 .. index:: PCA::PCA
 
+.. _PCA::PCA:
+
 PCA::PCA
 ------------
 .. c:function:: PCA::PCA()
 
-.. c:function:: PCA::PCA(const Mat\& data, const Mat\& mean, int flags, int maxComponents=0)
+.. c:function:: PCA::PCA(const Mat& data, const Mat& mean, int flags, int maxComponents=0)
 
     PCA constructors
 
@@ -1976,9 +2068,12 @@ The default constructor initializes empty PCA structure. The second constructor
 
 .. index:: PCA::operator ()
 
+.. _PCA::operator ():
+
 PCA::operator ()
---------------------
-.. c:function:: PCA\& PCA::operator()(const Mat\& data, const Mat\& mean, int flags, int maxComponents=0)
+----------------
+
+.. c:function:: PCA& PCA::operator()(const Mat& data, const Mat& mean, int flags, int maxComponents=0)
 
     Performs Principal Component Analysis of the supplied dataset.
 
@@ -2000,11 +2095,14 @@ The computed eigenvalues are sorted from the largest to the smallest and the cor
 
 .. index:: PCA::project
 
+.. _PCA::project:
+
 PCA::project
-----------------
-.. c:function:: Mat PCA::project(const Mat\& vec) const
+------------
+
+.. c:function:: Mat PCA::project(const Mat& vec) const
 
-.. c:function:: void PCA::project(const Mat\& vec, Mat\& result) const
+.. c:function:: void PCA::project(const Mat& vec, Mat& result) const
 
     Project vector(s) to the principal component subspace
 
@@ -2016,11 +2114,14 @@ The methods project one or more vectors to the principal component subspace, whe
 
 .. index:: PCA::backProject
 
+.. _PCA::backProject:
+
 PCA::backProject
---------------------
-.. c:function:: Mat PCA::backProject(const Mat\& vec) const
+----------------
 
-.. c:function:: void PCA::backProject(const Mat\& vec, Mat\& result) const
+.. c:function:: Mat PCA::backProject(const Mat& vec) const
+
+.. c:function:: void PCA::backProject(const Mat& vec, Mat& result) const
 
     Reconstruct vectors from their PC projections.
 
@@ -2033,9 +2134,11 @@ The methods are inverse operations to
 
 .. index:: perspectiveTransform
 
+.. _perspectiveTransform:
+
 perspectiveTransform
-------------------------
-.. c:function:: void perspectiveTransform(const Mat\& src,  Mat\& dst, const Mat\& mtx )
+--------------------
+.. c:function:: void perspectiveTransform(const Mat& src, Mat& dst, const Mat& mtx )
 
     Performs perspective matrix transformation of vectors.
 
@@ -2075,9 +2178,12 @@ See also:
 
 .. index:: phase
 
+.. _phase:
+
 phase
----------
-.. c:function:: void phase(const Mat\& x, const Mat\& y, Mat\& angle,           bool angleInDegrees=false)
+-----
+
+.. c:function:: void phase(const Mat& x, const Mat& y, Mat& angle, bool angleInDegrees=false)
 
     Calculates the rotation angle of 2d vectors
 
@@ -2093,7 +2199,7 @@ The function ``phase`` computes the rotation angle of each 2D vector that is for
 
 .. math::
 
-    \texttt{angle} (I) =  \texttt{atan2} ( \texttt{y} (I),  \texttt{x} (I))
+    \texttt{angle} (I) =  \texttt{atan2} ( \texttt{y} (I), \texttt{x} (I))
 
 The angle estimation accuracy is
 :math:`\sim\,0.3^\circ` , when ``x(I)=y(I)=0`` , the corresponding ``angle`` (I) is set to
@@ -2103,9 +2209,12 @@ See also:
 
 .. index:: polarToCart
 
+.. _polarToCart:
+
 polarToCart
----------------
-.. c:function:: void polarToCart(const Mat\& magnitude, const Mat\& angle,                 Mat\& x, Mat\& y, bool angleInDegrees=false)
+-----------
+
+.. c:function:: void polarToCart(const Mat& magnitude, const Mat& angle, Mat& x, Mat& y, bool angleInDegrees=false)
 
     Computes x and y coordinates of 2D vectors from their magnitude and angle.
 
@@ -2133,11 +2242,14 @@ See also:
 
 .. index:: pow
 
+.. _pow:
+
 pow
--------
-.. c:function:: void pow(const Mat\& src, double p, Mat\& dst)
+---
+
+.. c:function:: void pow(const Mat& src, double p, Mat& dst)
 
-.. c:function:: void pow(const MatND\& src, double p, MatND\& dst)
+.. c:function:: void pow(const MatND& src, double p, MatND& dst)
 
     Raises every array element to a power.
 
@@ -2163,7 +2275,13 @@ That is, for a non-integer power exponent the absolute values of input array ele
 For some values of ``p`` , such as integer values, 0.5, and -0.5, specialized faster algorithms are used.
 
 See also:
-:func:`sqrt`,:func:`exp`,:func:`log`,:func:`cartToPolar`,:func:`polarToCart` RNG
+:func:`sqrt`,:func:`exp`,:func:`log`,:func:`cartToPolar`,:func:`polarToCart`
+
+.. index:: RNG
+
+.. _RNG:
+
+RNG
 ---
 
 Random number generator class. ::
@@ -2217,6 +2335,8 @@ http://en.wikipedia.org/wiki/Ziggurat_algorithm
 
 .. index:: RNG::RNG
 
+.. _RNG::RNG:
+
 RNG::RNG
 ------------
 .. c:function:: RNG::RNG()
@@ -2231,6 +2351,8 @@ These are the RNG constructors. The first form sets the state to some pre-define
 
 .. index:: RNG::next
 
+.. _RNG::next:
+
 RNG::next
 -------------
 .. c:function:: unsigned RNG::next()
@@ -2241,9 +2363,24 @@ The method updates the state using MWC algorithm and returns the next 32-bit ran
 
 .. index:: RNG::operator T
 
+.. _RNG::operator T:
+
 RNG::operator T
--------------------
-.. c:function:: RNG::operator uchar() RNG::operator schar() RNG::operator ushort() RNG::operator short() RNG::operator unsigned() RNG::operator int() RNG::operator float() RNG::operator double()
+---------------
+
+.. cpp:function:: RNG::operator uchar()
+
+.. cpp:function:: RNG::operator schar()
+
+.. cpp:function:: RNG::operator ushort()
+
+.. cpp:function:: RNG::operator short()
+
+.. cpp:function:: RNG::operator int()
+
+.. cpp:function:: RNG::operator float()
+
+.. cpp:function:: RNG::operator double()
 
     Returns the next random number of the specified type
 
@@ -2251,6 +2388,8 @@ Each of the methods updates the state using MWC algorithm and returns the next r
 
 .. index:: RNG::operator ()
 
+.. _RNG::operator ():
+
 RNG::operator ()
 --------------------
 .. c:function:: unsigned RNG::operator ()()
@@ -2266,6 +2405,8 @@ The methods transforms the state using MWC algorithm and returns the next random
 
 .. index:: RNG::uniform
 
+.. _RNG::uniform:
+
 RNG::uniform
 ----------------
 .. c:function:: int RNG::uniform(int a, int b)
@@ -2305,6 +2446,8 @@ That is, the compiler does not take into account type of the variable that you a
 
 .. index:: RNG::gaussian
 
+.. _RNG::gaussian:
+
 RNG::gaussian
 -----------------
 .. c:function:: double RNG::gaussian(double sigma)
@@ -2317,17 +2460,19 @@ The methods transforms the state using MWC algorithm and returns the next random
 
 .. index:: RNG::fill
 
+.. _RNG::fill:
+
 RNG::fill
 -------------
-.. c:function:: void RNG::fill( Mat\& mat, int distType, const Scalar\& a, const Scalar\& b )
+.. c:function:: void RNG::fill( Mat& mat, int distType, const Scalar& a, const Scalar& b )
 
-.. c:function:: void RNG::fill( MatND\& mat, int distType, const Scalar\& a, const Scalar\& b )
+.. c:function:: void RNG::fill( MatND& mat, int distType, const Scalar& a, const Scalar& b )
 
     Fill arrays with random numbers
 
     :param mat: 2D or N-dimensional matrix. Currently matrices with more than 4 channels are not supported by the methods. Use  :func:`reshape`  as a possible workaround.
 
-    :param distType: The distribution type,  ``RNG::UNIFORM``  or  ``RNG::NORMAL``
+    :param distType: The distribution type, ``RNG::UNIFORM``  or  ``RNG::NORMAL``
     
     :param a: The first distribution parameter. In the case of uniform distribution this is inclusive lower boundary. In the case of normal distribution this is mean value.
 
@@ -2339,11 +2484,14 @@ Each of the methods fills the matrix with the random values from the specified d
 
 .. index:: randu
 
+.. _randu:
+
 randu
----------
+-----
+
 .. c:function:: template<typename _Tp> _Tp randu()
 
-.. c:function:: void randu(Mat\& mtx, const Scalar\& low, const Scalar\& high)
+.. c:function:: void randu(Mat& mtx, const Scalar& low, const Scalar& high)
 
     Generates a single uniformly-distributed random number or array of random numbers
 
@@ -2367,9 +2515,12 @@ See also:
 
 .. index:: randn
 
+.. _randn:
+
 randn
----------
-.. c:function:: void randn(Mat\& mtx, const Scalar\& mean, const Scalar\& stddev)
+-----
+
+.. c:function:: void randn(Mat& mtx, const Scalar& mean, const Scalar& stddev)
 
     Fills array with normally distributed random numbers
 
@@ -2387,9 +2538,12 @@ See also:
 
 .. index:: randShuffle
 
+.. randShuffle:
+
 randShuffle
----------------
-.. c:function:: void randShuffle(Mat\& mtx, double iterFactor=1., RNG* rng=0)
+-----------
+
+.. c:function:: void randShuffle(Mat& mtx, double iterFactor=1., RNG* rng=0)
 
     Shuffles the array elements randomly
 
@@ -2397,16 +2551,19 @@ randShuffle
 
     :param iterFactor: The scale factor that determines the number of random swap operations. See the discussion
 
-    :param rng: The optional random number generator used for shuffling. If it is zero,  :func:`theRNG` () is used instead
+    :param rng: The optional random number generator used for shuffling. If it is zero, :func:`theRNG` () is used instead
 
 The function ``randShuffle`` shuffles the specified 1D array by randomly choosing pairs of elements and swapping them. The number of such swap operations will be ``mtx.rows*mtx.cols*iterFactor`` See also:
 :func:`RNG`,:func:`sort`
 
 .. index:: reduce
 
+.. _reduce:
+
 reduce
-----------
-.. c:function:: void reduce(const Mat\& mtx, Mat\& vec,  int dim, int reduceOp, int dtype=-1)
+------
+
+.. c:function:: void reduce(const Mat& mtx, Mat& vec, int dim, int reduceOp, int dtype=-1)
 
     Reduces a matrix to a vector
 
@@ -2430,16 +2587,18 @@ reduce
     
 The function ``reduce`` reduces matrix to a vector by treating the matrix rows/columns as a set of 1D vectors and performing the specified operation on the vectors until a single row/column is obtained. For example, the function can be used to compute horizontal and vertical projections of an raster image. In the case of ``CV_REDUCE_SUM`` and ``CV_REDUCE_AVG`` the output may have a larger element bit-depth to preserve accuracy. And multi-channel arrays are also supported in these two reduction modes.
 
-See also:
-:func:`repeat`
+See also: :func:`repeat`
 
 .. index:: repeat
 
+.. _repeat:
+
 repeat
-----------
-.. c:function:: void repeat(const Mat\& src, int ny, int nx, Mat\& dst)
+------
 
-.. c:function:: Mat repeat(const Mat\& src, int ny, int nx)
+.. c:function:: void repeat(const Mat& src, int ny, int nx, Mat& dst)
+
+.. c:function:: Mat repeat(const Mat& src, int ny, int nx)
 
     Fill the destination array with repeated copies of the source array.
 
@@ -2459,13 +2618,16 @@ The functions
     \texttt{dst} _{ij}= \texttt{src} _{i \mod \texttt{src.rows} , \; j \mod \texttt{src.cols} }
 
 The second variant of the function is more convenient to use with
-:ref:`Matrix Expressions` See also:
-:func:`reduce`,:ref:`Matrix Expressions`
+:ref:`MatrixExpressions` See also:
+:func:`reduce`,:ref:`MatrixExpressions`
 
 .. index:: saturate_cast
 
+.. _saturate_cast_:
+
 saturate_cast
 -------------
+
 .. c:function:: template<typename _Tp> inline _Tp saturate_cast(unsigned char v)
 
 .. c:function:: template<typename _Tp> inline _Tp saturate_cast(signed char v)
@@ -2503,11 +2665,14 @@ See also:
 
 .. index:: scaleAdd
 
+.. _scaleAdd:
+
 scaleAdd
-------------
-.. c:function:: void scaleAdd(const Mat\& src1, double scale,  const Mat\& src2, Mat\& dst)
+--------
+
+.. c:function:: void scaleAdd(const Mat& src1, double scale, const Mat& src2, Mat& dst)
 
-.. c:function:: void scaleAdd(const MatND\& src1, double scale,  const MatND\& src2, MatND\& dst)
+.. c:function:: void scaleAdd(const MatND& src1, double scale, const MatND& src2, MatND& dst)
 
     Calculates the sum of a scaled array and another array.
 
@@ -2533,13 +2698,16 @@ The function can also be emulated with a matrix expression, for example: ::
 
 
 See also:
-:func:`add`,:func:`addWeighted`,:func:`subtract`,:func:`Mat::dot`,:func:`Mat::convertTo`,:ref:`Matrix Expressions`
+:func:`add`,:func:`addWeighted`,:func:`subtract`,:func:`Mat::dot`,:func:`Mat::convertTo`,:ref:`MatrixExpressions`
 
 .. index:: setIdentity
 
+.. _setIdentity:
+
 setIdentity
----------------
-.. c:function:: void setIdentity(Mat\& dst, const Scalar\& value=Scalar(1))
+-----------
+
+.. c:function:: void setIdentity(Mat& dst, const Scalar& value=Scalar(1))
 
     Initializes a scaled identity matrix
 
@@ -2561,12 +2729,16 @@ The function can also be emulated using the matrix initializers and the matrix e
 
 
 See also:
-:func:`Mat::zeros`,:func:`Mat::ones`,:ref:`Matrix Expressions`,:func:`Mat::setTo`,:func:`Mat::operator=`,
+:func:`Mat::zeros`,:func:`Mat::ones`,:ref:`MatrixExpressions`,:func:`Mat::setTo`,:func:`Mat::operator=`
+
 .. index:: solve
 
+.. _solve:
+
 solve
----------
-.. c:function:: bool solve(const Mat\& src1, const Mat\& src2,  Mat\& dst, int flags=DECOMP_LU)
+-----
+
+.. c:function:: bool solve(const Mat& src1, const Mat& src2, Mat& dst, int flags=DECOMP_LU)
 
     Solves one or more linear systems or least-squares problems.
 
@@ -2608,9 +2780,11 @@ See also:
 
 .. index:: solveCubic
 
+.. _solveCubic:
+
 solveCubic
 --------------
-.. c:function:: void solveCubic(const Mat\& coeffs, Mat\& roots)
+.. c:function:: void solveCubic(const Mat& coeffs, Mat& roots)
 
     Finds the real roots of a cubic equation.
 
@@ -2636,9 +2810,12 @@ The roots are stored to ``roots`` array.
 
 .. index:: solvePoly
 
+.. _solvePoly:
+
 solvePoly
--------------
-.. c:function:: void solvePoly(const Mat\& coeffs, Mat\& roots,  int maxIters=20, int fig=100)
+---------
+
+.. c:function:: void solvePoly(const Mat& coeffs, Mat& roots, int maxIters=20, int fig=100)
 
     Finds the real or complex roots of a polynomial equation
 
@@ -2658,9 +2835,12 @@ The function ``solvePoly`` finds real and complex roots of a polynomial equation
 
 .. index:: sort
 
+.. _sort:
+
 sort
---------
-.. c:function:: void sort(const Mat\& src, Mat\& dst, int flags)
+----
+
+.. c:function:: void sort(const Mat& src, Mat& dst, int flags)
 
     Sorts each row or each column of a matrix
 
@@ -2685,9 +2865,12 @@ See also:
 
 .. index:: sortIdx
 
+.. _sortIdx:
+
 sortIdx
------------
-.. c:function:: void sortIdx(const Mat\& src, Mat\& dst, int flags)
+-------
+
+.. c:function:: void sortIdx(const Mat& src, Mat& dst, int flags)
 
     Sorts each row or each column of a matrix
 
@@ -2719,15 +2902,18 @@ See also:
 
 .. index:: split
 
+.. _split:
+
 split
----------
-.. c:function:: void split(const Mat\& mtx, Mat* mv)
+-----
 
-.. c:function:: void split(const Mat\& mtx, vector<Mat>\& mv)
+.. c:function:: void split(const Mat& mtx, Mat* mv)
 
-.. c:function:: void split(const MatND\& mtx, MatND* mv)
+.. c:function:: void split(const Mat& mtx, vector<Mat>& mv)
 
-.. c:function:: void split(const MatND\& mtx, vector<MatND>\& mv)
+.. c:function:: void split(const MatND& mtx, MatND* mv)
+
+.. c:function:: void split(const MatND& mtx, vector<MatND>& mv)
 
     Divides multi-channel array into several single-channel arrays
 
@@ -2747,11 +2933,14 @@ If you need to extract a single-channel or do some other sophisticated channel p
 
 .. index:: sqrt
 
+.. _sqrt:
+
 sqrt
---------
-.. c:function:: void sqrt(const Mat\& src, Mat\& dst)
+----
+
+.. c:function:: void sqrt(const Mat& src, Mat& dst)
 
-.. c:function:: void sqrt(const MatND\& src, MatND\& dst)
+.. c:function:: void sqrt(const MatND& src, MatND& dst)
 
     Calculates square root of array elements
 
@@ -2766,23 +2955,26 @@ See also:
 
 .. index:: subtract
 
+.. _subtract:
+
 subtract
-------------
-.. c:function:: void subtract(const Mat\& src1, const Mat\& src2, Mat\& dst)
+--------
 
-.. c:function:: void subtract(const Mat\& src1, const Mat\& src2,  Mat\& dst, const Mat\& mask)
+.. c:function:: void subtract(const Mat& src1, const Mat& src2, Mat& dst)
 
-.. c:function:: void subtract(const Mat\& src1, const Scalar\& sc,  Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void subtract(const Mat& src1, const Mat& src2, Mat& dst, const Mat& mask)
 
-.. c:function:: void subtract(const Scalar\& sc, const Mat\& src2,  Mat\& dst, const Mat\& mask=Mat())
+.. c:function:: void subtract(const Mat& src1, const Scalar& sc, Mat& dst, const Mat& mask=Mat())
 
-.. c:function:: void subtract(const MatND\& src1, const MatND\& src2, MatND\& dst)
+.. c:function:: void subtract(const Scalar& sc, const Mat& src2, Mat& dst, const Mat& mask=Mat())
 
-.. c:function:: void subtract(const MatND\& src1, const MatND\& src2,  MatND\& dst, const MatND\& mask)
+.. c:function:: void subtract(const MatND& src1, const MatND& src2, MatND& dst)
 
-.. c:function:: void subtract(const MatND\& src1, const Scalar\& sc,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void subtract(const MatND& src1, const MatND& src2, MatND& dst, const MatND& mask)
 
-.. c:function:: void subtract(const Scalar\& sc, const MatND\& src2,  MatND\& dst, const MatND\& mask=MatND())
+.. c:function:: void subtract(const MatND& src1, const Scalar& sc, MatND& dst, const MatND& mask=MatND())
+
+.. c:function:: void subtract(const Scalar& sc, const MatND& src2, MatND& dst, const MatND& mask=MatND())
 
     Calculates per-element difference between two arrays or array and a scalar
 
@@ -2828,7 +3020,7 @@ The first function in the above list can be replaced with matrix expressions: ::
 
 
 See also:
-:func:`add`,:func:`addWeighted`,:func:`scaleAdd`,:func:`convertScale`,:ref:`Matrix Expressions`,.
+:func:`add`,:func:`addWeighted`,:func:`scaleAdd`,:func:`convertScale`,:ref:`MatrixExpressions`,.
 
 .. index:: SVD
 
@@ -2873,11 +3065,14 @@ See also:
 
 .. index:: SVD::SVD
 
+.. _SVD::SVD:
+
 SVD::SVD
-------------
+--------
+
 .. c:function:: SVD::SVD()
 
-.. c:function:: SVD::SVD( const Mat\& A, int flags=0 )
+.. c:function:: SVD::SVD( const Mat& A, int flags=0 )
 
     SVD constructors
 
@@ -2889,16 +3084,19 @@ SVD::SVD
 
         * **SVD::NO_UV** Indicates that only the vector of singular values  ``w``  is to be computed, while  ``u``  and  ``vt``  will be set to empty matrices
 
-        * **SVD::FULL_UV** When the matrix is not square, by default the algorithm produces  ``u``  and  ``vt``  matrices of sufficiently large size for the further  ``A``  reconstruction. If, however,  ``FULL_UV``  flag is specified,  ``u``  and  ``vt``  will be full-size square orthogonal matrices.
+        * **SVD::FULL_UV** When the matrix is not square, by default the algorithm produces  ``u``  and  ``vt``  matrices of sufficiently large size for the further  ``A``  reconstruction. If, however, ``FULL_UV``  flag is specified, ``u``  and  ``vt``  will be full-size square orthogonal matrices.
 
 The first constructor initializes empty ``SVD`` structure. The second constructor initializes empty ``SVD`` structure and then calls
 :func:`SVD::operator ()` .
 
 .. index:: SVD::operator ()
 
+.. _SVD::operator ():
+
 SVD::operator ()
---------------------
-.. c:function:: SVD\& SVD::operator ()( const Mat\& A, int flags=0 )
+----------------
+
+.. c:function:: SVD& SVD::operator ()( const Mat& A, int flags=0 )
 
     Performs SVD of a matrix
 
@@ -2910,16 +3108,19 @@ SVD::operator ()
 
         * **SVD::NO_UV** Only singular values are needed. The algorithm will not compute  ``u``  and  ``vt``  matrices
 
-        * **SVD::FULL_UV** When the matrix is not square, by default the algorithm produces  ``u``  and  ``vt``  matrices of sufficiently large size for the further  ``A``  reconstruction. If, however,  ``FULL_UV``  flag is specified,  ``u``  and  ``vt``  will be full-size square orthogonal matrices.
+        * **SVD::FULL_UV** When the matrix is not square, by default the algorithm produces  ``u``  and  ``vt``  matrices of sufficiently large size for the further  ``A``  reconstruction. If, however, ``FULL_UV``  flag is specified, ``u``  and  ``vt``  will be full-size square orthogonal matrices.
 
 The operator performs singular value decomposition of the supplied matrix. The ``u``,``vt`` and the vector of singular values ``w`` are stored in the structure. The same ``SVD`` structure can be reused many times with different matrices. Each time, if needed, the previous ``u``,``vt`` and ``w`` are reclaimed and the new matrices are created, which is all handled by
 :func:`Mat::create` .
 
 .. index:: SVD::solveZ
 
+.. _SVD::solveZ:
+
 SVD::solveZ
----------------
-.. c:function:: static void SVD::solveZ( const Mat\& A, Mat\& x )
+-----------
+
+.. c:function:: static void SVD::solveZ( const Mat& A, Mat& x )
 
     Solves under-determined singular linear system
 
@@ -2938,9 +3139,12 @@ of the under-determined system
 
 .. index:: SVD::backSubst
 
+.. _SVD::backSubst:
+
 SVD::backSubst
-------------------
-.. c:function:: void SVD::backSubst( const Mat\& rhs, Mat\& x ) const
+--------------
+
+.. c:function:: void SVD::backSubst( const Mat& rhs, Mat& x ) const
 
     Performs singular value back substitution
 
@@ -2959,11 +3163,14 @@ Using this technique you can either get a very accurate solution of convenient l
 
 .. index:: sum
 
+.. _sum:
+
 sum
--------
-.. c:function:: Scalar sum(const Mat\& mtx)
+---
 
-.. c:function:: Scalar sum(const MatND\& mtx)
+.. c:function:: Scalar sum(const Mat& mtx)
+
+.. c:function:: Scalar sum(const MatND& mtx)
 
     Calculates sum of array elements
 
@@ -2977,8 +3184,9 @@ See also:
 .. index:: theRNG
 
 theRNG
-----------
-.. c:function:: RNG\& theRNG()
+------
+
+.. c:function:: RNG& theRNG()
 
     Returns the default random number generator
 
@@ -2991,9 +3199,12 @@ See also:
 
 .. index:: trace
 
+.. _trace:
+
 trace
----------
-.. c:function:: Scalar trace(const Mat\& mtx)
+-----
+
+.. c:function:: Scalar trace(const Mat& mtx)
 
     Returns the trace of a matrix
 
@@ -3007,9 +3218,12 @@ The function ``trace`` returns the sum of the diagonal elements of the matrix ``
 
 .. index:: transform
 
+.. _transform:
+
 transform
--------------
-.. c:function:: void transform(const Mat\& src,  Mat\& dst, const Mat\& mtx )
+---------
+
+.. c:function:: void transform(const Mat& src, Mat& dst, const Mat& mtx )
 
     Performs matrix transformation of every array element.
 
@@ -3050,9 +3264,12 @@ See also:
 
 .. index:: transpose
 
+.. _transpose:
+
 transpose
--------------
-.. c:function:: void transpose(const Mat\& src, Mat\& dst)
+---------
+
+.. c:function:: void transpose(const Mat& src, Mat& dst)
 
     Transposes a matrix
 
@@ -3068,4 +3285,3 @@ The function :func:`transpose` transposes the matrix ``src`` :
 
 Note that no complex conjugation is done in the case of a complex
 matrix, it should be done separately if needed.
-
index e0b3fa9..9482327 100644 (file)
@@ -84,8 +84,6 @@ This is structure is similar to DevMem2D_but contains only pointer and row step
 
 .. index:: gpu::GpuMat
 
-.. gpu::GpuMat:
-
 gpu::GpuMat
 -----------
 .. c:type:: gpu::GpuMat
@@ -216,8 +214,6 @@ gpu::CudaMem::canMapHostMemory
 
 .. index:: gpu::Stream
 
-.. _gpu::Stream:
-
 gpu::Stream
 -----------
 .. c:type:: gpu::Stream
index 053ecdd..73c1f82 100644 (file)
@@ -126,13 +126,9 @@ See also:
 
 gpu::minMaxLoc
 ------------------
-.. c:function:: void gpu::minMaxLoc(const GpuMat\& src, double\* minVal, double* maxVal=0,
-   Point* minLoc=0, Point* maxLoc=0,
-   const GpuMat\& mask=GpuMat())
+.. c:function:: void gpu::minMaxLoc(const GpuMat& src, double* minVal, double* maxVal=0, Point* minLoc=0, Point* maxLoc=0, const GpuMat& mask=GpuMat())
 
-.. c:function:: void gpu::minMaxLoc(const GpuMat\& src, double* minVal, double* maxVal,
-   Point* minLoc, Point* maxLoc, const GpuMat\& mask,
-   GpuMat\& valbuf, GpuMat\& locbuf)
+.. c:function:: void gpu::minMaxLoc(const GpuMat& src, double* minVal, double* maxVal, Point* minLoc, Point* maxLoc, const GpuMat& mask, GpuMat& valbuf, GpuMat& locbuf)
 
     Finds global minimum and maximum matrix elements and returns their values with locations.
 
diff --git a/modules/gpu/doc/per_element_operations..rst b/modules/gpu/doc/per_element_operations..rst
deleted file mode 100644 (file)
index c52674c..0000000
+++ /dev/null
@@ -1,365 +0,0 @@
-Per-element Operations.
-=======================
-
-.. highlight:: cpp
-
-.. index:: gpu::add
-
-gpu::add
-------------
-.. c:function:: void gpu::add(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
-
-    Computes matrix-matrix or matrix-scalar sum.
-
-    :param a: First source matrix.  ``CV_8UC1`` ,  ``CV_8UC4`` ,  ``CV_32SC1``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destination matrix. Will have the same size and type as  ``a`` .
-
-.. c:function:: void gpu::add(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
-
-    * **a** Source matrix.  ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
-
-    * **b** Source scalar to be added to the source matrix.
-
-    * **c** Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`add` .
-
-.. index:: gpu::subtract
-
-gpu::subtract
------------------
-.. c:function:: void gpu::subtract(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
-
-    Subtracts matrix from another matrix (or scalar from matrix).
-
-    :param a: First source matrix.  ``CV_8UC1`` ,  ``CV_8UC4`` ,  ``CV_32SC1``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destination matrix. Will have the same size and type as  ``a`` .
-
-.. c:function:: void subtract(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
-
-    * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
-
-    * **b** Scalar to be subtracted from the source matrix elements.
-
-    * **c** Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`subtract` .
-
-.. index:: gpu::multiply
-
-gpu::multiply
------------------
-.. c:function:: void gpu::multiply(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
-
-    Computes per-element product of two matrices (or of matrix and scalar).
-
-    :param a: First source matrix.  ``CV_8UC1`` ,  ``CV_8UC4`` ,  ``CV_32SC1``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destionation matrix. Will have the same size and type as  ``a`` .
-
-.. c:function:: void multiply(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
-
-    * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
-
-    * **b** Scalar to be multiplied by.
-
-    * **c** Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`multiply` .
-
-.. index:: gpu::divide
-
-gpu::divide
----------------
-.. c:function:: void gpu::divide(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
-
-    Performs per-element division of two matrices (or division of matrix by scalar).
-
-    :param a: First source matrix.  ``CV_8UC1`` ,  ``CV_8UC4`` ,  ``CV_32SC1``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destionation matrix. Will have the same size and type as  ``a`` .
-
-.. c:function:: void divide(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
-
-    * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
-
-    * **b** Scalar to be divided by.
-
-    * **c** Destination matrix. Will have the same size and type as  ``a`` .
-
-This function in contrast to
-:func:`divide` uses round-down rounding mode.
-
-See also:
-:func:`divide` .
-
-.. index:: gpu::exp
-
-gpu::exp
-------------
-.. c:function:: void gpu::exp(const GpuMat\& a, GpuMat\& b)
-
-    Computes exponent of each matrix element.
-
-    :param a: Source matrix.  ``CV_32FC1``  matrixes are supported for now.
-
-    :param b: Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`exp` .
-
-.. index:: gpu::log
-
-gpu::log
-------------
-.. c:function:: void gpu::log(const GpuMat\& a, GpuMat\& b)
-
-    Computes natural logarithm of absolute value of each matrix element.
-
-    :param a: Source matrix.  ``CV_32FC1``  matrixes are supported for now.
-
-    :param b: Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`log` .
-
-.. index:: gpu::absdiff
-
-gpu::absdiff
-----------------
-.. c:function:: void gpu::absdiff(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
-
-    Computes per-element absolute difference of two matrices (or of matrix and scalar).
-
-    :param a: First source matrix.  ``CV_8UC1`` ,  ``CV_8UC4`` ,  ``CV_32SC1``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destionation matrix. Will have the same size and type as  ``a`` .
-
-.. c:function:: void absdiff(const GpuMat\& a, const Scalar\& s, GpuMat\& c)
-
-    * **a** Source matrix.  ``CV_32FC1``  matrixes are supported for now.
-
-    * **b** Scalar to be subtracted from the source matrix elements.
-
-    * **c** Destination matrix. Will have the same size and type as  ``a`` .
-
-See also:
-:func:`absdiff` .
-
-.. index:: gpu::compare
-
-gpu::compare
-----------------
-.. c:function:: void gpu::compare(const GpuMat\& a, const GpuMat\& b, GpuMat\& c, int cmpop)
-
-    Compares elements of two matrices.
-
-    :param a: First source matrix.  ``CV_8UC4``  and  ``CV_32FC1``  matrices are supported for now.
-
-    :param b: Second source matrix. Must have the same size and type as  ``a`` .
-
-    :param c: Destination matrix. Will have the same size as  ``a``  and be  ``CV_8UC1``  type.
-
-    :param cmpop: Flag specifying the relation between the elements to be checked:
-        
-            * **CMP_EQ** :math:`=`             
-            * **CMP_GT** :math:`>`             
-            * **CMP_GE** :math:`\ge`             
-            * **CMP_LT** :math:`<`             
-            * **CMP_LE** :math:`\le`             
-            * **CMP_NE** :math:`\ne`             
-            
-
-See also:
-:func:`compare` .
-
-.. index:: gpu::bitwise_not
-
-.. _gpu::bitwise_not:
-
-gpu::bitwise_not
---------------------
-.. c:function:: void gpu::bitwise_not(const GpuMat\& src, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
-
-.. c:function:: void gpu::bitwise_not(const GpuMat\& src, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
-
-    Performs per-element bitwise inversion.
-
-    :param src: Source matrix.
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src`` .
-
-    :param mask: Optional operation mask. 8-bit single channel image.
-
-    :param stream: Stream for the asynchronous version.
-
-See also:
-.
-
-.. index:: gpu::bitwise_or
-
-.. _gpu::bitwise_or:
-
-gpu::bitwise_or
--------------------
-.. c:function:: void gpu::bitwise_or(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
-
-.. c:function:: void gpu::bitwise_or(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
-
-    Performs per-element bitwise disjunction of two matrices.
-
-    :param src1: First source matrix.
-
-    :param src2: Second source matrix. It must have the same size and type as  ``src1`` .
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
-
-    :param mask: Optional operation mask. 8-bit single channel image.
-
-    :param stream: Stream for the asynchronous version.
-
-See also:
-.
-
-.. index:: gpu::bitwise_and
-
-.. _gpu::bitwise_and:
-
-gpu::bitwise_and
---------------------
-.. c:function:: void gpu::bitwise_and(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
-
-.. c:function:: void gpu::bitwise_and(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
-
-    Performs per-element bitwise conjunction of two matrices.
-
-    :param src1: First source matrix.
-
-    :param src2: Second source matrix. It must have the same size and type as  ``src1`` .
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
-
-    :param mask: Optional operation mask. 8-bit single channel image.
-
-    :param stream: Stream for the asynchronous version.
-
-See also:
-.
-
-.. index:: gpu::bitwise_xor
-
-.. _gpu::bitwise_xor:
-
-gpu::bitwise_xor
---------------------
-.. c:function:: void gpu::bitwise_xor(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
-
-.. c:function:: void gpu::bitwise_xor(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
-
-    Performs per-element bitwise "exclusive or" of two matrices.
-
-    :param src1: First source matrix.
-
-    :param src2: Second source matrix. It must have the same size and type as  ``src1`` .
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
-
-    :param mask: Optional operation mask. 8-bit single channel image.
-
-    :param stream: Stream for the asynchronous version.
-
-See also:
-.
-
-.. index:: gpu::min
-
-gpu::min
-------------
-.. c:function:: void gpu::min(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst)
-
-.. c:function:: void gpu::min(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const Stream\& stream)
-
-    Computes per-element minimum of two matrices (or of matrix and scalar).
-
-    :param src1: First source matrix.
-
-    :param src2: Second source matrix.
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
-
-    :param stream: Stream for the asynchronous version.
-
-.. c:function:: void gpu::min(const GpuMat\& src1, double src2, GpuMat\& dst)
-
-.. c:function:: void gpu::min(const GpuMat\& src1, double src2, GpuMat\& dst,
-   const Stream\& stream)
-
-    * **src1** Source matrix.
-
-    * **src2** Scalar to be compared with.
-
-    * **dst** Destination matrix. Will have the same size and type as  ``src1`` .
-
-    * **stream** Stream for the asynchronous version.
-
-See also:
-:func:`min` .
-
-.. index:: gpu::max
-
-gpu::max
-------------
-.. c:function:: void gpu::max(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst)
-
-.. c:function:: void gpu::max(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const Stream\& stream)
-
-    Computes per-element maximum of two matrices (or of matrix and scalar).
-
-    :param src1: First source matrix.
-
-    :param src2: Second source matrix.
-
-    :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
-
-    :param stream: Stream for the asynchronous version.
-
-.. c:function:: void max(const GpuMat\& src1, double src2, GpuMat\& dst)
-
-.. c:function:: void max(const GpuMat\& src1, double src2, GpuMat\& dst,
-   const Stream\& stream)
-
-    * **src1** Source matrix.
-
-    * **src2** Scalar to be compared with.
-
-    * **dst** Destination matrix. Will have the same size and type as  ``src1`` .
-
-    * **stream** Stream for the asynchronous version.
-
-See also:
-:func:`max` .
index c52674c..af17588 100644 (file)
@@ -7,7 +7,7 @@ Per-element Operations.
 
 gpu::add
 ------------
-.. c:function:: void gpu::add(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
+.. c:function:: void gpu::add(const GpuMat& a, const GpuMat& b, GpuMat& c)
 
     Computes matrix-matrix or matrix-scalar sum.
 
@@ -17,7 +17,7 @@ gpu::add
 
     :param c: Destination matrix. Will have the same size and type as  ``a`` .
 
-.. c:function:: void gpu::add(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
+.. c:function:: void gpu::add(const GpuMat& a, const Scalar& sc, GpuMat& c)
 
     * **a** Source matrix.  ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
 
@@ -32,7 +32,7 @@ See also:
 
 gpu::subtract
 -----------------
-.. c:function:: void gpu::subtract(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
+.. c:function:: void gpu::subtract(const GpuMat& a, const GpuMat& b, GpuMat& c)
 
     Subtracts matrix from another matrix (or scalar from matrix).
 
@@ -42,7 +42,7 @@ gpu::subtract
 
     :param c: Destination matrix. Will have the same size and type as  ``a`` .
 
-.. c:function:: void subtract(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
+.. c:function:: void subtract(const GpuMat& a, const Scalar& sc, GpuMat& c)
 
     * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
 
@@ -57,7 +57,7 @@ See also:
 
 gpu::multiply
 -----------------
-.. c:function:: void gpu::multiply(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
+.. c:function:: void gpu::multiply(const GpuMat& a, const GpuMat& b, GpuMat& c)
 
     Computes per-element product of two matrices (or of matrix and scalar).
 
@@ -67,7 +67,7 @@ gpu::multiply
 
     :param c: Destionation matrix. Will have the same size and type as  ``a`` .
 
-.. c:function:: void multiply(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
+.. c:function:: void multiply(const GpuMat& a, const Scalar& sc, GpuMat& c)
 
     * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
 
@@ -82,7 +82,7 @@ See also:
 
 gpu::divide
 ---------------
-.. c:function:: void gpu::divide(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
+.. c:function:: void gpu::divide(const GpuMat& a, const GpuMat& b, GpuMat& c)
 
     Performs per-element division of two matrices (or division of matrix by scalar).
 
@@ -92,7 +92,7 @@ gpu::divide
 
     :param c: Destionation matrix. Will have the same size and type as  ``a`` .
 
-.. c:function:: void divide(const GpuMat\& a, const Scalar\& sc, GpuMat\& c)
+.. c:function:: void divide(const GpuMat& a, const Scalar& sc, GpuMat& c)
 
     * **a** Source matrix.   ``CV_32FC1``  and  ``CV_32FC2``  matrixes are supported for now.
 
@@ -110,7 +110,7 @@ See also:
 
 gpu::exp
 ------------
-.. c:function:: void gpu::exp(const GpuMat\& a, GpuMat\& b)
+.. c:function:: void gpu::exp(const GpuMat& a, GpuMat& b)
 
     Computes exponent of each matrix element.
 
@@ -125,7 +125,7 @@ See also:
 
 gpu::log
 ------------
-.. c:function:: void gpu::log(const GpuMat\& a, GpuMat\& b)
+.. c:function:: void gpu::log(const GpuMat& a, GpuMat& b)
 
     Computes natural logarithm of absolute value of each matrix element.
 
@@ -140,7 +140,7 @@ See also:
 
 gpu::absdiff
 ----------------
-.. c:function:: void gpu::absdiff(const GpuMat\& a, const GpuMat\& b, GpuMat\& c)
+.. c:function:: void gpu::absdiff(const GpuMat& a, const GpuMat& b, GpuMat& c)
 
     Computes per-element absolute difference of two matrices (or of matrix and scalar).
 
@@ -150,7 +150,7 @@ gpu::absdiff
 
     :param c: Destionation matrix. Will have the same size and type as  ``a`` .
 
-.. c:function:: void absdiff(const GpuMat\& a, const Scalar\& s, GpuMat\& c)
+.. c:function:: void absdiff(const GpuMat& a, const Scalar& s, GpuMat& c)
 
     * **a** Source matrix.  ``CV_32FC1``  matrixes are supported for now.
 
@@ -165,7 +165,7 @@ See also:
 
 gpu::compare
 ----------------
-.. c:function:: void gpu::compare(const GpuMat\& a, const GpuMat\& b, GpuMat\& c, int cmpop)
+.. c:function:: void gpu::compare(const GpuMat& a, const GpuMat& b, GpuMat& c, int cmpop)
 
     Compares elements of two matrices.
 
@@ -190,15 +190,11 @@ See also:
 
 .. index:: gpu::bitwise_not
 
-.. _gpu::bitwise_not:
-
 gpu::bitwise_not
 --------------------
-.. c:function:: void gpu::bitwise_not(const GpuMat\& src, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
+.. c:function:: void gpu::bitwise_not(const GpuMat& src, GpuMat& dst, const GpuMat& mask=GpuMat())
 
-.. c:function:: void gpu::bitwise_not(const GpuMat\& src, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
+.. c:function:: void gpu::bitwise_not(const GpuMat& src, GpuMat& dst, const GpuMat& mask, const Stream& stream)
 
     Performs per-element bitwise inversion.
 
@@ -210,20 +206,14 @@ gpu::bitwise_not
 
     :param stream: Stream for the asynchronous version.
 
-See also:
-.
 
 .. index:: gpu::bitwise_or
 
-.. _gpu::bitwise_or:
-
 gpu::bitwise_or
 -------------------
-.. c:function:: void gpu::bitwise_or(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
+.. c:function:: void gpu::bitwise_or(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask=GpuMat())
 
-.. c:function:: void gpu::bitwise_or(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
+.. c:function:: void gpu::bitwise_or(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, const Stream& stream)
 
     Performs per-element bitwise disjunction of two matrices.
 
@@ -237,20 +227,13 @@ gpu::bitwise_or
 
     :param stream: Stream for the asynchronous version.
 
-See also:
-.
-
 .. index:: gpu::bitwise_and
 
-.. _gpu::bitwise_and:
-
 gpu::bitwise_and
 --------------------
-.. c:function:: void gpu::bitwise_and(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
+.. c:function:: void gpu::bitwise_and(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask=GpuMat())
 
-.. c:function:: void gpu::bitwise_and(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
+.. c:function:: void gpu::bitwise_and(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, const Stream& stream)
 
     Performs per-element bitwise conjunction of two matrices.
 
@@ -264,20 +247,14 @@ gpu::bitwise_and
 
     :param stream: Stream for the asynchronous version.
 
-See also:
-.
 
 .. index:: gpu::bitwise_xor
 
-.. _gpu::bitwise_xor:
-
 gpu::bitwise_xor
 --------------------
-.. c:function:: void gpu::bitwise_xor(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask=GpuMat())
+.. c:function:: void gpu::bitwise_xor(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask=GpuMat())
 
-.. c:function:: void gpu::bitwise_xor(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const GpuMat\& mask, const Stream\& stream)
+.. c:function:: void gpu::bitwise_xor(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, const Stream& stream)
 
     Performs per-element bitwise "exclusive or" of two matrices.
 
@@ -291,19 +268,16 @@ gpu::bitwise_xor
 
     :param stream: Stream for the asynchronous version.
 
-See also:
-.
 
 .. index:: gpu::min
 
 gpu::min
 ------------
-.. c:function:: void gpu::min(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst)
+.. c:function:: void gpu::min(const GpuMat& src1, const GpuMat& src2, GpuMat& dst)
 
-.. c:function:: void gpu::min(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const Stream\& stream)
+.. c:function:: void gpu::min(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const Stream& stream)
 
-    Computes per-element minimum of two matrices (or of matrix and scalar).
+    Computes per-element minimum of two matrices (or a matrix and a scalar).
 
     :param src1: First source matrix.
 
@@ -313,10 +287,10 @@ gpu::min
 
     :param stream: Stream for the asynchronous version.
 
-.. c:function:: void gpu::min(const GpuMat\& src1, double src2, GpuMat\& dst)
+.. c:function:: void gpu::min(const GpuMat& src1, double src2, GpuMat& dst)
 
-.. c:function:: void gpu::min(const GpuMat\& src1, double src2, GpuMat\& dst,
-   const Stream\& stream)
+.. c:function:: void gpu::min(const GpuMat& src1, double src2, GpuMat& dst,
+   const Stream& stream)
 
     * **src1** Source matrix.
 
@@ -333,33 +307,25 @@ See also:
 
 gpu::max
 ------------
-.. c:function:: void gpu::max(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst)
+.. c:function:: void gpu::max(const GpuMat& src1, const GpuMat& src2, GpuMat& dst)
+
+.. c:function:: void gpu::max(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const Stream& stream)
+
+.. c:function:: void gpu::max(const GpuMat& src1, double value, GpuMat& dst)
 
-.. c:function:: void gpu::max(const GpuMat\& src1, const GpuMat\& src2, GpuMat\& dst,
-   const Stream\& stream)
+.. c:function:: void gpu::max(const GpuMat& src1, double value, GpuMat& dst, const Stream& stream)
 
-    Computes per-element maximum of two matrices (or of matrix and scalar).
+    Computes per-element maximum of two matrices (or a matrix and a scalar).
 
     :param src1: First source matrix.
 
     :param src2: Second source matrix.
+    
+    :param value: The scalar value to compare ``src1`` elements with
 
     :param dst: Destination matrix. Will have the same size and type as  ``src1`` .
 
     :param stream: Stream for the asynchronous version.
 
-.. c:function:: void max(const GpuMat\& src1, double src2, GpuMat\& dst)
-
-.. c:function:: void max(const GpuMat\& src1, double src2, GpuMat\& dst,
-   const Stream\& stream)
-
-    * **src1** Source matrix.
-
-    * **src2** Scalar to be compared with.
-
-    * **dst** Destination matrix. Will have the same size and type as  ``src1`` .
-
-    * **stream** Stream for the asynchronous version.
-
 See also:
 :func:`max` .
index f39e472..f875657 100644 (file)
@@ -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)
index 1fcc41a..5d496ce 100644 (file)
@@ -5,6 +5,8 @@ Reading and Writing Images and Video
 
 .. index:: imdecode
 
+.. _imdecode:
+
 imdecode
 ------------
 .. c:function:: Mat imdecode( const Mat\& buf,  int flags )
@@ -23,6 +25,8 @@ See
 
 .. index:: imencode
 
+.. _imencode:
+
 imencode
 ------------
 .. c:function:: bool imencode( const string\& ext,               const Mat\& img,               vector<uchar>\& buf,               const vector<int>\& params=vector<int>())
@@ -43,6 +47,8 @@ See
 
 .. index:: imread
 
+.. _imread:
+
 imread
 ----------
 .. 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
 
 .. index:: imwrite
 
+.. _imwrite:
+
 imwrite
 -----------
 .. c:function:: bool imwrite( const string\& filename,  const Mat\& img,              const vector<int>\& params=vector<int>())
@@ -211,6 +204,8 @@ The class provides C++ video capturing API. Here is how the class can be used: :
 
 .. index:: VideoCapture::VideoCapture
 
+.. _VideoCapture::VideoCapture:
+
 VideoCapture::VideoCapture
 ------------------------------
 .. c:function:: VideoCapture::VideoCapture()
@@ -227,6 +222,8 @@ VideoCapture constructors.
 
 .. index:: VideoCapture::get
 
+.. _VideoCapture::get:
+
 VideoCapture::get
 ---------------------
 .. c:function:: double VideoCapture::get(int property_id)
@@ -275,6 +272,8 @@ Note that when querying a property which is unsupported by the backend used by t
 
 .. index:: VideoCapture::set
 
+.. _VideoCapture::set:
+
 VideoCapture::set
 ---------------------
 .. c:function:: bool VideoCapture::set(int property_id, double value)
index 79b03a0..b134c2c 100644 (file)
@@ -5,9 +5,11 @@ User Interface
 
 .. index:: createTrackbar
 
+.. _createTrackbar:
+
 createTrackbar
 ------------------
-.. c:function:: int createTrackbar( const string\& trackbarname,                    const string\& winname,                    int* value, int count,                    TrackbarCallback onChange CV_DEFAULT(0),                    void* userdata CV_DEFAULT(0))
+.. c:function:: int createTrackbar( const string& trackbarname, const string& winname, int* value, int count, TrackbarCallback onChange CV_DEFAULT(0), void* userdata CV_DEFAULT(0))
 
     Creates a trackbar and attaches it to the specified window
 
@@ -43,7 +45,7 @@ By clicking on the label of each trackbar, it is possible to edit the trackbar's
 
 getTrackbarPos
 ------------------
-.. c:function:: int getTrackbarPos( const string\& trackbarname,  const string\& winname )
+.. c:function:: int getTrackbarPos( const string& trackbarname, const string& winname )
 
     Returns the trackbar position.
 
@@ -61,9 +63,11 @@ qt-specific details:
 
 .. index:: imshow
 
+.. _imshow:
+
 imshow
 ----------
-.. c:function:: void imshow( const string\& winname,  const Mat\& image )
+.. c:function:: void imshow( const string& winname, const Mat& image )
 
     Displays the image in the specified window
 
@@ -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:
 
         ::
 
-            namedWindow( ``myWindow'',  ``CV_WINDOW_NORMAL``   textbar   ``CV_GUI_NORMAL`` );
+            namedWindow( ``myWindow'', ``CV_WINDOW_NORMAL``   textbar   ``CV_GUI_NORMAL`` );
 
         ..
 
 .. index:: setTrackbarPos
 
+.. _setTrackbarPos:
+
 setTrackbarPos
 ------------------
-.. c:function:: void setTrackbarPos( const string\& trackbarname,  const string\& winname, int pos )
+.. c:function:: void setTrackbarPos( const string& trackbarname, const string& winname, int pos )
 
     Sets the trackbar position.
 
@@ -144,6 +152,8 @@ qt-specific details:
 
 .. index:: waitKey
 
+.. _waitKey:
+
 waitKey
 -----------
 .. c:function:: int waitKey(int delay=0)
index e3fc9ff..33820d4 100644 (file)
@@ -3,9 +3,11 @@ Feature Detection
 
 .. index:: Canny
 
+.. _Canny:
+
 Canny
 ---------
-.. c:function:: void Canny( const Mat& image, Mat& edges,            double threshold1, double threshold2,            int apertureSize=3, bool L2gradient=false )
+.. c:function:: void Canny( const Mat& image, Mat& edges, double threshold1, double threshold2, int apertureSize=3, bool L2gradient=false )
 
     Finds edges in an image using Canny algorithm.
 
@@ -26,9 +28,12 @@ http://en.wikipedia.org/wiki/Canny_edge_detector
 
 .. index:: cornerEigenValsAndVecs
 
+.. _cornerEigenValsAndVecs:
+
 cornerEigenValsAndVecs
---------------------------
-.. c:function:: void cornerEigenValsAndVecs( const Mat& src, Mat& dst,                            int blockSize, int apertureSize,                            int borderType=BORDER_DEFAULT )
+----------------------
+
+.. c:function:: void cornerEigenValsAndVecs( const Mat& src, Mat& dst, int blockSize, int apertureSize, int borderType=BORDER_DEFAULT )
 
     Calculates eigenvalues and eigenvectors of image blocks for corner detection.
 
@@ -67,11 +72,15 @@ The output of the function can be used for robust edge or corner detection.
 
 See also:
 :func:`cornerMinEigenVal`,:func:`cornerHarris`,:func:`preCornerDetect`
+
 .. index:: cornerHarris
 
+.. _cornerHarris:
+
 cornerHarris
-----------------
-.. c:function:: void cornerHarris( const Mat& src, Mat& dst, int blockSize,                  int apertureSize, double k,                  int borderType=BORDER_DEFAULT )
+------------
+
+.. c:function:: void cornerHarris( const Mat& src, Mat& dst, int blockSize, int apertureSize, double k, int borderType=BORDER_DEFAULT )
 
     Harris edge detector.
 
@@ -103,9 +112,12 @@ Corners in the image can be found as the local maxima of this response map.
 
 .. index:: cornerMinEigenVal
 
+.. _cornerMinEigenVal:
+
 cornerMinEigenVal
----------------------
-.. c:function:: void cornerMinEigenVal( const Mat& src, Mat& dst,                        int blockSize, int apertureSize=3,                        int borderType=BORDER_DEFAULT )
+-----------------
+
+.. c:function:: void cornerMinEigenVal( const Mat& src, Mat& dst, int blockSize, int apertureSize=3, int borderType=BORDER_DEFAULT )
 
     Calculates the minimal eigenvalue of gradient matrices for corner detection.
 
@@ -126,9 +138,11 @@ The function is similar to
 
 .. index:: cornerSubPix
 
+.. _cornerSubPix:
+
 cornerSubPix
 ----------------
-.. c:function:: void cornerSubPix( const Mat& image, vector<Point2f>& corners,                   Size winSize, Size zeroZone,                   TermCriteria criteria )
+.. c:function:: void cornerSubPix( const Mat& image, vector<Point2f>& corners, Size winSize, Size zeroZone, TermCriteria criteria )
 
     Refines the corner locations.
 
@@ -182,9 +196,12 @@ The algorithm sets the center of the neighborhood window at this new center
 
 .. index:: goodFeaturesToTrack
 
+.. _goodFeaturesToTrack:
+
 goodFeaturesToTrack
------------------------
-.. c:function:: void goodFeaturesToTrack( const Mat& image, vector<Point2f>& corners,                         int maxCorners, double qualityLevel, double minDistance,                         const Mat& mask=Mat(), int blockSize=3,                         bool useHarrisDetector=false, double k=0.04 )
+-------------------
+
+.. c:function:: void goodFeaturesToTrack( const Mat& image, vector<Point2f>& corners, int maxCorners, double qualityLevel, double minDistance, const Mat& mask=Mat(), int blockSize=3, bool useHarrisDetector=false, double k=0.04 )
 
     Determines strong corners on an image.
 
@@ -239,8 +256,11 @@ See also: :func:`cornerMinEigenVal`, :func:`cornerHarris`, :func:`calcOpticalFlo
 
 .. index:: HoughCircles
 
+.. _HoughCircles:
+
 HoughCircles
-----------------
+------------
+
 .. c:function:: void HoughCircles( Mat& image, vector<Vec3f>& circles, int method, double dp, double minDist, double param1=100, double param2=100, int minRadius=0, int maxRadius=0 )
 
     Finds circles in a grayscale image using a Hough transform.
@@ -300,11 +320,15 @@ Note that usually the function detects the circles' centers well, however it may
 
 See also:
 :func:`fitEllipse`,:func:`minEnclosingCircle`
+
 .. index:: HoughLines
 
+.. _HoughLines:
+
 HoughLines
---------------
-.. c:function:: void HoughLines( Mat& image, vector<Vec2f>& lines,                 double rho, double theta, int threshold,                 double srn=0, double stn=0 )
+----------
+
+.. c:function:: void HoughLines( Mat& image, vector<Vec2f>& lines, double rho, double theta, int threshold, double srn=0, double stn=0 )
 
     Finds lines in a binary image using standard Hough transform.
 
@@ -327,9 +351,12 @@ The function implements standard or standard multi-scale Hough transform algorit
 
 .. index:: HoughLinesP
 
+.. _HoughLinesP:
+
 HoughLinesP
----------------
-.. c:function:: void HoughLinesP( Mat& image, vector<Vec4i>& lines,                  double rho, double theta, int threshold,                  double minLineLength=0, double maxLineGap=0 )
+-----------
+
+.. c:function:: void HoughLinesP( Mat& image, vector<Vec4i>& lines, double rho, double theta, int threshold, double minLineLength=0, double maxLineGap=0 )
 
     Finds lines segments in a binary image using probabilistic Hough transform.
 
@@ -414,9 +441,12 @@ And this is the output of the above program in the case of probabilistic Hough t
 
 .. index:: preCornerDetect
 
+.. _preCornerDetect:
+
 preCornerDetect
--------------------
-.. c:function:: void preCornerDetect( const Mat& src, Mat& dst, int apertureSize,                     int borderType=BORDER_DEFAULT )
+---------------
+
+.. c:function:: void preCornerDetect( const Mat& src, Mat& dst, int apertureSize, int borderType=BORDER_DEFAULT )
 
     Calculates the feature map for corner detection
 
index e7dac8c..a2ae920 100644 (file)
@@ -34,19 +34,25 @@ The actual implementations of the geometrical transformations, from the most gen
 
 .. index:: convertMaps
 
+.. _convertMaps:
+
 convertMaps
----------------
-.. c:function:: void convertMaps( const Mat\& map1, const Mat\& map2,                  Mat\& dstmap1, Mat\& dstmap2,                  int dstmap1type, bool nninterpolation=false )
+-----------
+
+.. c:function:: void convertMaps( const Mat& map1, const Mat& map2, Mat& dstmap1, Mat& dstmap2, int dstmap1type, bool nninterpolation=false )
 
     Converts image transformation maps from one representation to another
 
     :param map1: The first input map of type  ``CV_16SC2``  or  ``CV_32FC1``  or  ``CV_32FC2``
+    
     :param map2: The second input map of type  ``CV_16UC1``  or  ``CV_32FC1``  or none (empty matrix), respectively
 
     :param dstmap1: The first output map; will have type  ``dstmap1type``  and the same size as  ``src``
+    
     :param dstmap2: The second output map
 
-    :param dstmap1type: The type of the first output map; should be  ``CV_16SC2`` ,  ``CV_32FC1``  or  ``CV_32FC2``
+    :param dstmap1type: The type of the first output map; should be  ``CV_16SC2`` , ``CV_32FC1``  or  ``CV_32FC2``
+    
     :param nninterpolation: Indicates whether the fixed-point maps will be used for nearest-neighbor or for more complex interpolation
 
 The function converts a pair of maps for
@@ -64,8 +70,11 @@ The function converts a pair of maps for
 
 See also:
 :func:`remap`,:func:`undisort`,:func:`initUndistortRectifyMap`
+
 .. index:: getAffineTransform
 
+.. _getAffineTransform:
+
 getAffineTransform
 ----------------------
 .. c:function:: Mat getAffineTransform( const Point2f src[], const Point2f dst[] )
@@ -76,8 +85,7 @@ getAffineTransform
 
     :param dst: Coordinates of the corresponding triangle vertices in the destination image
 
-The function calculates the
-:math:`2 \times 3` matrix of an affine transform such that:
+The function calculates the :math:`2 \times 3` matrix of an affine transform such that:
 
 .. math::
 
@@ -93,11 +101,15 @@ where
 
 See also:
 :func:`warpAffine`,:func:`transform`
+
+
 .. index:: getPerspectiveTransform
 
+.. _getPerspectiveTransform:
+
 getPerspectiveTransform
 ---------------------------
-.. c:function:: Mat getPerspectiveTransform( const Point2f src[],  const Point2f dst[] )
+.. c:function:: Mat getPerspectiveTransform( const Point2f src[], const Point2f dst[] )
 
     Calculates the perspective transform from 4 pairs of the corresponding points
 
@@ -105,8 +117,7 @@ getPerspectiveTransform
 
     :param dst: Coordinates of the corresponding quadrangle vertices in the destination image
 
-The function calculates the
-:math:`3 \times 3` matrix of a perspective transform such that:
+The function calculates the :math:`3 \times 3` matrix of a perspective transform such that:
 
 .. math::
 
@@ -122,11 +133,14 @@ where
 
 See also:
 :func:`findHomography`,:func:`warpPerspective`,:func:`perspectiveTransform`
+
 .. index:: getRectSubPix
 
+.. getRectSubPix:
+
 getRectSubPix
 -----------------
-.. c:function:: void getRectSubPix( const Mat\& image, Size patchSize,                    Point2f center, Mat\& dst, int patchType=-1 )
+.. c:function:: void getRectSubPix( const Mat& image, Size patchSize, Point2f center, Mat& dst, int patchType=-1 )
 
     Retrieves the pixel rectangle from an image with sub-pixel accuracy
 
@@ -156,8 +170,11 @@ the pixel values outside of the image.
 
 See also:
 :func:`warpAffine`,:func:`warpPerspective`
+
 .. index:: getRotationMatrix2D
 
+.. _getRotationMatrix2D:
+
 getRotationMatrix2D
 -----------------------
 .. c:function:: Mat getRotationMatrix2D( Point2f center, double angle, double scale )
@@ -186,11 +203,14 @@ The transformation maps the rotation center to itself. If this is not the purpos
 
 See also:
 :func:`getAffineTransform`,:func:`warpAffine`,:func:`transform`
+
 .. index:: invertAffineTransform
 
+.. _invertAffineTransform:
+
 invertAffineTransform
 -------------------------
-.. c:function:: void invertAffineTransform(const Mat\& M, Mat\& iM)
+.. c:function:: void invertAffineTransform(const Mat& M, Mat& iM)
 
     Inverts an affine transformation
 
@@ -210,18 +230,21 @@ The result will also be a
 
 .. index:: remap
 
+.. _remap:
+
 remap
----------
-.. c:function:: void remap( const Mat\& src, Mat\& dst, const Mat\& map1, const Mat\& map2,            int interpolation, int borderMode=BORDER_CONSTANT,            const Scalar\& borderValue=Scalar())
+-----
+
+.. c:function:: void remap( const Mat& src, Mat& dst, const Mat& map1, const Mat& map2, int interpolation, int borderMode=BORDER_CONSTANT, const Scalar& borderValue=Scalar())
 
     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.
 
 .. index:: resize
 
+.. _resize:
+
 resize
 ----------
-.. c:function:: void resize( const Mat\& src, Mat\& dst,             Size dsize, double fx=0, double fy=0,             int interpolation=INTER_LINEAR )
+
+.. c:function:: void resize( const Mat& src, Mat& dst, Size dsize, double fx=0, double fy=0, int interpolation=INTER_LINEAR )
 
     Resizes an image
 
@@ -313,9 +339,11 @@ See also:
 
 .. index:: warpAffine
 
+.. _warpAffine:
+
 warpAffine
 --------------
-.. c:function:: void warpAffine( const Mat\& src, Mat\& dst,                 const Mat\& M, Size dsize,                 int flags=INTER_LINEAR,                 int borderMode=BORDER_CONSTANT,                 const Scalar\& borderValue=Scalar())
+.. c:function:: void warpAffine( const Mat& src, Mat& dst, const Mat& M, Size dsize, int flags=INTER_LINEAR, int borderMode=BORDER_CONSTANT, const Scalar& borderValue=Scalar())
 
     Applies an affine transformation to an image.
 
@@ -337,7 +365,7 @@ The function ``warpAffine`` transforms the source image using the specified matr
 
 .. math::
 
-    \texttt{dst} (x,y) =  \texttt{src} ( \texttt{M} _{11} x +  \texttt{M} _{12} y +  \texttt{M} _{13},  \texttt{M} _{21} x +  \texttt{M} _{22} y +  \texttt{M} _{23})
+    \texttt{dst} (x,y) =  \texttt{src} ( \texttt{M} _{11} x +  \texttt{M} _{12} y +  \texttt{M} _{13}, \texttt{M} _{21} x +  \texttt{M} _{22} y +  \texttt{M} _{23})
 
 when the flag ``WARP_INVERSE_MAP`` is set. Otherwise, the transformation is first inverted with
 :func:`invertAffineTransform` and then put in the formula above instead of ``M`` .
@@ -345,11 +373,14 @@ The function can not operate in-place.
 
 See also:
 :func:`warpPerspective`,:func:`resize`,:func:`remap`,:func:`getRectSubPix`,:func:`transform`
+
 .. index:: warpPerspective
 
+.. _warpPerspective:
+
 warpPerspective
 -------------------
-.. c:function:: void warpPerspective( const Mat\& src, Mat\& dst,                      const Mat\& M, Size dsize,                      int flags=INTER_LINEAR,                      int borderMode=BORDER_CONSTANT,                      const Scalar\& borderValue=Scalar())
+.. c:function:: void warpPerspective( const Mat& src, Mat& dst, const Mat& M, Size dsize, int flags=INTER_LINEAR, int borderMode=BORDER_CONSTANT, const Scalar& borderValue=Scalar())
 
     Applies a perspective transformation to an image.
 
@@ -378,4 +409,5 @@ when the flag ``WARP_INVERSE_MAP`` is set. Otherwise, the transformation is firs
 The function can not operate in-place.
 
 See also:
-:func:`warpAffine`,:func:`resize`,:func:`remap`,:func:`getRectSubPix`,:func:`perspectiveTransform` 
\ No newline at end of file
+:func:`warpAffine`,:func:`resize`,:func:`remap`,:func:`getRectSubPix`,:func:`perspectiveTransform`
\ No newline at end of file
index 3bf6080..b403389 100644 (file)
@@ -3,6 +3,8 @@ Histograms
 
 .. index:: calcHist
 
+.. _calcHist:
+
 calcHist
 ------------
 .. c:function:: void calcHist( const Mat* arrays, int narrays,               const int* channels, const Mat\& mask,               MatND\& hist, int dims, const int* histSize,               const float** ranges, bool uniform=true,               bool accumulate=false )
@@ -95,6 +97,8 @@ input arrays. The sample below shows how to compute 2D Hue-Saturation histogram
 
 .. index:: calcBackProject
 
+.. _calcBackProject:
+
 calcBackProject
 -------------------
 .. c:function:: void calcBackProject( const Mat* arrays, int narrays,                      const int* channels, const MatND\& hist,                      Mat\& backProject, const float** ranges,                      double scale=1, bool uniform=true )
@@ -133,10 +137,14 @@ That is the approximate algorithm of
 
 See also:
 :func:`calcHist`
+
 .. index:: compareHist
 
+.. _compareHist:
+
 compareHist
----------------
+-----------
+
 .. c:function:: double compareHist( const MatND\& H1, const MatND\& H2, int method )
 
 .. c:function:: double compareHist( const SparseMat\& H1,  const SparseMat\& H2, int method )
@@ -199,6 +207,8 @@ While the function works well with 1-, 2-, 3-dimensional dense histograms, it ma
 
 .. index:: equalizeHist
 
+.. _equalizeHist:
+
 equalizeHist
 ----------------
 .. c:function:: void equalizeHist( const Mat\& src, Mat\& dst )
index c811488..d5de243 100644 (file)
@@ -3,6 +3,8 @@ Miscellaneous Image Transformations
 
 .. index:: adaptiveThreshold
 
+.. _adaptiveThreshold:
+
 adaptiveThreshold
 ---------------------
 .. c:function:: void adaptiveThreshold( const Mat& src, Mat& dst, double maxValue,                        int adaptiveMethod, int thresholdType,                        int blockSize, double C )
@@ -56,8 +58,12 @@ The function can process the image in-place.
 
 See also:
 :func:`threshold`,:func:`blur`,:func:`GaussianBlur`
+
+
 .. index:: cvtColor
 
+.. _cvtColor:
+
 cvtColor
 ------------
 .. c:function:: void cvtColor( const Mat& src, Mat& dst, int code, int dstCn=0 )
@@ -389,6 +395,8 @@ The function can do the following transformations:
 
 .. index:: distanceTransform
 
+.. _distanceTransform:
+
 distanceTransform
 ---------------------
 .. c:function:: void distanceTransform( const Mat& src, Mat& dst, int distanceType, int maskSize )
@@ -457,6 +465,8 @@ Currently, this second variant can only use the approximate distance transform a
 
 .. index:: floodFill
 
+.. _floodFill:
+
 floodFill
 -------------
 .. c:function:: int floodFill( Mat& image, Point seed, Scalar newVal, Rect* rect=0, Scalar loDiff=Scalar(), Scalar upDiff=Scalar(),               int flags=4 )
@@ -540,8 +550,11 @@ By using these functions you can either mark a connected component with the spec
 
 See also:
 :func:`findContours`
+
 .. index:: inpaint
 
+.. _inpaint:
+
 inpaint
 -----------
 .. c:function:: void inpaint( const Mat& src, const Mat& inpaintMask,              Mat& dst, double inpaintRadius, int flags )
@@ -568,6 +581,8 @@ for more details.
 
 .. index:: integral
 
+.. _integral:
+
 integral
 ------------
 .. c:function:: void integral( const Mat& image, Mat& sum, int sdepth=-1 )
@@ -620,6 +635,8 @@ As a practical example, the next figure shows the calculation of the integral of
 
 .. index:: threshold
 
+.. _threshold:
+
 threshold
 -------------
 .. c:function:: double threshold( const Mat& src, Mat& dst, double thresh,                  double maxVal, int thresholdType )
@@ -684,8 +701,11 @@ Currently, Otsu's method is implemented only for 8-bit images.
 
 See also:
 :func:`adaptiveThreshold`,:func:`findContours`,:func:`compare`,:func:`min`,:func:`max`
+
 .. index:: watershed
 
+.. _watershed:
+
 watershed
 -------------
 .. c:function:: void watershed( const Mat& image, Mat& markers )
@@ -723,10 +743,14 @@ can be found in OpenCV samples directory; see ``watershed.cpp`` demo.
 
 See also:
 :func:`findContours`
+
 .. index:: grabCut
 
+.. _grabCut:
+
 grabCut
------------
+-------
+
 .. c:function:: void grabCut(const Mat& image, Mat& mask, Rect rect, Mat& bgdModel, Mat& fgdModel, int iterCount, int mode )
 
     Runs GrabCut algorithm
@@ -756,7 +780,5 @@ grabCut
 
         * **GC_EVAL** The value means that algorithm should just resume.
 
-The function implements the `GrabCut <http://en.wikipedia.org/wiki/GrabCut>`_
-image segmentation algorithm.
+The function implements the `GrabCut image segmentation algorithm <http://en.wikipedia.org/wiki/GrabCut>`_.
 See the sample grabcut.cpp on how to use the function.
-
diff --git a/modules/imgproc/doc/planar_subdivisions.rst b/modules/imgproc/doc/planar_subdivisions.rst
deleted file mode 100644 (file)
index bd6b1f2..0000000
+++ /dev/null
@@ -1,5 +0,0 @@
-Planar Subdivisions
-===================
-
-.. highlight:: cpp
-
index b75493f..c45557f 100644 (file)
@@ -1,3 +1,5 @@
+.. _Boosting:
+
 Boosting
 ========
 
@@ -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.**
 
 .. index:: CvBoostParams
 
index 6ed2e67..8c8ed9c 100644 (file)
@@ -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 ::
 
index 4e6fd0f..54e3d50 100644 (file)
@@ -61,7 +61,7 @@ so the error on the test set usually starts increasing after the network
 size reaches some limit. Besides, the larger networks are train much
 longer than the smaller ones, so it is reasonable to preprocess the data
 (using
-:ref:`CalcPCA` or similar technique) and train a smaller network
+:ref:`PCA::operator ()` or similar technique) and train a smaller network
 on only the essential features.
 
 Another feature of the MLP's is their inability to handle categorical
index a5dc24a..a134376 100644 (file)
@@ -1,8 +1,8 @@
+.. _Bayes Classifier:
+
 Normal Bayes Classifier
 =======================
 
-.. highlight:: cpp
-
 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.**
index 93ea696..d7cbf78 100644 (file)
@@ -1,8 +1,8 @@
+.. _Random Trees:
+
 Random Trees
 ============
 
-.. highlight:: cpp
-
 Random trees have been introduced by Leo Breiman and Adele Cutler:
 http://www.stat.berkeley.edu/users/breiman/RandomForests/
 . The algorithm can deal with both classification and regression problems. Random trees is a collection (ensemble) of tree predictors that is called