Merge branch 4.x

pull/3333/head
Alexander Alekhin 3 years ago
commit 429d111c35
  1. 623
      modules/aruco/include/opencv2/aruco.hpp
  2. 286
      modules/aruco/include/opencv2/aruco/aruco_calib_pose.hpp
  3. 243
      modules/aruco/include/opencv2/aruco/board.hpp
  4. 222
      modules/aruco/include/opencv2/aruco/charuco.hpp
  5. 60
      modules/aruco/include/opencv2/aruco/dictionary.hpp
  6. 436
      modules/aruco/include/opencv2/aruco_detector.hpp
  7. 58
      modules/aruco/misc/java/test/ArucoTest.java
  8. 78
      modules/aruco/misc/python/test/test_aruco.py
  9. 9
      modules/aruco/perf/perf_aruco.cpp
  10. 2
      modules/aruco/perf/perf_precomp.hpp
  11. 2
      modules/aruco/samples/aruco_dict_utils.cpp
  12. 2
      modules/aruco/samples/aruco_samples_utility.hpp
  13. 9
      modules/aruco/samples/calibrate_camera.cpp
  14. 2
      modules/aruco/samples/create_board.cpp
  15. 2
      modules/aruco/samples/create_marker.cpp
  16. 11
      modules/aruco/samples/detect_board.cpp
  17. 7
      modules/aruco/samples/detect_markers.cpp
  18. 4
      modules/aruco/samples/tutorial_charuco_create_detect.cpp
  19. 150
      modules/aruco/src/apriltag/apriltag_quad_thresh.cpp
  20. 24
      modules/aruco/src/apriltag/apriltag_quad_thresh.hpp
  21. 0
      modules/aruco/src/apriltag/predefined_dictionaries_apriltag.hpp
  22. 0
      modules/aruco/src/apriltag/unionfind.hpp
  23. 0
      modules/aruco/src/apriltag/zarray.hpp
  24. 2
      modules/aruco/src/apriltag/zmaxheap.cpp
  25. 0
      modules/aruco/src/apriltag/zmaxheap.hpp
  26. 1875
      modules/aruco/src/aruco.cpp
  27. 257
      modules/aruco/src/aruco_calib_pose.cpp
  28. 1261
      modules/aruco/src/aruco_detector.cpp
  29. 50
      modules/aruco/src/aruco_utils.cpp
  30. 44
      modules/aruco/src/aruco_utils.hpp
  31. 467
      modules/aruco/src/board.cpp
  32. 445
      modules/aruco/src/charuco.cpp
  33. 113
      modules/aruco/src/dictionary.cpp
  34. 43
      modules/aruco/src/precomp.hpp
  35. 40
      modules/aruco/src/predefined_dictionaries.hpp
  36. 12
      modules/aruco/test/test_aruco_utils.hpp
  37. 96
      modules/aruco/test/test_arucodetection.cpp
  38. 105
      modules/aruco/test/test_boarddetection.cpp
  39. 106
      modules/aruco/test/test_charucodetection.cpp
  40. 1
      modules/aruco/test/test_precomp.hpp
  41. 2
      modules/aruco/tutorials/aruco_board_detection/aruco_board_detection.markdown
  42. 0
      modules/aruco/tutorials/aruco_board_detection/images/board.png
  43. BIN
      modules/aruco/tutorials/aruco_board_detection/images/singlemarkersaxes2.jpg
  44. 5
      modules/aruco/tutorials/aruco_detection/aruco_detection.markdown
  45. 2
      modules/aruco/tutorials/charuco_detection/charuco_detection.markdown
  46. 0
      modules/aruco/tutorials/charuco_detection/images/charucoboard.png
  47. 6
      modules/bioinspired/include/opencv2/bioinspired/retina.hpp
  48. 2
      modules/bioinspired/include/opencv2/bioinspired/transientareassegmentationmodule.hpp
  49. 12
      modules/bioinspired/src/retina.cpp
  50. 6
      modules/bioinspired/src/retina_ocl.cpp
  51. 6
      modules/bioinspired/src/retina_ocl.hpp
  52. 6
      modules/bioinspired/src/transientareassegmentationmodule.cpp
  53. 0
      modules/bioinspired/tutorials/retina_illusion/images/checkershadow_illusion4med_proof.png
  54. 4
      modules/bioinspired/tutorials/retina_illusion/retina_illusion.markdown
  55. 112
      modules/cudacodec/include/opencv2/cudacodec.hpp
  56. 29
      modules/cudacodec/misc/python/test/test_cudacodec.py
  57. 21
      modules/cudacodec/src/frame_queue.cpp
  58. 14
      modules/cudacodec/src/frame_queue.hpp
  59. 39
      modules/cudacodec/src/video_decoder.cpp
  60. 20
      modules/cudacodec/src/video_parser.cpp
  61. 16
      modules/cudacodec/src/video_parser.hpp
  62. 69
      modules/cudacodec/src/video_reader.cpp
  63. 64
      modules/cudacodec/test/test_video.cpp
  64. 30
      modules/cudafeatures2d/include/opencv2/cudafeatures2d.hpp
  65. 12
      modules/cudafeatures2d/misc/python/test/test_cudafeatures2d.py
  66. 4
      modules/cudafeatures2d/src/orb.cpp
  67. 13
      modules/cudaimgproc/src/cuda/gftt.cu
  68. 18
      modules/cudaimgproc/src/gftt.cpp
  69. 5
      modules/cudastereo/include/opencv2/cudastereo.hpp
  70. 28
      modules/cudastereo/misc/python/test/test_cudastereo.py
  71. 2
      modules/cudastereo/src/cuda/stereobm.cu
  72. 8
      modules/freetype/include/opencv2/freetype.hpp
  73. 194
      modules/freetype/src/freetype.cpp
  74. 250
      modules/freetype/test/test_basic.cpp
  75. 6
      modules/freetype/test/test_main.cpp
  76. 10
      modules/freetype/test/test_precomp.hpp
  77. 201
      modules/freetype/test/test_putText.cpp
  78. 2
      modules/ovis/samples/aruco_ar_demo.cpp
  79. 3
      modules/ovis/src/ovis.cpp
  80. 2
      modules/rgbd/include/opencv2/rgbd/colored_kinfu.hpp
  81. 2
      modules/rgbd/include/opencv2/rgbd/dynafu.hpp
  82. 2
      modules/rgbd/include/opencv2/rgbd/kinfu.hpp
  83. 2
      modules/rgbd/include/opencv2/rgbd/large_kinfu.hpp
  84. 4
      modules/rgbd/src/colored_kinfu.cpp
  85. 4
      modules/rgbd/src/dynafu.cpp
  86. 4
      modules/rgbd/src/kinfu.cpp
  87. 4
      modules/rgbd/src/large_kinfu.cpp
  88. 6
      modules/sfm/CMakeLists.txt
  89. 4
      modules/sfm/src/libmv_light/libmv/multiview/robust_estimation.h
  90. 22
      modules/sfm/src/libmv_light/libmv/simple_pipeline/bundle.cc
  91. 2
      modules/surface_matching/src/pose_3d.cpp
  92. 12
      modules/tracking/samples/multitracker.py
  93. 4
      modules/tracking/samples/tracker.py
  94. 2
      modules/wechat_qrcode/samples/qrcode.py
  95. 2
      modules/xfeatures2d/README.md
  96. 12
      modules/xfeatures2d/doc/xfeatures2d.bib
  97. 43
      modules/xfeatures2d/include/opencv2/xfeatures2d.hpp
  98. 36
      modules/xfeatures2d/perf/perf_teblid.cpp
  99. 119
      modules/xfeatures2d/src/beblid.cpp
  100. 4
      modules/xfeatures2d/src/beblid.p256.hpp
  101. Some files were not shown because too many files have changed in this diff Show More

@ -1,627 +1,34 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_ARUCO_HPP__
#define __OPENCV_ARUCO_HPP__
#include <opencv2/core.hpp>
#include <vector>
#include "opencv2/aruco/dictionary.hpp"
/**
* @defgroup aruco ArUco Marker Detection
* This module is dedicated to square fiducial markers (also known as Augmented Reality Markers)
* These markers are useful for easy, fast and robust camera pose estimation.ç
*
* The main functionalities are:
* - Detection of markers in an image
* - Pose estimation from a single marker or from a board/set of markers
* - Detection of ChArUco board for high subpixel accuracy
* - Camera calibration from both, ArUco boards and ChArUco boards.
* - Detection of ChArUco diamond markers
* The samples directory includes easy examples of how to use the module.
*
* The implementation is based on the ArUco Library by R. Muñoz-Salinas and S. Garrido-Jurado @cite Aruco2014.
*
* Markers can also be detected based on the AprilTag 2 @cite wang2016iros fiducial detection method.
*
* @sa S. Garrido-Jurado, R. Muñoz-Salinas, F. J. Madrid-Cuevas, and M. J. Marín-Jiménez. 2014.
* "Automatic generation and detection of highly reliable fiducial markers under occlusion".
* Pattern Recogn. 47, 6 (June 2014), 2280-2292. DOI=10.1016/j.patcog.2014.01.005
*
* @sa http://www.uco.es/investiga/grupos/ava/node/26
*
* This module has been originally developed by Sergio Garrido-Jurado as a project
* for Google Summer of Code 2015 (GSoC 15).
*
*
*/
#include "opencv2/aruco_detector.hpp"
#include "opencv2/aruco/aruco_calib_pose.hpp"
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
enum CornerRefineMethod{
CORNER_REFINE_NONE, ///< Tag and corners detection based on the ArUco approach
CORNER_REFINE_SUBPIX, ///< ArUco approach and refine the corners locations using corner subpixel accuracy
CORNER_REFINE_CONTOUR, ///< ArUco approach and refine the corners locations using the contour-points line fitting
CORNER_REFINE_APRILTAG, ///< Tag and corners detection based on the AprilTag 2 approach @cite wang2016iros
};
/**
* @brief Parameters for the detectMarker process:
* - adaptiveThreshWinSizeMin: minimum window size for adaptive thresholding before finding
* contours (default 3).
* - adaptiveThreshWinSizeMax: maximum window size for adaptive thresholding before finding
* contours (default 23).
* - adaptiveThreshWinSizeStep: increments from adaptiveThreshWinSizeMin to adaptiveThreshWinSizeMax
* during the thresholding (default 10).
* - adaptiveThreshConstant: constant for adaptive thresholding before finding contours (default 7)
* - minMarkerPerimeterRate: determine minimum perimeter for marker contour to be detected. This
* is defined as a rate respect to the maximum dimension of the input image (default 0.03).
* - maxMarkerPerimeterRate: determine maximum perimeter for marker contour to be detected. This
* is defined as a rate respect to the maximum dimension of the input image (default 4.0).
* - polygonalApproxAccuracyRate: minimum accuracy during the polygonal approximation process to
* determine which contours are squares. (default 0.03)
* - minCornerDistanceRate: minimum distance between corners for detected markers relative to its
* perimeter (default 0.05)
* - minDistanceToBorder: minimum distance of any corner to the image border for detected markers
* (in pixels) (default 3)
* - minMarkerDistanceRate: minimum mean distance beetween two marker corners to be considered
* similar, so that the smaller one is removed. The rate is relative to the smaller perimeter
* of the two markers (default 0.05).
* - cornerRefinementMethod: corner refinement method. (CORNER_REFINE_NONE, no refinement.
* CORNER_REFINE_SUBPIX, do subpixel refinement. CORNER_REFINE_CONTOUR use contour-Points,
* CORNER_REFINE_APRILTAG use the AprilTag2 approach). (default CORNER_REFINE_NONE)
* - cornerRefinementWinSize: window size for the corner refinement process (in pixels) (default 5).
* - cornerRefinementMaxIterations: maximum number of iterations for stop criteria of the corner
* refinement process (default 30).
* - cornerRefinementMinAccuracy: minimum error for the stop cristeria of the corner refinement
* process (default: 0.1)
* - markerBorderBits: number of bits of the marker border, i.e. marker border width (default 1).
* - perspectiveRemovePixelPerCell: number of bits (per dimension) for each cell of the marker
* when removing the perspective (default 4).
* - perspectiveRemoveIgnoredMarginPerCell: width of the margin of pixels on each cell not
* considered for the determination of the cell bit. Represents the rate respect to the total
* size of the cell, i.e. perspectiveRemovePixelPerCell (default 0.13)
* - maxErroneousBitsInBorderRate: maximum number of accepted erroneous bits in the border (i.e.
* number of allowed white bits in the border). Represented as a rate respect to the total
* number of bits per marker (default 0.35).
* - minOtsuStdDev: minimun standard deviation in pixels values during the decodification step to
* apply Otsu thresholding (otherwise, all the bits are set to 0 or 1 depending on mean higher
* than 128 or not) (default 5.0)
* - errorCorrectionRate error correction rate respect to the maximun error correction capability
* for each dictionary. (default 0.6).
* - aprilTagMinClusterPixels: reject quads containing too few pixels. (default 5)
* - aprilTagMaxNmaxima: how many corner candidates to consider when segmenting a group of pixels into a quad. (default 10)
* - aprilTagCriticalRad: Reject quads where pairs of edges have angles that are close to straight or close to
* 180 degrees. Zero means that no quads are rejected. (In radians) (default 10*PI/180)
* - aprilTagMaxLineFitMse: When fitting lines to the contours, what is the maximum mean squared error
* allowed? This is useful in rejecting contours that are far from being quad shaped; rejecting
* these quads "early" saves expensive decoding processing. (default 10.0)
* - aprilTagMinWhiteBlackDiff: When we build our model of black & white pixels, we add an extra check that
* the white model must be (overall) brighter than the black model. How much brighter? (in pixel values, [0,255]). (default 5)
* - aprilTagDeglitch: should the thresholded image be deglitched? Only useful for very noisy images. (default 0)
* - aprilTagQuadDecimate: Detection of quads can be done on a lower-resolution image, improving speed at a
* cost of pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still
* done at full resolution. (default 0.0)
* - aprilTagQuadSigma: What Gaussian blur should be applied to the segmented image (used for quad detection?)
* Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values (e.g. 0.8). (default 0.0)
* - detectInvertedMarker: to check if there is a white marker. In order to generate a "white" marker just
* invert a normal marker by using a tilde, ~markerImage. (default false)
* - useAruco3Detection: to enable the new and faster Aruco detection strategy. The most important observation from the authors of
* Romero-Ramirez et al: Speeded up detection of squared fiducial markers (2018) is, that the binary
* code of a marker can be reliably detected if the canonical image (that is used to extract the binary code)
* has a size of minSideLengthCanonicalImg (in practice tau_c=16-32 pixels).
* Link to article: https://www.researchgate.net/publication/325787310_Speeded_Up_Detection_of_Squared_Fiducial_Markers
* In addition, very small markers are barely useful for pose estimation and thus a we can define a minimum marker size that we
* still want to be able to detect (e.g. 50x50 pixel).
* To decouple this from the initial image size they propose to resize the input image
* to (I_w_r, I_h_r) = (tau_c / tau_dot_i) * (I_w, I_h), with tau_dot_i = tau_c + max(I_w,I_h) * tau_i.
* Here tau_i (parameter: minMarkerLengthRatioOriginalImg) is a ratio in the range [0,1].
* If we set this to 0, the smallest marker we can detect
* has a side length of tau_c. If we set it to 1 the marker would fill the entire image.
* For a FullHD video a good value to start with is 0.1.
* - minSideLengthCanonicalImg: minimum side length of a marker in the canonical image.
* Latter is the binarized image in which contours are searched.
* So all contours with a size smaller than minSideLengthCanonicalImg*minSideLengthCanonicalImg will omitted from the search.
* - minMarkerLengthRatioOriginalImg: range [0,1], eq (2) from paper
* The parameter tau_i has a direct influence on the processing speed.
*/
struct CV_EXPORTS_W DetectorParameters {
DetectorParameters();
CV_WRAP static Ptr<DetectorParameters> create();
CV_WRAP bool readDetectorParameters(const FileNode& fn);
CV_PROP_RW int adaptiveThreshWinSizeMin;
CV_PROP_RW int adaptiveThreshWinSizeMax;
CV_PROP_RW int adaptiveThreshWinSizeStep;
CV_PROP_RW double adaptiveThreshConstant;
CV_PROP_RW double minMarkerPerimeterRate;
CV_PROP_RW double maxMarkerPerimeterRate;
CV_PROP_RW double polygonalApproxAccuracyRate;
CV_PROP_RW double minCornerDistanceRate;
CV_PROP_RW int minDistanceToBorder;
CV_PROP_RW double minMarkerDistanceRate;
CV_PROP_RW int cornerRefinementMethod;
CV_PROP_RW int cornerRefinementWinSize;
CV_PROP_RW int cornerRefinementMaxIterations;
CV_PROP_RW double cornerRefinementMinAccuracy;
CV_PROP_RW int markerBorderBits;
CV_PROP_RW int perspectiveRemovePixelPerCell;
CV_PROP_RW double perspectiveRemoveIgnoredMarginPerCell;
CV_PROP_RW double maxErroneousBitsInBorderRate;
CV_PROP_RW double minOtsuStdDev;
CV_PROP_RW double errorCorrectionRate;
// April :: User-configurable parameters.
CV_PROP_RW float aprilTagQuadDecimate;
CV_PROP_RW float aprilTagQuadSigma;
// April :: Internal variables
CV_PROP_RW int aprilTagMinClusterPixels;
CV_PROP_RW int aprilTagMaxNmaxima;
CV_PROP_RW float aprilTagCriticalRad;
CV_PROP_RW float aprilTagMaxLineFitMse;
CV_PROP_RW int aprilTagMinWhiteBlackDiff;
CV_PROP_RW int aprilTagDeglitch;
// to detect white (inverted) markers
CV_PROP_RW bool detectInvertedMarker;
// New Aruco functionality proposed in the paper:
// Romero-Ramirez et al: Speeded up detection of squared fiducial markers (2018)
CV_PROP_RW bool useAruco3Detection;
CV_PROP_RW int minSideLengthCanonicalImg;
CV_PROP_RW float minMarkerLengthRatioOriginalImg;
};
/**
* @brief Basic marker detection
*
* @param image input image
* @param dictionary indicates the type of markers that will be searched
* @param corners vector of detected marker corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers,
* the dimensions of this array is Nx4. The order of the corners is clockwise.
* @param ids vector of identifiers of the detected markers. The identifier is of type int
* (e.g. std::vector<int>). For N detected markers, the size of ids is also N.
* The identifiers have the same order than the markers in the imgPoints array.
* @param parameters marker detection parameters
* @param rejectedImgPoints contains the imgPoints of those squares whose inner code has not a
* correct codification. Useful for debugging purposes.
*
* Performs marker detection in the input image. Only markers included in the specific dictionary
* are searched. For each detected marker, it returns the 2D position of its corner in the image
* and its corresponding identifier.
* Note that this function does not perform pose estimation.
* @note The function does not correct lens distortion or takes it into account. It's recommended to undistort
* input image with corresponging camera model, if camera parameters are known
* @sa undistort, estimatePoseSingleMarkers, estimatePoseBoard
*
*/
@deprecated Use class ArucoDetector
*/
CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr<Dictionary> &dictionary, OutputArrayOfArrays corners,
OutputArray ids, const Ptr<DetectorParameters> &parameters = DetectorParameters::create(),
OutputArrayOfArrays rejectedImgPoints = noArray());
/**
* @brief Pose estimation for single markers
*
* @param corners vector of already detected markers corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers,
* the dimensions of this array should be Nx4. The order of the corners should be clockwise.
* @sa detectMarkers
* @param markerLength the length of the markers' side. The returning translation vectors will
* be in the same unit. Normally, unit is meters.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs array of output rotation vectors (@sa Rodrigues) (e.g. std::vector<cv::Vec3d>).
* Each element in rvecs corresponds to the specific marker in imgPoints.
* @param tvecs array of output translation vectors (e.g. std::vector<cv::Vec3d>).
* Each element in tvecs corresponds to the specific marker in imgPoints.
* @param _objPoints array of object points of all the marker corners
*
* This function receives the detected markers and returns their pose estimation respect to
* the camera individually. So for each marker, one rotation and translation vector is returned.
* The returned transformation is the one that transforms points from each marker coordinate system
* to the camera coordinate system.
* The marker corrdinate system is centered on the middle of the marker, with the Z axis
* perpendicular to the marker plane.
* The coordinates of the four corners of the marker in its own coordinate system are:
* (0, 0, 0), (markerLength, 0, 0),
* (markerLength, markerLength, 0), (0, markerLength, 0)
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
InputArray cameraMatrix, InputArray distCoeffs,
OutputArray rvecs, OutputArray tvecs, OutputArray _objPoints = noArray());
/**
* @brief Board of markers
*
* A board is a set of markers in the 3D space with a common coordinate system.
* The common form of a board of marker is a planar (2D) board, however any 3D layout can be used.
* A Board object is composed by:
* - The object points of the marker corners, i.e. their coordinates respect to the board system.
* - The dictionary which indicates the type of markers of the board
* - The identifier of all the markers in the board.
*/
class CV_EXPORTS_W Board {
public:
/**
* @brief Provide way to create Board by passing necessary data. Specially needed in Python.
*
* @param objPoints array of object points of all the marker corners in the board
* @param dictionary the dictionary of markers employed for this board
* @param ids vector of the identifiers of the markers in the board
*
*/
CV_WRAP static Ptr<Board> create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids);
/**
* @brief Set ids vector
*
* @param ids vector of the identifiers of the markers in the board (should be the same size
* as objPoints)
*
* Recommended way to set ids vector, which will fail if the size of ids does not match size
* of objPoints.
*/
CV_WRAP void setIds(InputArray ids);
/// array of object points of all the marker corners in the board
/// each marker include its 4 corners in this order:
///- objPoints[i][0] - left-top point of i-th marker
///- objPoints[i][1] - right-top point of i-th marker
///- objPoints[i][2] - right-bottom point of i-th marker
///- objPoints[i][3] - left-bottom point of i-th marker
///
/// Markers are placed in a certain order - row by row, left to right in every row.
/// For M markers, the size is Mx4.
CV_PROP std::vector< std::vector< Point3f > > objPoints;
/// the dictionary of markers employed for this board
CV_PROP Ptr<Dictionary> dictionary;
/// vector of the identifiers of the markers in the board (same size than objPoints)
/// The identifiers refers to the board dictionary
CV_PROP_RW std::vector< int > ids;
/// coordinate of the bottom right corner of the board, is set when calling the function create()
CV_PROP Point3f rightBottomBorder;
};
/**
* @brief Planar board with grid arrangement of markers
* More common type of board. All markers are placed in the same plane in a grid arrangement.
* The board can be drawn using drawPlanarBoard() function (@sa drawPlanarBoard)
*/
class CV_EXPORTS_W GridBoard : public Board {
public:
/**
* @brief Draw a GridBoard
*
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of the GridBoard, ready to be printed.
*/
CV_WRAP void draw(Size outSize, OutputArray img, int marginSize = 0, int borderBits = 1);
/**
* @brief Create a GridBoard object
*
* @param markersX number of markers in X direction
* @param markersY number of markers in Y direction
* @param markerLength marker side length (normally in meters)
* @param markerSeparation separation between two markers (same unit as markerLength)
* @param dictionary dictionary of markers indicating the type of markers
* @param firstMarker id of first marker in dictionary to use on board.
* @return the output GridBoard object
*
* This functions creates a GridBoard object given the number of markers in each direction and
* the marker size and marker separation.
*/
CV_WRAP static Ptr<GridBoard> create(int markersX, int markersY, float markerLength,
float markerSeparation, const Ptr<Dictionary> &dictionary, int firstMarker = 0);
/**
*
*/
CV_WRAP Size getGridSize() const { return Size(_markersX, _markersY); }
/**
*
*/
CV_WRAP float getMarkerLength() const { return _markerLength; }
/**
*
*/
CV_WRAP float getMarkerSeparation() const { return _markerSeparation; }
private:
// number of markers in X and Y directions
int _markersX, _markersY;
// marker side length (normally in meters)
float _markerLength;
// separation between markers in the grid
float _markerSeparation;
};
/**
* @brief Pose estimation for a board of markers
*
* @param corners vector of already detected markers corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers, the
* dimensions of this array should be Nx4. The order of the corners should be clockwise.
* @param ids list of identifiers for each marker in corners
* @param board layout of markers in the board. The layout is composed by the marker identifiers
* and the positions of each marker corner in the board reference system.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvec Output vector (e.g. cv::Mat) corresponding to the rotation vector of the board
* (see cv::Rodrigues). Used as initial guess if not empty.
* @param tvec Output vector (e.g. cv::Mat) corresponding to the translation vector of the board.
* @param useExtrinsicGuess defines whether initial guess for \b rvec and \b tvec will be used or not.
* Used as initial guess if not empty.
*
* This function receives the detected markers and returns the pose of a marker board composed
* by those markers.
* A Board of marker has a single world coordinate system which is defined by the board layout.
* The returned transformation is the one that transforms points from the board coordinate system
* to the camera coordinate system.
* Input markers that are not included in the board layout are ignored.
* The function returns the number of markers from the input employed for the board pose estimation.
* Note that returning a 0 means the pose has not been estimated.
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/**
* @brief Refind not detected markers based on the already detected and the board layout
*
* @param image input image
* @param board layout of markers in the board.
* @param detectedCorners vector of already detected marker corners.
* @param detectedIds vector of already detected marker identifiers.
* @param rejectedCorners vector of rejected candidates during the marker detection process.
* @param cameraMatrix optional input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs optional vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param minRepDistance minimum distance between the corners of the rejected candidate and the
* reprojected marker in order to consider it as a correspondence.
* @param errorCorrectionRate rate of allowed erroneous bits respect to the error correction
* capability of the used dictionary. -1 ignores the error correction step.
* @param checkAllOrders Consider the four posible corner orders in the rejectedCorners array.
* If it set to false, only the provided corner order is considered (default true).
* @param recoveredIdxs Optional array to returns the indexes of the recovered candidates in the
* original rejectedCorners array.
* @param parameters marker detection parameters
*
* This function tries to find markers that were not detected in the basic detecMarkers function.
* First, based on the current detected marker and the board layout, the function interpolates
* the position of the missing markers. Then it tries to find correspondence between the reprojected
* markers and the rejected candidates based on the minRepDistance and errorCorrectionRate
* parameters.
* If camera parameters and distortion coefficients are provided, missing markers are reprojected
* using projectPoint function. If not, missing marker projections are interpolated using global
* homography, and all the marker corners in the board must have the same Z coordinate.
*/
CV_EXPORTS_W void refineDetectedMarkers(
InputArray image,const Ptr<Board> &board, InputOutputArrayOfArrays detectedCorners,
InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
float minRepDistance = 10.f, float errorCorrectionRate = 3.f, bool checkAllOrders = true,
OutputArray recoveredIdxs = noArray(), const Ptr<DetectorParameters> &parameters = DetectorParameters::create());
/**
* @brief Draw detected markers in image
*
* @param image input/output image. It must have 1 or 3 channels. The number of channels is not
* altered.
* @param corners positions of marker corners on input image.
* (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers, the dimensions of
* this array should be Nx4. The order of the corners should be clockwise.
* @param ids vector of identifiers for markers in markersCorners .
* Optional, if not provided, ids are not painted.
* @param borderColor color of marker borders. Rest of colors (text color and first corner color)
* are calculated based on this one to improve visualization.
*
* Given an array of detected marker corners and its corresponding ids, this functions draws
* the markers in the image. The marker borders are painted and the markers identifiers if provided.
* Useful for debugging purposes.
*
*/
CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners,
InputArray ids = noArray(),
Scalar borderColor = Scalar(0, 255, 0));
/**
* @brief Draw a canonical marker image
*
* @param dictionary dictionary of markers indicating the type of markers
* @param id identifier of the marker that will be returned. It has to be a valid id
* in the specified dictionary.
* @param sidePixels size of the image in pixels
* @param img output image with the marker
* @param borderBits width of the marker border.
*
* This function returns a marker image in its canonical form (i.e. ready to be printed)
*/
CV_EXPORTS_W void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray img,
int borderBits = 1);
/**
* @brief Draw a planar board
* @sa _drawPlanarBoardImpl
*
* @param board layout of the board that will be drawn. The board should be planar,
* z coordinate is ignored
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of a planar board, ready to be printed. It assumes
* the Board layout specified is planar by ignoring the z coordinates of the object points.
*/
CV_EXPORTS_W void drawPlanarBoard(const Ptr<Board> &board, Size outSize, OutputArray img,
int marginSize = 0, int borderBits = 1);
/**
* @brief Implementation of drawPlanarBoard that accepts a raw Board pointer.
*/
void _drawPlanarBoardImpl(Board *board, Size outSize, OutputArray img,
int marginSize = 0, int borderBits = 1);
/**
* @brief Calibrate a camera using aruco markers
*
* @param corners vector of detected marker corners in all frames.
* The corners should have the same format returned by detectMarkers (see #detectMarkers).
* @param ids list of identifiers for each marker in corners
* @param counter number of markers in each frame so that corners and ids can be split
* @param board Marker Board layout
* @param imageSize Size of the image used only to initialize the intrinsic camera matrix.
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using an Aruco Board. The function receives a list of
* detected markers from several views of the Board. The process is similar to the chessboard
* calibration in calibrateCamera(). The function returns the final re-projection error.
*/
CV_EXPORTS_AS(calibrateCameraArucoExtended) double calibrateCameraAruco(
InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
OutputArray perViewErrors, int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/** @brief It's the same function as #calibrateCameraAruco but without calibration error estimation.
*/
CV_EXPORTS_W double calibrateCameraAruco(
InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs = noArray(), OutputArrayOfArrays tvecs = noArray(), int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/**
* @brief Given a board configuration and a set of detected markers, returns the corresponding
* image points and object points to call solvePnP
*
* @param board Marker board layout.
* @param detectedCorners List of detected marker corners of the board.
* @param detectedIds List of identifiers for each marker.
* @param objPoints Vector of vectors of board marker points in the board coordinate space.
* @param imgPoints Vector of vectors of the projections of board marker corner points.
@deprecated Use class ArucoDetector
*/
CV_EXPORTS_W void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints);
CV_EXPORTS_W void refineDetectedMarkers(InputArray image,const Ptr<Board> &board,
InputOutputArrayOfArrays detectedCorners,
InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
float minRepDistance = 10.f, float errorCorrectionRate = 3.f,
bool checkAllOrders = true, OutputArray recoveredIdxs = noArray(),
const Ptr<DetectorParameters> &parameters = DetectorParameters::create());
//! @}
}
}

@ -0,0 +1,286 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_ARUCO_CALIB_POSE_HPP__
#define __OPENCV_ARUCO_CALIB_POSE_HPP__
#include <opencv2/aruco/board.hpp>
#include <opencv2/calib3d.hpp>
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
/** @brief rvec/tvec define the right handed coordinate system of the marker.
* PatternPos defines center this system and axes direction.
* Axis X (red color) - first coordinate, axis Y (green color) - second coordinate,
* axis Z (blue color) - third coordinate.
* @sa estimatePoseSingleMarkers(), @ref tutorial_aruco_detection
*/
enum PatternPos {
/** @brief The marker coordinate system is centered on the middle of the marker.
* The coordinates of the four corners (CCW order) of the marker in its own coordinate system are:
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0).
*
* These pattern points define this coordinate system:
* ![Image with axes drawn](images/singlemarkersaxes.jpg)
*/
ARUCO_CCW_CENTER,
/** @brief The marker coordinate system is centered on the top-left corner of the marker.
* The coordinates of the four corners (CW order) of the marker in its own coordinate system are:
* (0, 0, 0), (markerLength, 0, 0),
* (markerLength, markerLength, 0), (0, markerLength, 0).
*
* These pattern points define this coordinate system:
* ![Image with axes drawn](images/singlemarkersaxes2.jpg)
*
* These pattern dots are convenient to use with a chessboard/ChArUco board.
*/
ARUCO_CW_TOP_LEFT_CORNER
};
/** @brief Pose estimation parameters
* @param pattern Defines center this system and axes direction (default PatternPos::ARUCO_CCW_CENTER).
* @param useExtrinsicGuess Parameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided
* rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further
* optimizes them (default false).
* @param solvePnPMethod Method for solving a PnP problem: see @ref calib3d_solvePnP_flags (default SOLVEPNP_ITERATIVE).
* @sa PatternPos, solvePnP(), @ref tutorial_aruco_detection
*/
struct CV_EXPORTS_W EstimateParameters {
CV_PROP_RW PatternPos pattern;
CV_PROP_RW bool useExtrinsicGuess;
CV_PROP_RW SolvePnPMethod solvePnPMethod;
EstimateParameters(): pattern(ARUCO_CCW_CENTER), useExtrinsicGuess(false),
solvePnPMethod(SOLVEPNP_ITERATIVE) {}
CV_WRAP static Ptr<EstimateParameters> create() {
return makePtr<EstimateParameters>();
}
};
/**
* @brief Pose estimation for single markers
*
* @param corners vector of already detected markers corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers,
* the dimensions of this array should be Nx4. The order of the corners should be clockwise.
* @sa detectMarkers
* @param markerLength the length of the markers' side. The returning translation vectors will
* be in the same unit. Normally, unit is meters.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs array of output rotation vectors (@sa Rodrigues) (e.g. std::vector<cv::Vec3d>).
* Each element in rvecs corresponds to the specific marker in imgPoints.
* @param tvecs array of output translation vectors (e.g. std::vector<cv::Vec3d>).
* Each element in tvecs corresponds to the specific marker in imgPoints.
* @param objPoints array of object points of all the marker corners
* @param estimateParameters set the origin of coordinate system and the coordinates of the four corners of the marker
* (default estimateParameters.pattern = PatternPos::ARUCO_CCW_CENTER, estimateParameters.useExtrinsicGuess = false,
* estimateParameters.solvePnPMethod = SOLVEPNP_ITERATIVE).
*
* This function receives the detected markers and returns their pose estimation respect to
* the camera individually. So for each marker, one rotation and translation vector is returned.
* The returned transformation is the one that transforms points from each marker coordinate system
* to the camera coordinate system.
* The marker coordinate system is centered on the middle (by default) or on the top-left corner of the marker,
* with the Z axis perpendicular to the marker plane.
* estimateParameters defines the coordinates of the four corners of the marker in its own coordinate system (by default) are:
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0)
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
* @sa @ref tutorial_aruco_detection
* @sa EstimateParameters
* @sa PatternPos
*/
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
InputArray cameraMatrix, InputArray distCoeffs,
OutputArray rvecs, OutputArray tvecs, OutputArray objPoints = noArray(),
const Ptr<EstimateParameters>& estimateParameters = EstimateParameters::create());
/**
* @brief Pose estimation for a board of markers
*
* @param corners vector of already detected markers corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers, the
* dimensions of this array should be Nx4. The order of the corners should be clockwise.
* @param ids list of identifiers for each marker in corners
* @param board layout of markers in the board. The layout is composed by the marker identifiers
* and the positions of each marker corner in the board reference system.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvec Output vector (e.g. cv::Mat) corresponding to the rotation vector of the board
* (see cv::Rodrigues). Used as initial guess if not empty.
* @param tvec Output vector (e.g. cv::Mat) corresponding to the translation vector of the board.
* @param useExtrinsicGuess defines whether initial guess for \b rvec and \b tvec will be used or not.
* Used as initial guess if not empty.
*
* This function receives the detected markers and returns the pose of a marker board composed
* by those markers.
* A Board of marker has a single world coordinate system which is defined by the board layout.
* The returned transformation is the one that transforms points from the board coordinate system
* to the camera coordinate system.
* Input markers that are not included in the board layout are ignored.
* The function returns the number of markers from the input employed for the board pose estimation.
* Note that returning a 0 means the pose has not been estimated.
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/**
* @brief Given a board configuration and a set of detected markers, returns the corresponding
* image points and object points to call solvePnP
*
* @param board Marker board layout.
* @param detectedCorners List of detected marker corners of the board.
* @param detectedIds List of identifiers for each marker.
* @param objPoints Vector of vectors of board marker points in the board coordinate space.
* @param imgPoints Vector of vectors of the projections of board marker corner points.
*/
CV_EXPORTS_W void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints);
/**
* @brief Calibrate a camera using aruco markers
*
* @param corners vector of detected marker corners in all frames.
* The corners should have the same format returned by detectMarkers (see #detectMarkers).
* @param ids list of identifiers for each marker in corners
* @param counter number of markers in each frame so that corners and ids can be split
* @param board Marker Board layout
* @param imageSize Size of the image used only to initialize the intrinsic camera matrix.
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using an Aruco Board. The function receives a list of
* detected markers from several views of the Board. The process is similar to the chessboard
* calibration in calibrateCamera(). The function returns the final re-projection error.
*/
CV_EXPORTS_AS(calibrateCameraArucoExtended)
double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, OutputArray stdDeviationsIntrinsics,
OutputArray stdDeviationsExtrinsics, OutputArray perViewErrors, int flags = 0,
const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/** @overload
* @brief It's the same function as #calibrateCameraAruco but without calibration error estimation.
*/
CV_EXPORTS_W double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArray counter,
const Ptr<Board> &board, Size imageSize, InputOutputArray cameraMatrix,
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs = noArray(),
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS,
30, DBL_EPSILON));
/**
* @brief Pose estimation for a ChArUco board given some of their corners
* @param charucoCorners vector of detected charuco corners
* @param charucoIds list of identifiers for each corner in charucoCorners
* @param board layout of ChArUco board.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvec Output vector (e.g. cv::Mat) corresponding to the rotation vector of the board
* (see cv::Rodrigues).
* @param tvec Output vector (e.g. cv::Mat) corresponding to the translation vector of the board.
* @param useExtrinsicGuess defines whether initial guess for \b rvec and \b tvec will be used or not.
*
* This function estimates a Charuco board pose from some detected corners.
* The function checks if the input corners are enough and valid to perform pose estimation.
* If pose estimation is valid, returns true, else returns false.
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
const Ptr<CharucoBoard> &board, InputArray cameraMatrix,
InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/**
* @brief Calibrate a camera using Charuco corners
*
* @param charucoCorners vector of detected charuco corners per frame
* @param charucoIds list of identifiers for each corner in charucoCorners per frame
* @param board Marker Board layout
* @param imageSize input image size
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using a set of corners of a Charuco Board. The function
* receives a list of detected corners and its identifiers from several views of the Board.
* The function returns the final re-projection error.
*/
CV_EXPORTS_AS(calibrateCameraCharucoExtended)
double calibrateCameraCharuco(InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds,
const Ptr<CharucoBoard> &board, Size imageSize, InputOutputArray cameraMatrix,
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
OutputArray perViewErrors, int flags = 0, const TermCriteria& criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/**
* @brief It's the same function as #calibrateCameraCharuco but without calibration error estimation.
*/
CV_EXPORTS_W double calibrateCameraCharuco(InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds,
const Ptr<CharucoBoard> &board, Size imageSize,
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs = noArray(),
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
const TermCriteria& criteria=TermCriteria(TermCriteria::COUNT +
TermCriteria::EPS, 30, DBL_EPSILON));
//! @}
}
}
#endif

@ -0,0 +1,243 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_ARUCO_BOARD_HPP__
#define __OPENCV_ARUCO_BOARD_HPP__
#include <opencv2/core.hpp>
#include <vector>
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
class Dictionary;
/**
* @brief Board of markers
*
* A board is a set of markers in the 3D space with a common coordinate system.
* The common form of a board of marker is a planar (2D) board, however any 3D layout can be used.
* A Board object is composed by:
* - The object points of the marker corners, i.e. their coordinates respect to the board system.
* - The dictionary which indicates the type of markers of the board
* - The identifier of all the markers in the board.
*/
class CV_EXPORTS_W Board {
public:
CV_WRAP Board();
/** @brief Provide way to create Board by passing necessary data. Specially needed in Python.
* @param objPoints array of object points of all the marker corners in the board
* @param dictionary the dictionary of markers employed for this board
* @param ids vector of the identifiers of the markers in the board
*/
CV_WRAP static Ptr<Board> create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids);
/** @brief Set ids vector
* @param ids vector of the identifiers of the markers in the board (should be the same size
* as objPoints)
*
* Recommended way to set ids vector, which will fail if the size of ids does not match size
* of objPoints.
*/
CV_WRAP void setIds(InputArray ids);
/** @brief change id for ids[index]
* @param index - element index in ids
* @param newId - new value for ids[index], should be less than Dictionary size
*/
CV_WRAP void changeId(int index, int newId);
/** @brief return ids
*/
CV_WRAP const std::vector<int>& getIds() const;
/** @brief set dictionary
*/
CV_WRAP void setDictionary(const Ptr<Dictionary> &dictionary);
/** @brief return dictionary
*/
CV_WRAP Ptr<Dictionary> getDictionary() const;
/** @brief set objPoints
*/
CV_WRAP void setObjPoints(const std::vector<std::vector<Point3f> > &objPoints);
/** @brief get objPoints
*/
CV_WRAP const std::vector<std::vector<Point3f> >& getObjPoints() const;
/** @brief get rightBottomBorder
*/
CV_WRAP const Point3f& getRightBottomBorder() const;
protected:
/** @brief array of object points of all the marker corners in the board each marker include its 4 corners in this order:
* - objPoints[i][0] - left-top point of i-th marker
* - objPoints[i][1] - right-top point of i-th marker
* - objPoints[i][2] - right-bottom point of i-th marker
* - objPoints[i][3] - left-bottom point of i-th marker
*
* Markers are placed in a certain order - row by row, left to right in every row.
* For M markers, the size is Mx4.
*/
CV_PROP std::vector<std::vector<Point3f> > objPoints;
/// the dictionary of markers employed for this board
CV_PROP Ptr<Dictionary> dictionary;
/// coordinate of the bottom right corner of the board, is set when calling the function create()
CV_PROP Point3f rightBottomBorder;
/** @brief vector of the identifiers of the markers in the board (same size than objPoints)
* The identifiers refers to the board dictionary
*/
CV_PROP_RW std::vector<int> ids;
};
/**
* @brief Draw a planar board
* @sa drawPlanarBoard
*
* @param board layout of the board that will be drawn. The board should be planar,
* z coordinate is ignored
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of a planar board, ready to be printed. It assumes
* the Board layout specified is planar by ignoring the z coordinates of the object points.
*/
CV_EXPORTS_W void drawPlanarBoard(const Ptr<Board> &board, Size outSize, OutputArray img,
int marginSize = 0, int borderBits = 1);
/**
* @brief Planar board with grid arrangement of markers
* More common type of board. All markers are placed in the same plane in a grid arrangement.
* The board can be drawn using drawPlanarBoard() function (@sa drawPlanarBoard)
*/
class CV_EXPORTS_W GridBoard : public Board {
public:
CV_WRAP GridBoard();
/**
* @brief Draw a GridBoard
*
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of the GridBoard, ready to be printed.
*/
CV_WRAP void draw(Size outSize, OutputArray img, int marginSize = 0, int borderBits = 1);
/**
* @brief Create a GridBoard object
*
* @param markersX number of markers in X direction
* @param markersY number of markers in Y direction
* @param markerLength marker side length (normally in meters)
* @param markerSeparation separation between two markers (same unit as markerLength)
* @param dictionary dictionary of markers indicating the type of markers
* @param firstMarker id of first marker in dictionary to use on board.
* @return the output GridBoard object
*
* This functions creates a GridBoard object given the number of markers in each direction and
* the marker size and marker separation.
*/
CV_WRAP static Ptr<GridBoard> create(int markersX, int markersY, float markerLength, float markerSeparation,
const Ptr<Dictionary> &dictionary, int firstMarker = 0);
CV_WRAP Size getGridSize() const;
CV_WRAP float getMarkerLength() const;
CV_WRAP float getMarkerSeparation() const;
protected:
struct GridImpl;
Ptr<GridImpl> gridImpl;
friend class CharucoBoard;
};
/**
* @brief ChArUco board
* Specific class for ChArUco boards. A ChArUco board is a planar board where the markers are placed
* inside the white squares of a chessboard. The benefits of ChArUco boards is that they provide
* both, ArUco markers versatility and chessboard corner precision, which is important for
* calibration and pose estimation.
* This class also allows the easy creation and drawing of ChArUco boards.
*/
class CV_EXPORTS_W CharucoBoard : public Board {
public:
CV_WRAP CharucoBoard();
// vector of chessboard 3D corners precalculated
CV_PROP std::vector<Point3f> chessboardCorners;
// for each charuco corner, nearest marker id and nearest marker corner id of each marker
CV_PROP std::vector<std::vector<int> > nearestMarkerIdx;
CV_PROP std::vector<std::vector<int> > nearestMarkerCorners;
/** @brief Draw a ChArUco board
*
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of the ChArUco board, ready to be printed.
*/
CV_WRAP void draw(Size outSize, OutputArray img, int marginSize = 0, int borderBits = 1);
/** @brief Create a CharucoBoard object
* @param squaresX number of chessboard squares in X direction
* @param squaresY number of chessboard squares in Y direction
* @param squareLength chessboard square side length (normally in meters)
* @param markerLength marker side length (same unit than squareLength)
* @param dictionary dictionary of markers indicating the type of markers.
* The first markers in the dictionary are used to fill the white chessboard squares.
* @return the output CharucoBoard object
*
* This functions creates a CharucoBoard object given the number of squares in each direction
* and the size of the markers and chessboard squares.
*/
CV_WRAP static Ptr<CharucoBoard> create(int squaresX, int squaresY, float squareLength,
float markerLength, const Ptr<Dictionary> &dictionary);
CV_WRAP Size getChessboardSize() const;
CV_WRAP float getSquareLength() const;
CV_WRAP float getMarkerLength() const;
protected:
struct CharucoImpl;
Ptr<CharucoImpl> charucoImpl;
};
/**
* @brief test whether the ChArUco markers are collinear
*
* @param board layout of ChArUco board.
* @param charucoIds list of identifiers for each corner in charucoCorners per frame.
* @return bool value, 1 (true) if detected corners form a line, 0 (false) if they do not.
* solvePnP, calibration functions will fail if the corners are collinear (true).
*
* The number of ids in charucoIDs should be <= the number of chessboard corners in the board.
* This functions checks whether the charuco corners are on a straight line (returns true, if so), or not (false).
* Axis parallel, as well as diagonal and other straight lines detected. Degenerate cases:
* for number of charucoIDs <= 2,the function returns true.
*/
CV_EXPORTS_W bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &board, InputArray charucoIds);
//! @}
}
}
#endif

@ -1,47 +1,14 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_CHARUCO_HPP__
#define __OPENCV_CHARUCO_HPP__
#include <opencv2/core.hpp>
#include <vector>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
namespace cv {
@ -50,87 +17,6 @@ namespace aruco {
//! @addtogroup aruco
//! @{
/**
* @brief ChArUco board
* Specific class for ChArUco boards. A ChArUco board is a planar board where the markers are placed
* inside the white squares of a chessboard. The benefits of ChArUco boards is that they provide
* both, ArUco markers versatility and chessboard corner precision, which is important for
* calibration and pose estimation.
* This class also allows the easy creation and drawing of ChArUco boards.
*/
class CV_EXPORTS_W CharucoBoard : public Board {
public:
// vector of chessboard 3D corners precalculated
CV_PROP std::vector< Point3f > chessboardCorners;
// for each charuco corner, nearest marker id and nearest marker corner id of each marker
CV_PROP std::vector< std::vector< int > > nearestMarkerIdx;
CV_PROP std::vector< std::vector< int > > nearestMarkerCorners;
/**
* @brief Draw a ChArUco board
*
* @param outSize size of the output image in pixels.
* @param img output image with the board. The size of this image will be outSize
* and the board will be on the center, keeping the board proportions.
* @param marginSize minimum margins (in pixels) of the board in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of the ChArUco board, ready to be printed.
*/
CV_WRAP void draw(Size outSize, OutputArray img, int marginSize = 0, int borderBits = 1);
/**
* @brief Create a CharucoBoard object
*
* @param squaresX number of chessboard squares in X direction
* @param squaresY number of chessboard squares in Y direction
* @param squareLength chessboard square side length (normally in meters)
* @param markerLength marker side length (same unit than squareLength)
* @param dictionary dictionary of markers indicating the type of markers.
* The first markers in the dictionary are used to fill the white chessboard squares.
* @return the output CharucoBoard object
*
* This functions creates a CharucoBoard object given the number of squares in each direction
* and the size of the markers and chessboard squares.
*/
CV_WRAP static Ptr<CharucoBoard> create(int squaresX, int squaresY, float squareLength,
float markerLength, const Ptr<Dictionary> &dictionary);
/**
*
*/
CV_WRAP Size getChessboardSize() const { return Size(_squaresX, _squaresY); }
/**
*
*/
CV_WRAP float getSquareLength() const { return _squareLength; }
/**
*
*/
CV_WRAP float getMarkerLength() const { return _markerLength; }
private:
void _getNearestMarkerCorners();
// number of markers in X and Y directions
int _squaresX, _squaresY;
// size of chessboard squares side (normally in meters)
float _squareLength;
// marker side length (normally in meters)
float _markerLength;
};
/**
* @brief Interpolate position of ChArUco board corners
* @param markerCorners vector of already detected markers corners. For each marker, its four
@ -161,36 +47,6 @@ CV_EXPORTS_W int interpolateCornersCharuco(InputArrayOfArrays markerCorners, Inp
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray(), int minMarkers = 2);
/**
* @brief Pose estimation for a ChArUco board given some of their corners
* @param charucoCorners vector of detected charuco corners
* @param charucoIds list of identifiers for each corner in charucoCorners
* @param board layout of ChArUco board.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvec Output vector (e.g. cv::Mat) corresponding to the rotation vector of the board
* (see cv::Rodrigues).
* @param tvec Output vector (e.g. cv::Mat) corresponding to the translation vector of the board.
* @param useExtrinsicGuess defines whether initial guess for \b rvec and \b tvec will be used or not.
*
* This function estimates a Charuco board pose from some detected corners.
* The function checks if the input corners are enough and valid to perform pose estimation.
* If pose estimation is valid, returns true, else returns false.
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
const Ptr<CharucoBoard> &board, InputArray cameraMatrix,
InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/**
* @brief Draws a set of Charuco corners
* @param image input/output image. It must have 1 or 3 channels. The number of channels is not
@ -206,60 +62,6 @@ CV_EXPORTS_W void drawDetectedCornersCharuco(InputOutputArray image, InputArray
InputArray charucoIds = noArray(),
Scalar cornerColor = Scalar(255, 0, 0));
/**
* @brief Calibrate a camera using Charuco corners
*
* @param charucoCorners vector of detected charuco corners per frame
* @param charucoIds list of identifiers for each corner in charucoCorners per frame
* @param board Marker Board layout
* @param imageSize input image size
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using a set of corners of a Charuco Board. The function
* receives a list of detected corners and its identifiers from several views of the Board.
* The function returns the final re-projection error.
*/
CV_EXPORTS_AS(calibrateCameraCharucoExtended) double calibrateCameraCharuco(
InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds, const Ptr<CharucoBoard> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
OutputArray perViewErrors, int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/** @brief It's the same function as #calibrateCameraCharuco but without calibration error estimation.
*/
CV_EXPORTS_W double calibrateCameraCharuco(
InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds, const Ptr<CharucoBoard> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs = noArray(), OutputArrayOfArrays tvecs = noArray(), int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/**
* @brief Detect ChArUco Diamond markers
*
@ -335,20 +137,6 @@ CV_EXPORTS_W void drawCharucoDiamond(const Ptr<Dictionary> &dictionary, Vec4i id
int markerLength, OutputArray img, int marginSize = 0,
int borderBits = 1);
/**
* @brief test whether the ChArUco markers are collinear
*
* @param _board layout of ChArUco board.
* @param _charucoIds list of identifiers for each corner in charucoCorners per frame.
* @return bool value, 1 (true) if detected corners form a line, 0 (false) if they do not.
solvePnP, calibration functions will fail if the corners are collinear (true).
*
* The number of ids in charucoIDs should be <= the number of chessboard corners in the board. This functions checks whether the charuco corners are on a straight line (returns true, if so), or not (false). Axis parallel, as well as diagonal and other straight lines detected. Degenerate cases: for number of charucoIDs <= 2, the function returns true.
*/
CV_EXPORTS_W bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &_board,
InputArray _charucoIds);
//! @}
}
}

@ -1,41 +1,6 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_DICTIONARY_HPP__
#define __OPENCV_DICTIONARY_HPP__
@ -66,28 +31,22 @@ class CV_EXPORTS_W Dictionary {
CV_PROP_RW int maxCorrectionBits; // maximum number of bits that can be corrected
/**
*/
Dictionary(const Mat &_bytesList = Mat(), int _markerSize = 0, int _maxcorr = 0);
/**
Dictionary(const Dictionary &_dictionary);
* Dictionary(const Dictionary &_dictionary);
*/
Dictionary(const Ptr<Dictionary> &dictionary);
/**
*/
Dictionary(const Ptr<Dictionary> &_dictionary);
/**
/** @brief returns generateCustomDictionary(nMarkers, markerSize, randomSeed)
* @see generateCustomDictionary
*/
CV_WRAP_AS(create) static Ptr<Dictionary> create(int nMarkers, int markerSize, int randomSeed=0);
/**
/** @brief returns generateCustomDictionary(nMarkers, markerSize, baseDictionary, randomSeed)
* @see generateCustomDictionary
*/
CV_WRAP_AS(create_from) static Ptr<Dictionary> create(int nMarkers, int markerSize,
@ -108,6 +67,7 @@ class CV_EXPORTS_W Dictionary {
* @brief Write a dictionary to FileStorage. Format is the same as in readDictionary().
*/
CV_WRAP void writeDictionary(Ptr<FileStorage>& fs);
/**
* @see getPredefinedDictionary
*/
@ -117,13 +77,13 @@ class CV_EXPORTS_W Dictionary {
* @brief Given a matrix of bits. Returns whether if marker is identified or not.
* It returns by reference the correct id (if any) and the correct rotation
*/
bool identify(const Mat &onlyBits, int &idx, int &rotation, double maxCorrectionRate) const;
CV_WRAP bool identify(const Mat &onlyBits, CV_OUT int &idx, CV_OUT int &rotation, double maxCorrectionRate) const;
/**
* @brief Returns the distance of the input bits to the specific id. If allRotations is true,
* the four posible bits rotation are considered
*/
int getDistanceToId(InputArray bits, int id, bool allRotations = true) const;
CV_WRAP int getDistanceToId(InputArray bits, int id, bool allRotations = true) const;
/**

@ -0,0 +1,436 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_ARUCO_DETECTOR_HPP__
#define __OPENCV_ARUCO_DETECTOR_HPP__
#include <opencv2/aruco/board.hpp>
#include <opencv2/aruco/dictionary.hpp>
/**
* @defgroup aruco ArUco Marker Detection
* This module is dedicated to square fiducial markers (also known as Augmented Reality Markers)
* These markers are useful for easy, fast and robust camera pose estimation.
*
* The main functionality of ArucoDetector class is:
* - Detection of markers in an image
*
* There are even more functionalities implemented in charuco.hpp and aruco_calib_pose.hpp:
* - Pose estimation from a single marker or from a board/set of markers
* - Detection of ChArUco board for high subpixel accuracy
* - Camera calibration from both, ArUco boards and ChArUco boards.
* - Detection of ChArUco diamond markers
* The samples directory includes easy examples of how to use the module.
*
* The implementation is based on the ArUco Library by R. Muñoz-Salinas and S. Garrido-Jurado @cite Aruco2014.
*
* Markers can also be detected based on the AprilTag 2 @cite wang2016iros fiducial detection method.
*
* @sa S. Garrido-Jurado, R. Muñoz-Salinas, F. J. Madrid-Cuevas, and M. J. Marín-Jiménez. 2014.
* "Automatic generation and detection of highly reliable fiducial markers under occlusion".
* Pattern Recogn. 47, 6 (June 2014), 2280-2292. DOI=10.1016/j.patcog.2014.01.005
*
* @sa http://www.uco.es/investiga/grupos/ava/node/26
*
* This module has been originally developed by Sergio Garrido-Jurado as a project
* for Google Summer of Code 2015 (GSoC 15).
*
*
*/
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
enum CornerRefineMethod{
CORNER_REFINE_NONE, ///< Tag and corners detection based on the ArUco approach
CORNER_REFINE_SUBPIX, ///< ArUco approach and refine the corners locations using corner subpixel accuracy
CORNER_REFINE_CONTOUR, ///< ArUco approach and refine the corners locations using the contour-points line fitting
CORNER_REFINE_APRILTAG, ///< Tag and corners detection based on the AprilTag 2 approach @cite wang2016iros
};
/**
* @brief struct DetectorParameters is used by ArucoDetector
*/
struct CV_EXPORTS_W DetectorParameters {
DetectorParameters() {
adaptiveThreshWinSizeMin = 3;
adaptiveThreshWinSizeMax = 23;
adaptiveThreshWinSizeStep = 10;
adaptiveThreshConstant = 7;
minMarkerPerimeterRate = 0.03;
maxMarkerPerimeterRate = 4.;
polygonalApproxAccuracyRate = 0.03;
minCornerDistanceRate = 0.05;
minDistanceToBorder = 3;
minMarkerDistanceRate = 0.05;
cornerRefinementMethod = CORNER_REFINE_NONE;
cornerRefinementWinSize = 5;
cornerRefinementMaxIterations = 30;
cornerRefinementMinAccuracy = 0.1;
markerBorderBits = 1;
perspectiveRemovePixelPerCell = 4;
perspectiveRemoveIgnoredMarginPerCell = 0.13;
maxErroneousBitsInBorderRate = 0.35;
minOtsuStdDev = 5.0;
errorCorrectionRate = 0.6;
aprilTagQuadDecimate = 0.0;
aprilTagQuadSigma = 0.0;
aprilTagMinClusterPixels = 5;
aprilTagMaxNmaxima = 10;
aprilTagCriticalRad = (float)(10* CV_PI /180);
aprilTagMaxLineFitMse = 10.0;
aprilTagMinWhiteBlackDiff = 5;
aprilTagDeglitch = 0;
detectInvertedMarker = false;
useAruco3Detection = false;
minSideLengthCanonicalImg = 32;
minMarkerLengthRatioOriginalImg = 0.0;
};
/** @brief Create a new set of DetectorParameters with default values.
*/
CV_WRAP static Ptr<DetectorParameters> create() {
Ptr<DetectorParameters> params = makePtr<DetectorParameters>();
return params;
}
/**
* @brief Read a new set of DetectorParameters from FileNode (use FileStorage.root()).
*/
CV_WRAP bool readDetectorParameters(const FileNode& fn);
/**
* @brief Write a set of DetectorParameters to FileStorage
*/
CV_WRAP bool writeDetectorParameters(const Ptr<FileStorage>& fs);
/// minimum window size for adaptive thresholding before finding contours (default 3).
CV_PROP_RW int adaptiveThreshWinSizeMin;
/// maximum window size for adaptive thresholding before finding contours (default 23).
CV_PROP_RW int adaptiveThreshWinSizeMax;
/// increments from adaptiveThreshWinSizeMin to adaptiveThreshWinSizeMax during the thresholding (default 10).
CV_PROP_RW int adaptiveThreshWinSizeStep;
/// constant for adaptive thresholding before finding contours (default 7)
CV_PROP_RW double adaptiveThreshConstant;
/** @brief determine minimum perimeter for marker contour to be detected. This is defined as a rate respect to the
* maximum dimension of the input image (default 0.03).
*/
CV_PROP_RW double minMarkerPerimeterRate;
/** @brief determine maximum perimeter for marker contour to be detected. This is defined as a rate respect to
* the maximum dimension of the input image (default 4.0).
*/
CV_PROP_RW double maxMarkerPerimeterRate;
/// minimum accuracy during the polygonal approximation process to determine which contours are squares. (default 0.03)
CV_PROP_RW double polygonalApproxAccuracyRate;
/// minimum distance between corners for detected markers relative to its perimeter (default 0.05)
CV_PROP_RW double minCornerDistanceRate;
/// minimum distance of any corner to the image border for detected markers (in pixels) (default 3)
CV_PROP_RW int minDistanceToBorder;
/** @brief minimum mean distance beetween two marker corners to be considered imilar, so that the
* smaller one is removed. The rate is relative to the smaller perimeter of the two markers (default 0.05).
*/
CV_PROP_RW double minMarkerDistanceRate;
/** @brief default CORNER_REFINE_NONE.
* 0:CORNER_REFINE_NONE, no refinement.
* 1: CORNER_REFINE_SUBPIX, do subpixel refinement.
* 2: CORNER_REFINE_CONTOUR use contour-Points,
* 3: CORNER_REFINE_APRILTAG use the AprilTag2 approach).
*/
CV_PROP_RW int cornerRefinementMethod;
/// window size for the corner refinement process (in pixels) (default 5).
CV_PROP_RW int cornerRefinementWinSize;
/// maximum number of iterations for stop criteria of the corner refinement process (default 30).
CV_PROP_RW int cornerRefinementMaxIterations;
/// minimum error for the stop cristeria of the corner refinement process (default: 0.1)
CV_PROP_RW double cornerRefinementMinAccuracy;
/// number of bits of the marker border, i.e. marker border width (default 1).
CV_PROP_RW int markerBorderBits;
/// number of bits (per dimension) for each cell of the marker when removing the perspective (default 4).
CV_PROP_RW int perspectiveRemovePixelPerCell;
/** @brief width of the margin of pixels on each cell not considered for the
* determination of the cell bit. Represents the rate respect to the total size of the cell, i.e.
* perspectiveRemovePixelPerCell (default 0.13)
*/
CV_PROP_RW double perspectiveRemoveIgnoredMarginPerCell;
/** @brief maximum number of accepted erroneous bits in the border (i.e. number of allowed
* white bits in the border). Represented as a rate respect to the total number of bits per marker (default 0.35).
*/
CV_PROP_RW double maxErroneousBitsInBorderRate;
/** @brief minimun standard deviation in pixels values during the decodification step to apply Otsu
* thresholding (otherwise, all the bits are set to 0 or 1 depending on mean higher than 128 or not) (default 5.0)
*/
CV_PROP_RW double minOtsuStdDev;
/// error correction rate respect to the maximun error correction capability for each dictionary (default 0.6).
CV_PROP_RW double errorCorrectionRate;
/** @brief April :: User-configurable parameters.
* detection of quads can be done on a lower-resolution image, improving speed at a cost of
* pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still
*/
CV_PROP_RW float aprilTagQuadDecimate;
/// what Gaussian blur should be applied to the segmented image (used for quad detection?)
CV_PROP_RW float aprilTagQuadSigma;
// April :: Internal variables
/// reject quads containing too few pixels (default 5).
CV_PROP_RW int aprilTagMinClusterPixels;
/// how many corner candidates to consider when segmenting a group of pixels into a quad (default 10).
CV_PROP_RW int aprilTagMaxNmaxima;
/** @brief reject quads where pairs of edges have angles that are close to straight or close to 180 degrees.
* Zero means that no quads are rejected. (In radians) (default 10*PI/180)
*/
CV_PROP_RW float aprilTagCriticalRad;
/// when fitting lines to the contours, what is the maximum mean squared error
CV_PROP_RW float aprilTagMaxLineFitMse;
/** @brief when we build our model of black & white pixels, we add an extra check that the
* white model must be (overall) brighter than the black model. How much brighter? (in pixel values, [0,255]).
* (default 5)
*/
CV_PROP_RW int aprilTagMinWhiteBlackDiff;
/// should the thresholded image be deglitched? Only useful for very noisy images (default 0).
CV_PROP_RW int aprilTagDeglitch;
/** @brief to check if there is a white marker. In order to generate a "white" marker just invert a
* normal marker by using a tilde, ~markerImage. (default false)
*/
CV_PROP_RW bool detectInvertedMarker;
/** @brief new Aruco functionality proposed in the paper:
* Romero-Ramirez et al: Speeded up detection of squared fiducial markers (2018)
* https://www.researchgate.net/publication/325787310_Speeded_Up_Detection_of_Squared_Fiducial_Markers
*/
/// to enable the new and faster Aruco detection strategy.
CV_PROP_RW bool useAruco3Detection;
/// minimum side length of a marker in the canonical image. Latter is the binarized image in which contours are searched.
CV_PROP_RW int minSideLengthCanonicalImg;
/// range [0,1], eq (2) from paper. The parameter tau_i has a direct influence on the processing speed.
CV_PROP_RW float minMarkerLengthRatioOriginalImg;
};
/**
* @brief struct RefineParameters is used by ArucoDetector
*/
struct CV_EXPORTS_W RefineParameters {
RefineParameters() {
minRepDistance = 10.f;
errorCorrectionRate = 3.f;
checkAllOrders = true;
}
RefineParameters(float _minRepDistance, float _errorCorrectionRate, bool _checkAllOrders):
minRepDistance(_minRepDistance), errorCorrectionRate(_errorCorrectionRate), checkAllOrders(_checkAllOrders) {}
CV_WRAP static Ptr<RefineParameters> create(float _minRepDistance = 10.f, float _errorCorrectionRate = 3.f,
bool _checkAllOrders = true) {
return makePtr<RefineParameters>(_minRepDistance, _errorCorrectionRate, _checkAllOrders);
}
/**
* @brief Read a new set of RefineParameters from FileNode (use FileStorage.root()).
*/
CV_WRAP bool readRefineParameters(const FileNode& fn);
/** @brief Write a set of RefineParameters to FileStorage
*/
CV_WRAP bool writeRefineParameters(const Ptr<FileStorage>& fs);
/** @brief minRepDistance minimum distance between the corners of the rejected candidate and the reprojected marker in
* order to consider it as a correspondence.
*/
CV_PROP_RW float minRepDistance;
/** @brief minRepDistance rate of allowed erroneous bits respect to the error correction
* capability of the used dictionary. -1 ignores the error correction step.
*/
CV_PROP_RW float errorCorrectionRate;
/** @brief checkAllOrders consider the four posible corner orders in the rejectedCorners array.
* If it set to false, only the provided corner order is considered (default true).
*/
CV_PROP_RW bool checkAllOrders;
};
/**
* @brief The main functionality of ArucoDetector class is detection of markers in an image with detectMarkers() method.
* After detecting some markers in the image, you can try to find undetected markers from this dictionary with
* refineDetectedMarkers() method.
* @see DetectorParameters, RefineParameters
*/
class CV_EXPORTS_W ArucoDetector : public Algorithm
{
public:
/// dictionary indicates the type of markers that will be searched
CV_PROP_RW Ptr<Dictionary> dictionary;
/// marker detection parameters, check DetectorParameters docs to see available settings
CV_PROP_RW Ptr<DetectorParameters> params;
/// marker refine parameters
CV_PROP_RW Ptr<RefineParameters> refineParams;
/**
* @brief Basic ArucoDetector constructor
* @param _dictionary indicates the type of markers that will be searched
* @param _params marker detection parameters
* @param _refineParams marker refine detection parameters
*/
CV_WRAP ArucoDetector(const Ptr<Dictionary> &_dictionary = getPredefinedDictionary(DICT_4X4_50),
const Ptr<DetectorParameters> &_params = DetectorParameters::create(),
const Ptr<RefineParameters> &_refineParams = RefineParameters::create()):
dictionary(_dictionary), params(_params), refineParams(_refineParams) {}
CV_WRAP static Ptr<ArucoDetector> create(const Ptr<Dictionary> &_dictionary, const Ptr<DetectorParameters> &_params) {
return makePtr<ArucoDetector>(_dictionary, _params);
}
/**
* @brief Basic marker detection
*
* @param image input image
* @param corners vector of detected marker corners. For each marker, its four corners
* are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers,
* the dimensions of this array is Nx4. The order of the corners is clockwise.
* @param ids vector of identifiers of the detected markers. The identifier is of type int
* (e.g. std::vector<int>). For N detected markers, the size of ids is also N.
* The identifiers have the same order than the markers in the imgPoints array.
* @param rejectedImgPoints contains the imgPoints of those squares whose inner code has not a
* correct codification. Useful for debugging purposes.
*
* Performs marker detection in the input image. Only markers included in the specific dictionary
* are searched. For each detected marker, it returns the 2D position of its corner in the image
* and its corresponding identifier.
* Note that this function does not perform pose estimation.
* @note The function does not correct lens distortion or takes it into account. It's recommended to undistort
* input image with corresponging camera model, if camera parameters are known
* @sa undistort, estimatePoseSingleMarkers, estimatePoseBoard
*/
CV_WRAP void detectMarkers(InputArray image, OutputArrayOfArrays corners, OutputArray ids,
OutputArrayOfArrays rejectedImgPoints = noArray());
/**
* @brief Refind not detected markers based on the already detected and the board layout
*
* @param image input image
* @param board layout of markers in the board.
* @param detectedCorners vector of already detected marker corners.
* @param detectedIds vector of already detected marker identifiers.
* @param rejectedCorners vector of rejected candidates during the marker detection process.
* @param cameraMatrix optional input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs optional vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
* @param recoveredIdxs Optional array to returns the indexes of the recovered candidates in the
* original rejectedCorners array.
*
* This function tries to find markers that were not detected in the basic detecMarkers function.
* First, based on the current detected marker and the board layout, the function interpolates
* the position of the missing markers. Then it tries to find correspondence between the reprojected
* markers and the rejected candidates based on the minRepDistance and errorCorrectionRate
* parameters.
* If camera parameters and distortion coefficients are provided, missing markers are reprojected
* using projectPoint function. If not, missing marker projections are interpolated using global
* homography, and all the marker corners in the board must have the same Z coordinate.
*/
CV_WRAP void refineDetectedMarkers(InputArray image, const Ptr<Board> &board,
InputOutputArrayOfArrays detectedCorners,
InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
OutputArray recoveredIdxs = noArray());
/** @brief Stores algorithm parameters in a file storage
*/
virtual void write(FileStorage& fs) const override {
Ptr<FileStorage> pfs = makePtr<FileStorage>(fs);
dictionary->writeDictionary(pfs);
params->writeDetectorParameters(pfs);
refineParams->writeRefineParameters(pfs);
}
/** @brief simplified API for language bindings
* @overload
*/
CV_WRAP void write(const String& fileName) const {
FileStorage fs(fileName, FileStorage::WRITE);
write(fs);
}
/** @brief Reads algorithm parameters from a file storage
*/
CV_WRAP virtual void read(const FileNode& fn) override {
dictionary->readDictionary(fn);
params->readDetectorParameters(fn);
refineParams->readRefineParameters(fn);
}
};
/**
* @brief Draw detected markers in image
*
* @param image input/output image. It must have 1 or 3 channels. The number of channels is not
* altered.
* @param corners positions of marker corners on input image.
* (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers, the dimensions of
* this array should be Nx4. The order of the corners should be clockwise.
* @param ids vector of identifiers for markers in markersCorners .
* Optional, if not provided, ids are not painted.
* @param borderColor color of marker borders. Rest of colors (text color and first corner color)
* are calculated based on this one to improve visualization.
*
* Given an array of detected marker corners and its corresponding ids, this functions draws
* the markers in the image. The marker borders are painted and the markers identifiers if provided.
* Useful for debugging purposes.
*
*/
CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners,
InputArray ids = noArray(), Scalar borderColor = Scalar(0, 255, 0));
/**
* @brief Draw a canonical marker image
*
* @param dictionary dictionary of markers indicating the type of markers
* @param id identifier of the marker that will be returned. It has to be a valid id
* in the specified dictionary.
* @param sidePixels size of the image in pixels
* @param img output image with the marker
* @param borderBits width of the marker border.
*
* This function returns a marker image in its canonical form (i.e. ready to be printed)
*/
CV_EXPORTS_W void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray img,
int borderBits = 1);
//! @}
}
}
#endif

@ -0,0 +1,58 @@
package org.opencv.test.aruco;
import java.util.ArrayList;
import java.util.List;
import org.opencv.test.OpenCVTestCase;
import org.opencv.core.Scalar;
import org.opencv.core.Mat;
import org.opencv.core.CvType;
import org.opencv.aruco.*;
public class ArucoTest extends OpenCVTestCase {
public void testArucoIssue3133() {
byte[][] marker = {{0,1,1},{1,1,1},{0,1,1}};
Dictionary dictionary = Dictionary.create(1, 3);
dictionary.set_maxCorrectionBits(0);
Mat markerBits = new Mat(3, 3, CvType.CV_8UC1);
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
markerBits.put(i, j, marker[i][j]);
}
}
Mat markerCompressed = Dictionary.getByteListFromBits(markerBits);
assertMatNotEqual(markerCompressed, dictionary.get_bytesList());
dictionary.set_bytesList(markerCompressed);
assertMatEqual(markerCompressed, dictionary.get_bytesList());
}
public void testArucoDetector() {
Dictionary dictionary = Dictionary.get(0);
DetectorParameters detectorParameters = DetectorParameters.create();
ArucoDetector detector = ArucoDetector.create(dictionary, detectorParameters);
Mat markerImage = new Mat();
int id = 1, offset = 5, size = 40;
Aruco.drawMarker(dictionary, id, size, markerImage, detectorParameters.get_markerBorderBits());
Mat image = new Mat(markerImage.rows() + 2*offset, markerImage.cols() + 2*offset,
CvType.CV_8UC1, new Scalar(255));
Mat m = image.submat(offset, size+offset, offset, size+offset);
markerImage.copyTo(m);
List<Mat> corners = new ArrayList();
Mat ids = new Mat();
detector.detectMarkers(image, corners, ids);
assertEquals(1, corners.size());
Mat res = corners.get(0);
assertArrayEquals(new double[]{offset, offset}, res.get(0, 0), 0.0);
assertArrayEquals(new double[]{size + offset - 1, offset}, res.get(0, 1), 0.0);
assertArrayEquals(new double[]{size + offset - 1, size + offset - 1}, res.get(0, 2), 0.0);
assertArrayEquals(new double[]{offset, size + offset - 1}, res.get(0, 3), 0.0);
}
}

@ -19,13 +19,13 @@ class aruco_test(NewOpenCVTests):
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_5X5_250)
board = cv.aruco.CharucoBoard_create(7, 5, 1, 0.5, aruco_dict)
np.testing.assert_array_equal(board.ids.squeeze(), ids)
np.testing.assert_array_equal(board.getIds().squeeze(), ids)
board.ids = rev_ids
np.testing.assert_array_equal(board.ids.squeeze(), rev_ids)
board.setIds(rev_ids)
np.testing.assert_array_equal(board.getIds().squeeze(), rev_ids)
board.setIds(ids)
np.testing.assert_array_equal(board.ids.squeeze(), ids)
np.testing.assert_array_equal(board.getIds().squeeze(), ids)
with self.assertRaises(cv.error):
board.setIds(np.array([0]))
@ -64,6 +64,76 @@ class aruco_test(NewOpenCVTests):
if os.path.exists(filename):
os.remove(filename)
def test_identify(self):
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_4X4_50)
expected_idx = 9
expected_rotation = 2
bit_marker = np.array([[0, 1, 1, 0], [1, 0, 1, 0], [1, 1, 1, 1], [0, 0, 1, 1]], dtype=np.uint8)
check, idx, rotation = aruco_dict.identify(bit_marker, 0)
self.assertTrue(check, True)
self.assertEqual(idx, expected_idx)
self.assertEqual(rotation, expected_rotation)
def test_getDistanceToId(self):
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_4X4_50)
idx = 7
rotation = 3
bit_marker = np.array([[0, 1, 0, 1], [0, 1, 1, 1], [1, 1, 0, 0], [0, 1, 0, 0]], dtype=np.uint8)
dist = aruco_dict.getDistanceToId(bit_marker, idx)
self.assertEqual(dist, 0)
def test_aruco_detector(self):
aruco_params = cv.aruco.DetectorParameters_create()
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_4X4_250)
aruco_detector = cv.aruco.ArucoDetector_create(aruco_dict, aruco_params)
id = 2
marker_size = 100
offset = 10
img_marker = cv.aruco.drawMarker(aruco_dict, id, marker_size, aruco_params.markerBorderBits)
img_marker = np.pad(img_marker, pad_width=offset, mode='constant', constant_values=255)
gold_corners = np.array([[offset, offset],[marker_size+offset-1.0,offset],
[marker_size+offset-1.0,marker_size+offset-1.0],
[offset, marker_size+offset-1.0]], dtype=np.float32)
expected_corners, expected_ids, expected_rejected = cv.aruco.detectMarkers(img_marker, aruco_dict,
parameters=aruco_params)
corners, ids, rejected = aruco_detector.detectMarkers(img_marker)
self.assertEqual(1, len(ids))
self.assertEqual(id, ids[0])
for i in range(0, len(ids)):
np.testing.assert_array_equal(expected_corners[i], corners[i])
np.testing.assert_array_equal(gold_corners, corners[i].reshape(4, 2))
def test_aruco_detector_refine(self):
aruco_params = cv.aruco.DetectorParameters_create()
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_4X4_250)
aruco_detector = cv.aruco.ArucoDetector_create(aruco_dict, aruco_params)
board_size = (3, 4)
board = cv.aruco.GridBoard_create(board_size[0], board_size[1], 5.0, 1.0, aruco_dict)
board_image = board.draw((board_size[0]*50, board_size[1]*50), marginSize=10)
corners, ids, rejected = aruco_detector.detectMarkers(board_image)
self.assertEqual(board_size[0]*board_size[1], len(ids))
part_corners, part_ids, part_rejected = corners[:-1], ids[:-1], list(rejected)
part_rejected.append(corners[-1])
refine_corners, refine_ids, refine_rejected, recovered_ids = aruco_detector.refineDetectedMarkers(board_image, board, part_corners, part_ids, part_rejected)
refine_corners_c, _, _, _ = cv.aruco.refineDetectedMarkers(board_image, board, part_corners, part_ids, part_rejected)
self.assertEqual(board_size[0] * board_size[1], len(refine_ids))
self.assertEqual(1, len(recovered_ids))
for i in range(0, len(ids)):
np.testing.assert_array_equal(refine_corners_c[i], refine_corners[i])
#self.assertEqual(ids[-1], recovered_ids[0])
self.assertEqual(ids[-1], refine_ids[-1])
self.assertEqual((1, 4, 2), refine_corners[0].shape)
np.testing.assert_array_equal(corners, refine_corners)
if __name__ == '__main__':
NewOpenCVTests.bootstrap()

@ -190,6 +190,7 @@ PERF_TEST_P(EstimateAruco, ArucoFirst, ESTIMATE_PARAMS)
detectorParams->minSideLengthCanonicalImg = 32;
detectorParams->minMarkerLengthRatioOriginalImg = 0.04f / numMarkersInRow;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
MarkerPainter painter(markerSize);
auto image_map = painter.getProjectMarkersTile(numMarkersInRow, detectorParams, dictionary);
@ -198,7 +199,7 @@ PERF_TEST_P(EstimateAruco, ArucoFirst, ESTIMATE_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);
@ -221,6 +222,7 @@ PERF_TEST_P(EstimateAruco, ArucoSecond, ESTIMATE_PARAMS)
detectorParams->minSideLengthCanonicalImg = 64;
detectorParams->minMarkerLengthRatioOriginalImg = 0.f;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
const int markerSize = 200;
const int numMarkersInRow = 11;
MarkerPainter painter(markerSize);
@ -231,7 +233,7 @@ PERF_TEST_P(EstimateAruco, ArucoSecond, ESTIMATE_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);
@ -276,6 +278,7 @@ PERF_TEST_P(EstimateLargeAruco, ArucoFHD, ESTIMATE_FHD_PARAMS)
detectorParams->minSideLengthCanonicalImg = get<0>(testParams).minSideLengthCanonicalImg;
detectorParams->minMarkerLengthRatioOriginalImg = get<0>(testParams).minMarkerLengthRatioOriginalImg;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
const int markerSize = get<1>(testParams).first; // 1440 or 480 or 144
const int numMarkersInRow = get<1>(testParams).second; // 1 or 3 or 144
MarkerPainter painter(markerSize); // num pixels is 1440x1440 as in FHD 1920x1080
@ -286,7 +289,7 @@ PERF_TEST_P(EstimateLargeAruco, ArucoFHD, ESTIMATE_FHD_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);

@ -5,7 +5,7 @@
#define __OPENCV_PERF_PRECOMP_HPP__
#include "opencv2/ts.hpp"
#include "opencv2/aruco.hpp"
#include "opencv2/aruco_detector.hpp"
#include "opencv2/calib3d.hpp"
#endif

@ -1,5 +1,5 @@
#include <opencv2/core/hal/hal.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>
using namespace cv;

@ -1,5 +1,5 @@
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/calib3d.hpp>
#include <ctime>

@ -40,7 +40,8 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/highgui.hpp>
#include <opencv2/3d.hpp>
#include <opencv2/calib.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <opencv2/imgproc.hpp>
#include <vector>
#include <iostream>
@ -163,6 +164,8 @@ int main(int argc, char *argv[]) {
vector< vector< int > > allIds;
Size imgSize;
aruco::ArucoDetector detector(dictionary, detectorParams);
while(inputVideo.grab()) {
Mat image, imageCopy;
inputVideo.retrieve(image);
@ -171,10 +174,10 @@ int main(int argc, char *argv[]) {
vector< vector< Point2f > > corners, rejected;
// detect markers
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
// refind strategy to detect more markers
if(refindStrategy) aruco::refineDetectedMarkers(image, board, corners, ids, rejected);
if(refindStrategy) detector.refineDetectedMarkers(image, board, corners, ids, rejected);
// draw results
image.copyTo(imageCopy);

@ -38,7 +38,7 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"

@ -38,7 +38,7 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"

@ -38,7 +38,8 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <vector>
#include <iostream>
#include "aruco_samples_utility.hpp"
@ -135,7 +136,7 @@ int main(int argc, char *argv[]) {
cerr << "Dictionary not specified" << endl;
return 0;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
VideoCapture inputVideo;
int waitTime;
if(!video.empty()) {
@ -168,12 +169,12 @@ int main(int argc, char *argv[]) {
Vec3d rvec, tvec;
// detect markers
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
// refind strategy to detect more markers
if(refindStrategy)
aruco::refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix,
distCoeffs);
detector.refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix,
distCoeffs);
// estimate board pose
int markersOfBoardDetected = 0;

@ -38,7 +38,8 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"
@ -134,7 +135,7 @@ int main(int argc, char *argv[]) {
return 0;
}
}
aruco::ArucoDetector detector(dictionary, detectorParams);
VideoCapture inputVideo;
int waitTime;
if(!video.empty()) {
@ -159,7 +160,7 @@ int main(int argc, char *argv[]) {
vector< Vec3d > rvecs, tvecs;
// detect markers and estimate pose
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
if(estimatePose && ids.size() > 0)
aruco::estimatePoseSingleMarkers(corners, markerLength, camMatrix, distCoeffs, rvecs,
tvecs);

@ -50,7 +50,7 @@ static inline void detectCharucoBoardWithCalibrationPose()
//! [midcornerdet]
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f> > markerCorners;
cv::aruco::detectMarkers(image, board->dictionary, markerCorners, markerIds, params);
cv::aruco::detectMarkers(image, board->getDictionary(), markerCorners, markerIds, params);
//! [midcornerdet]
// if at least one marker detected
if (markerIds.size() > 0) {
@ -100,7 +100,7 @@ static inline void detectCharucoBoardWithoutCalibration()
image.copyTo(imageCopy);
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f> > markerCorners;
cv::aruco::detectMarkers(image, board->dictionary, markerCorners, markerIds, params);
cv::aruco::detectMarkers(image, board->getDictionary(), markerCorners, markerIds, params);
//or
//cv::aruco::detectMarkers(image, dictionary, markerCorners, markerIds, params);
// if at least one marker detected

@ -16,7 +16,7 @@
// because we use a fixed-point 16 bit integer representation with one
// fractional bit.
#include "precomp.hpp"
#include "../precomp.hpp"
#include "apriltag_quad_thresh.hpp"
//#define APRIL_DEBUG
@ -1028,17 +1028,7 @@ int fit_quad(const Ptr<DetectorParameters> &_params, const Mat im, zarray_t *clu
return res;
}
/**
*
* @param nCidx0
* @param nCidx1
* @param nClusters
* @param nW
* @param nH
* @param nquads
* @param td
* @param im
*/
static void do_quad(int nCidx0, int nCidx1, zarray_t &nClusters, int nW, int nH, zarray_t *nquads, const Ptr<DetectorParameters> &td, const Mat im){
CV_Assert(nquads != NULL);
@ -1078,12 +1068,6 @@ static void do_quad(int nCidx0, int nCidx1, zarray_t &nClusters, int nW, int nH,
}
}
/**
*
* @param mIm
* @param parameters
* @param mThresh
*/
void threshold(const Mat mIm, const Ptr<DetectorParameters> &parameters, Mat& mThresh){
int w = mIm.cols, h = mIm.rows;
int s = (unsigned) mIm.step;
@ -1306,14 +1290,7 @@ static void _darken(const Mat &im){
}
#endif
/**
*
* @param parameters
* @param mImg
* @param contours
* @return
*/
zarray_t *apriltag_quad_thresh(const Ptr<DetectorParameters> &parameters, const Mat & mImg, std::vector< std::vector< Point > > &contours){
zarray_t *apriltag_quad_thresh(const Ptr<DetectorParameters> &parameters, const Mat & mImg, std::vector<std::vector<Point > > &contours){
////////////////////////////////////////////////////////
// step 1. threshold the image, creating the edge image.
@ -1499,7 +1476,7 @@ out = Mat::zeros(h, w, CV_8UC3);
zarray_t *cluster;
_zarray_get(clusters, i, &cluster);
std::vector< Point > cnt;
std::vector<Point> cnt;
for (int j = 0; j < _zarray_size(cluster); j++) {
struct pt *p;
_zarray_get_volatile(cluster, j, &p);
@ -1567,4 +1544,123 @@ imwrite("2.5 debug_lines.pnm", out);
return quads;
}
void _apriltag(Mat im_orig, const Ptr<DetectorParameters> & _params, std::vector<std::vector<Point2f> > &candidates,
std::vector<std::vector<Point> > &contours){
///////////////////////////////////////////////////////////
/// Step 1. Detect quads according to requested image decimation
/// and blurring parameters.
Mat quad_im;
if (_params->aprilTagQuadDecimate > 1){
resize(im_orig, quad_im, Size(), 1/_params->aprilTagQuadDecimate, 1/_params->aprilTagQuadDecimate, INTER_AREA);
}
else {
im_orig.copyTo(quad_im);
}
// Apply a Blur
if (_params->aprilTagQuadSigma != 0) {
// compute a reasonable kernel width by figuring that the
// kernel should go out 2 std devs.
//
// max sigma ksz
// 0.499 1 (disabled)
// 0.999 3
// 1.499 5
// 1.999 7
float sigma = fabsf((float) _params->aprilTagQuadSigma);
int ksz = cvFloor(4 * sigma); // 2 std devs in each direction
ksz |= 1; // make odd number
if (ksz > 1) {
if (_params->aprilTagQuadSigma > 0)
GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);
else {
Mat orig;
quad_im.copyTo(orig);
GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);
// SHARPEN the image by subtracting the low frequency components.
for (int y = 0; y < orig.rows; y++) {
for (int x = 0; x < orig.cols; x++) {
int vorig = orig.data[y*orig.step + x];
int vblur = quad_im.data[y*quad_im.step + x];
int v = 2*vorig - vblur;
if (v < 0)
v = 0;
if (v > 255)
v = 255;
quad_im.data[y*quad_im.step + x] = (uint8_t) v;
}
}
}
}
}
#ifdef APRIL_DEBUG
imwrite("1.1 debug_preprocess.pnm", quad_im);
#endif
///////////////////////////////////////////////////////////
/// Step 2. do the Threshold :: get the set of candidate quads
zarray_t *quads = apriltag_quad_thresh(_params, quad_im, contours);
CV_Assert(quads != NULL);
// adjust centers of pixels so that they correspond to the
// original full-resolution image.
if (_params->aprilTagQuadDecimate > 1) {
for (int i = 0; i < _zarray_size(quads); i++) {
struct sQuad *q;
_zarray_get_volatile(quads, i, &q);
for (int j = 0; j < 4; j++) {
q->p[j][0] *= _params->aprilTagQuadDecimate;
q->p[j][1] *= _params->aprilTagQuadDecimate;
}
}
}
#ifdef APRIL_DEBUG
Mat im_quads = im_orig.clone();
im_quads = im_quads*0.5;
srandom(0);
for (int i = 0; i < _zarray_size(quads); i++) {
struct sQuad *quad;
_zarray_get_volatile(quads, i, &quad);
const int bias = 100;
int color = bias + (random() % (255-bias));
line(im_quads, Point(quad->p[0][0], quad->p[0][1]), Point(quad->p[1][0], quad->p[1][1]), color, 1);
line(im_quads, Point(quad->p[1][0], quad->p[1][1]), Point(quad->p[2][0], quad->p[2][1]), color, 1);
line(im_quads, Point(quad->p[2][0], quad->p[2][1]), Point(quad->p[3][0], quad->p[3][1]), color, 1);
line(im_quads, Point(quad->p[3][0], quad->p[3][1]), Point(quad->p[0][0], quad->p[0][1]), color, 1);
}
imwrite("1.2 debug_quads_raw.pnm", im_quads);
#endif
////////////////////////////////////////////////////////////////
/// Step 3. Save the output :: candidate corners
for (int i = 0; i < _zarray_size(quads); i++) {
struct sQuad *quad;
_zarray_get_volatile(quads, i, &quad);
std::vector<Point2f> corners;
corners.push_back(Point2f(quad->p[3][0], quad->p[3][1])); //pA
corners.push_back(Point2f(quad->p[0][0], quad->p[0][1])); //pB
corners.push_back(Point2f(quad->p[1][0], quad->p[1][1])); //pC
corners.push_back(Point2f(quad->p[2][0], quad->p[2][1])); //pD
candidates.push_back(corners);
}
_zarray_destroy(quads);
}
}}

@ -19,7 +19,8 @@
#ifndef _OPENCV_APRIL_QUAD_THRESH_HPP_
#define _OPENCV_APRIL_QUAD_THRESH_HPP_
#include "opencv2/aruco.hpp"
#include <opencv2/imgproc.hpp>
#include "opencv2/aruco_detector.hpp"
#include "unionfind.hpp"
#include "zmaxheap.hpp"
#include "zarray.hpp"
@ -104,22 +105,15 @@ int quad_segment_agg(int sz, struct line_fit_pt *lfps, int indices[4]);
**/
int fit_quad(const Ptr<DetectorParameters> &_params, const Mat im, zarray_t *cluster, struct sQuad *quad);
/**
*
* @param mIm
* @param parameters
* @param mThresh
*/
void threshold(const Mat mIm, const Ptr<DetectorParameters> &parameters, Mat& mThresh);
/**
*
* @param parameters
* @param mImg
* @param contours
* @return
*/
zarray_t *apriltag_quad_thresh(const Ptr<DetectorParameters> &parameters, const Mat & mImg, std::vector< std::vector< Point > > &contours);
zarray_t *apriltag_quad_thresh(const Ptr<DetectorParameters> &parameters, const Mat & mImg,
std::vector<std::vector<Point> > &contours);
void _apriltag(Mat im_orig, const Ptr<DetectorParameters> & _params, std::vector<std::vector<Point2f> > &candidates,
std::vector<std::vector<Point> > &contours);
}}
#endif

@ -12,7 +12,7 @@
// of the authors and should not be interpreted as representing official policies,
// either expressed or implied, of the Regents of The University of Michigan.
#include "precomp.hpp"
#include "../precomp.hpp"
#include "zmaxheap.hpp"

File diff suppressed because it is too large Load Diff

@ -0,0 +1,257 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include <opencv2/aruco/aruco_calib_pose.hpp>
namespace cv {
namespace aruco {
using namespace std;
void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners, InputArray detectedIds,
OutputArray objPoints, OutputArray imgPoints) {
CV_Assert(board->getIds().size() == board->getObjPoints().size());
CV_Assert(detectedIds.total() == detectedCorners.total());
size_t nDetectedMarkers = detectedIds.total();
vector<Point3f > objPnts;
objPnts.reserve(nDetectedMarkers);
vector<Point2f > imgPnts;
imgPnts.reserve(nDetectedMarkers);
// look for detected markers that belong to the board and get their information
for(unsigned int i = 0; i < nDetectedMarkers; i++) {
int currentId = detectedIds.getMat().ptr< int >(0)[i];
for(unsigned int j = 0; j < board->getIds().size(); j++) {
if(currentId == board->getIds()[j]) {
for(int p = 0; p < 4; p++) {
objPnts.push_back(board->getObjPoints()[j][p]);
imgPnts.push_back(detectedCorners.getMat(i).ptr< Point2f >(0)[p]);
}
}
}
}
// create output
Mat(objPnts).copyTo(objPoints);
Mat(imgPnts).copyTo(imgPoints);
}
/**
* @brief Return object points for the system centered in a middle (by default) or in a top left corner of single
* marker, given the marker length
*/
static Mat _getSingleMarkerObjectPoints(float markerLength, const EstimateParameters& estimateParameters) {
CV_Assert(markerLength > 0);
Mat objPoints(4, 1, CV_32FC3);
// set coordinate system in the top-left corner of the marker, with Z pointing out
if (estimateParameters.pattern == ARUCO_CW_TOP_LEFT_CORNER) {
objPoints.ptr<Vec3f>(0)[0] = Vec3f(0.f, 0.f, 0);
objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength, 0.f, 0);
objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength, markerLength, 0);
objPoints.ptr<Vec3f>(0)[3] = Vec3f(0.f, markerLength, 0);
}
else if (estimateParameters.pattern == ARUCO_CCW_CENTER) {
objPoints.ptr<Vec3f>(0)[0] = Vec3f(-markerLength/2.f, markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength/2.f, markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength/2.f, -markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[3] = Vec3f(-markerLength/2.f, -markerLength/2.f, 0);
}
else
CV_Error(Error::StsBadArg, "Unknown estimateParameters pattern");
return objPoints;
}
void estimatePoseSingleMarkers(InputArrayOfArrays _corners, float markerLength,
InputArray _cameraMatrix, InputArray _distCoeffs,
OutputArray _rvecs, OutputArray _tvecs, OutputArray _objPoints,
const Ptr<EstimateParameters>& estimateParameters) {
CV_Assert(markerLength > 0);
Mat markerObjPoints = _getSingleMarkerObjectPoints(markerLength, *estimateParameters);
int nMarkers = (int)_corners.total();
_rvecs.create(nMarkers, 1, CV_64FC3);
_tvecs.create(nMarkers, 1, CV_64FC3);
Mat rvecs = _rvecs.getMat(), tvecs = _tvecs.getMat();
//// for each marker, calculate its pose
parallel_for_(Range(0, nMarkers), [&](const Range& range) {
const int begin = range.start;
const int end = range.end;
for (int i = begin; i < end; i++) {
solvePnP(markerObjPoints, _corners.getMat(i), _cameraMatrix, _distCoeffs, rvecs.at<Vec3d>(i),
tvecs.at<Vec3d>(i), estimateParameters->useExtrinsicGuess, estimateParameters->solvePnPMethod);
}
});
if(_objPoints.needed()){
markerObjPoints.convertTo(_objPoints, -1);
}
}
int estimatePoseBoard(InputArrayOfArrays _corners, InputArray _ids, const Ptr<Board> &board,
InputArray _cameraMatrix, InputArray _distCoeffs, InputOutputArray _rvec,
InputOutputArray _tvec, bool useExtrinsicGuess) {
CV_Assert(_corners.total() == _ids.total());
// get object and image points for the solvePnP function
Mat objPoints, imgPoints;
getBoardObjectAndImagePoints(board, _corners, _ids, objPoints, imgPoints);
CV_Assert(imgPoints.total() == objPoints.total());
if(objPoints.total() == 0) // 0 of the detected markers in board
return 0;
solvePnP(objPoints, imgPoints, _cameraMatrix, _distCoeffs, _rvec, _tvec, useExtrinsicGuess);
// divide by four since all the four corners are concatenated in the array for each marker
return (int)objPoints.total() / 4;
}
/**
* Check if a set of 3d points are enough for calibration. Z coordinate is ignored.
* Only axis parallel lines are considered
*/
static bool _arePointsEnoughForPoseEstimation(const vector<Point3f> &points) {
if(points.size() < 4) return false;
vector<double> sameXValue; // different x values in points
vector<int> sameXCounter; // number of points with the x value in sameXValue
for(unsigned int i = 0; i < points.size(); i++) {
bool found = false;
for(unsigned int j = 0; j < sameXValue.size(); j++) {
if(sameXValue[j] == points[i].x) {
found = true;
sameXCounter[j]++;
}
}
if(!found) {
sameXValue.push_back(points[i].x);
sameXCounter.push_back(1);
}
}
// count how many x values has more than 2 points
int moreThan2 = 0;
for(unsigned int i = 0; i < sameXCounter.size(); i++) {
if(sameXCounter[i] >= 2) moreThan2++;
}
// if we have more than 1 two xvalues with more than 2 points, calibration is ok
if(moreThan2 > 1)
return true;
return false;
}
bool estimatePoseCharucoBoard(InputArray _charucoCorners, InputArray _charucoIds,
const Ptr<CharucoBoard> &_board, InputArray _cameraMatrix, InputArray _distCoeffs,
InputOutputArray _rvec, InputOutputArray _tvec, bool useExtrinsicGuess) {
CV_Assert((_charucoCorners.getMat().total() == _charucoIds.getMat().total()));
// need, at least, 4 corners
if(_charucoIds.getMat().total() < 4) return false;
vector<Point3f> objPoints;
objPoints.reserve(_charucoIds.getMat().total());
for(unsigned int i = 0; i < _charucoIds.getMat().total(); i++) {
int currId = _charucoIds.getMat().at< int >(i);
CV_Assert(currId >= 0 && currId < (int)_board->chessboardCorners.size());
objPoints.push_back(_board->chessboardCorners[currId]);
}
// points need to be in different lines, check if detected points are enough
if(!_arePointsEnoughForPoseEstimation(objPoints)) return false;
solvePnP(objPoints, _charucoCorners, _cameraMatrix, _distCoeffs, _rvec, _tvec, useExtrinsicGuess);
return true;
}
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
OutputArrayOfArrays _tvecs,
OutputArray _stdDeviationsIntrinsics,
OutputArray _stdDeviationsExtrinsics,
OutputArray _perViewErrors,
int flags, const TermCriteria& criteria) {
// for each frame, get properly processed imagePoints and objectPoints for the calibrateCamera
// function
vector<Mat> processedObjectPoints, processedImagePoints;
size_t nFrames = _counter.total();
int markerCounter = 0;
for(size_t frame = 0; frame < nFrames; frame++) {
int nMarkersInThisFrame = _counter.getMat().ptr< int >()[frame];
vector<Mat> thisFrameCorners;
vector<int> thisFrameIds;
CV_Assert(nMarkersInThisFrame > 0);
thisFrameCorners.reserve((size_t) nMarkersInThisFrame);
thisFrameIds.reserve((size_t) nMarkersInThisFrame);
for(int j = markerCounter; j < markerCounter + nMarkersInThisFrame; j++) {
thisFrameCorners.push_back(_corners.getMat(j));
thisFrameIds.push_back(_ids.getMat().ptr< int >()[j]);
}
markerCounter += nMarkersInThisFrame;
Mat currentImgPoints, currentObjPoints;
getBoardObjectAndImagePoints(board, thisFrameCorners, thisFrameIds, currentObjPoints,
currentImgPoints);
if(currentImgPoints.total() > 0 && currentObjPoints.total() > 0) {
processedImagePoints.push_back(currentImgPoints);
processedObjectPoints.push_back(currentObjPoints);
}
}
return calibrateCamera(processedObjectPoints, processedImagePoints, imageSize, _cameraMatrix, _distCoeffs, _rvecs,
_tvecs, _stdDeviationsIntrinsics, _stdDeviationsExtrinsics, _perViewErrors, flags, criteria);
}
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs, int flags, const TermCriteria& criteria) {
return calibrateCameraAruco(_corners, _ids, _counter, board, imageSize, _cameraMatrix, _distCoeffs,
_rvecs, _tvecs, noArray(), noArray(), noArray(), flags, criteria);
}
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize,
InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs,
OutputArray _stdDeviationsIntrinsics,
OutputArray _stdDeviationsExtrinsics,
OutputArray _perViewErrors,
int flags, const TermCriteria& criteria) {
CV_Assert(_charucoIds.total() > 0 && (_charucoIds.total() == _charucoCorners.total()));
// Join object points of charuco corners in a single vector for calibrateCamera() function
vector<vector<Point3f> > allObjPoints;
allObjPoints.resize(_charucoIds.total());
for(unsigned int i = 0; i < _charucoIds.total(); i++) {
unsigned int nCorners = (unsigned int)_charucoIds.getMat(i).total();
CV_Assert(nCorners > 0 && nCorners == _charucoCorners.getMat(i).total());
allObjPoints[i].reserve(nCorners);
for(unsigned int j = 0; j < nCorners; j++) {
int pointId = _charucoIds.getMat(i).at< int >(j);
CV_Assert(pointId >= 0 && pointId < (int)_board->chessboardCorners.size());
allObjPoints[i].push_back(_board->chessboardCorners[pointId]);
}
}
return calibrateCamera(allObjPoints, _charucoCorners, imageSize, _cameraMatrix, _distCoeffs, _rvecs, _tvecs,
_stdDeviationsIntrinsics, _stdDeviationsExtrinsics, _perViewErrors, flags, criteria);
}
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize, InputOutputArray _cameraMatrix,
InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs,
int flags, const TermCriteria& criteria) {
return calibrateCameraCharuco(_charucoCorners, _charucoIds, _board, imageSize, _cameraMatrix, _distCoeffs, _rvecs,
_tvecs, noArray(), noArray(), noArray(), flags, criteria);
}
}
}

File diff suppressed because it is too large Load Diff

@ -0,0 +1,50 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "aruco_utils.hpp"
#include <opencv2/imgproc.hpp>
namespace cv {
namespace aruco {
using namespace std;
void _copyVector2Output(std::vector<std::vector<Point2f> > &vec, OutputArrayOfArrays out, const float scale) {
out.create((int)vec.size(), 1, CV_32FC2);
if(out.isMatVector()) {
for (unsigned int i = 0; i < vec.size(); i++) {
out.create(4, 1, CV_32FC2, i);
Mat &m = out.getMatRef(i);
Mat(Mat(vec[i]).t()*scale).copyTo(m);
}
}
else if(out.isUMatVector()) {
for (unsigned int i = 0; i < vec.size(); i++) {
out.create(4, 1, CV_32FC2, i);
UMat &m = out.getUMatRef(i);
Mat(Mat(vec[i]).t()*scale).copyTo(m);
}
}
else if(out.kind() == _OutputArray::STD_VECTOR_VECTOR){
for (unsigned int i = 0; i < vec.size(); i++) {
out.create(4, 1, CV_32FC2, i);
Mat m = out.getMat(i);
Mat(Mat(vec[i]).t()*scale).copyTo(m);
}
}
else {
CV_Error(cv::Error::StsNotImplemented,
"Only Mat vector, UMat vector, and vector<vector> OutputArrays are currently supported.");
}
}
void _convertToGrey(InputArray _in, OutputArray _out) {
CV_Assert(_in.type() == CV_8UC1 || _in.type() == CV_8UC3);
if(_in.type() == CV_8UC3)
cvtColor(_in, _out, COLOR_BGR2GRAY);
else
_in.copyTo(_out);
}
}
}

@ -0,0 +1,44 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_ARUCO_UTILS_HPP__
#define __OPENCV_ARUCO_UTILS_HPP__
#include <opencv2/core.hpp>
#include <vector>
namespace cv {
namespace aruco {
/**
* @brief Copy the contents of a corners vector to an OutputArray, settings its size.
*/
void _copyVector2Output(std::vector<std::vector<Point2f> > &vec, OutputArrayOfArrays out, const float scale = 1.f);
/**
* @brief Convert input image to gray if it is a 3-channels image
*/
void _convertToGrey(InputArray _in, OutputArray _out);
template<typename T>
inline bool readParameter(const std::string& name, T& parameter, const FileNode& node)
{
if (!node.empty() && !node[name].empty()) {
node[name] >> parameter;
return true;
}
return false;
}
template<typename T>
inline bool readWriteParameter(const std::string& name, T& parameter, const Ptr<FileNode> readNode = nullptr,
const Ptr<FileStorage> writeStorage = nullptr) {
if (!readNode.empty())
return readParameter(name, parameter, *readNode);
*writeStorage << name << parameter;
return true;
}
}
}
#endif

@ -0,0 +1,467 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include <opencv2/imgproc.hpp>
#include <opencv2/aruco/board.hpp>
#include <opencv2/aruco/dictionary.hpp>
namespace cv {
namespace aruco {
using namespace std;
/** @brief Implementation of drawPlanarBoard that accepts a raw Board pointer.
*/
static void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img, int marginSize, int borderBits) {
CV_Assert(!outSize.empty());
CV_Assert(marginSize >= 0);
_img.create(outSize, CV_8UC1);
Mat out = _img.getMat();
out.setTo(Scalar::all(255));
out.adjustROI(-marginSize, -marginSize, -marginSize, -marginSize);
// calculate max and min values in XY plane
CV_Assert(_board->getObjPoints().size() > 0);
float minX, maxX, minY, maxY;
minX = maxX = _board->getObjPoints()[0][0].x;
minY = maxY = _board->getObjPoints()[0][0].y;
for(unsigned int i = 0; i < _board->getObjPoints().size(); i++) {
for(int j = 0; j < 4; j++) {
minX = min(minX, _board->getObjPoints()[i][j].x);
maxX = max(maxX, _board->getObjPoints()[i][j].x);
minY = min(minY, _board->getObjPoints()[i][j].y);
maxY = max(maxY, _board->getObjPoints()[i][j].y);
}
}
float sizeX = maxX - minX;
float sizeY = maxY - minY;
// proportion transformations
float xReduction = sizeX / float(out.cols);
float yReduction = sizeY / float(out.rows);
// determine the zone where the markers are placed
if(xReduction > yReduction) {
int nRows = int(sizeY / xReduction);
int rowsMargins = (out.rows - nRows) / 2;
out.adjustROI(-rowsMargins, -rowsMargins, 0, 0);
} else {
int nCols = int(sizeX / yReduction);
int colsMargins = (out.cols - nCols) / 2;
out.adjustROI(0, 0, -colsMargins, -colsMargins);
}
// now paint each marker
Dictionary &dictionary = *(_board->getDictionary());
Mat marker;
Point2f outCorners[3];
Point2f inCorners[3];
for(unsigned int m = 0; m < _board->getObjPoints().size(); m++) {
// transform corners to markerZone coordinates
for(int j = 0; j < 3; j++) {
Point2f pf = Point2f(_board->getObjPoints()[m][j].x, _board->getObjPoints()[m][j].y);
// move top left to 0, 0
pf -= Point2f(minX, minY);
pf.x = pf.x / sizeX * float(out.cols);
pf.y = pf.y / sizeY * float(out.rows);
outCorners[j] = pf;
}
// get marker
Size dst_sz(outCorners[2] - outCorners[0]); // assuming CCW order
dst_sz.width = dst_sz.height = std::min(dst_sz.width, dst_sz.height); //marker should be square
dictionary.drawMarker(_board->getIds()[m], dst_sz.width, marker, borderBits);
if((outCorners[0].y == outCorners[1].y) && (outCorners[1].x == outCorners[2].x)) {
// marker is aligned to image axes
marker.copyTo(out(Rect(outCorners[0], dst_sz)));
continue;
}
// interpolate tiny marker to marker position in markerZone
inCorners[0] = Point2f(-0.5f, -0.5f);
inCorners[1] = Point2f(marker.cols - 0.5f, -0.5f);
inCorners[2] = Point2f(marker.cols - 0.5f, marker.rows - 0.5f);
// remove perspective
Mat transformation = getAffineTransform(inCorners, outCorners);
warpAffine(marker, out, transformation, out.size(), INTER_LINEAR,
BORDER_TRANSPARENT);
}
}
void drawPlanarBoard(const Ptr<Board> &_board, Size outSize, OutputArray _img, int marginSize,
int borderBits) {
_drawPlanarBoardImpl(_board, outSize, _img, marginSize, borderBits);
}
struct GridBoard::GridImpl {
GridImpl(){};
// number of markers in X and Y directions
int sizeX = 3, sizeY = 3;
// marker side length (normally in meters)
float markerLength = 1.f;
// separation between markers in the grid
float markerSeparation = .5f;
};
GridBoard::GridBoard(): gridImpl(makePtr<GridImpl>()) {}
Board::Board(): dictionary(makePtr<Dictionary>(getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME::DICT_4X4_50))) {}
Ptr<Board> Board::create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids) {
CV_Assert(objPoints.total() == ids.total());
CV_Assert(objPoints.type() == CV_32FC3 || objPoints.type() == CV_32FC1);
std::vector<std::vector<Point3f> > obj_points_vector;
Point3f rightBottomBorder = Point3f(0.f, 0.f, 0.f);
for (unsigned int i = 0; i < objPoints.total(); i++) {
std::vector<Point3f> corners;
Mat corners_mat = objPoints.getMat(i);
if (corners_mat.type() == CV_32FC1)
corners_mat = corners_mat.reshape(3);
CV_Assert(corners_mat.total() == 4);
for (int j = 0; j < 4; j++) {
const Point3f &corner = corners_mat.at<Point3f>(j);
corners.push_back(corner);
rightBottomBorder.x = std::max(rightBottomBorder.x, corner.x);
rightBottomBorder.y = std::max(rightBottomBorder.y, corner.y);
rightBottomBorder.z = std::max(rightBottomBorder.z, corner.z);
}
obj_points_vector.push_back(corners);
}
Ptr<Board> res = makePtr<Board>();
ids.copyTo(res->ids);
res->objPoints = obj_points_vector;
res->dictionary = cv::makePtr<Dictionary>(dictionary);
res->rightBottomBorder = rightBottomBorder;
return res;
}
void Board::setIds(InputArray ids_) {
CV_Assert(objPoints.size() == ids_.total());
ids_.copyTo(this->ids);
}
Ptr<Dictionary> Board::getDictionary() const {
return this->dictionary;
}
void Board::setDictionary(const Ptr<Dictionary> &_dictionary) {
this->dictionary = _dictionary;
}
const std::vector<std::vector<Point3f> >& Board::getObjPoints() const {
return this->objPoints;
}
void Board::setObjPoints(const vector<std::vector<Point3f>> &_objPoints) {
CV_Assert(!_objPoints.empty());
this->objPoints = _objPoints;
rightBottomBorder = _objPoints.front().front();
for (size_t i = 0; i < this->objPoints.size(); i++) {
for (int j = 0; j < 4; j++) {
const Point3f &corner = this->objPoints[i][j];
rightBottomBorder.x = std::max(rightBottomBorder.x, corner.x);
rightBottomBorder.y = std::max(rightBottomBorder.y, corner.y);
rightBottomBorder.z = std::max(rightBottomBorder.z, corner.z);
}
}
}
const Point3f& Board::getRightBottomBorder() const {
return this->rightBottomBorder;
}
const std::vector<int>& Board::getIds() const {
return this->ids;
}
void Board::changeId(int index, int newId) {
CV_Assert(index >= 0 && index < (int)ids.size());
CV_Assert(newId >= 0 && newId < dictionary->bytesList.rows);
this->ids[index] = newId;
}
Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength, float markerSeparation,
const Ptr<Dictionary> &dictionary, int firstMarker) {
CV_Assert(markersX > 0 && markersY > 0 && markerLength > 0 && markerSeparation > 0);
Ptr<GridBoard> res = makePtr<GridBoard>();
res->gridImpl->sizeX = markersX;
res->gridImpl->sizeY = markersY;
res->gridImpl->markerLength = markerLength;
res->gridImpl->markerSeparation = markerSeparation;
res->setDictionary(dictionary);
size_t totalMarkers = (size_t) markersX * markersY;
res->ids.resize(totalMarkers);
std::vector<std::vector<Point3f> > objPoints;
objPoints.reserve(totalMarkers);
// fill ids with first identifiers
for (unsigned int i = 0; i < totalMarkers; i++) {
res->ids[i] = i + firstMarker;
}
// calculate Board objPoints
for (int y = 0; y < markersY; y++) {
for (int x = 0; x < markersX; x++) {
vector <Point3f> corners(4);
corners[0] = Point3f(x * (markerLength + markerSeparation),
y * (markerLength + markerSeparation), 0);
corners[1] = corners[0] + Point3f(markerLength, 0, 0);
corners[2] = corners[0] + Point3f(markerLength, markerLength, 0);
corners[3] = corners[0] + Point3f(0, markerLength, 0);
objPoints.push_back(corners);
}
}
res->setObjPoints(objPoints);
res->rightBottomBorder = Point3f(markersX * markerLength + markerSeparation * (markersX - 1),
markersY * markerLength + markerSeparation * (markersY - 1), 0.f);
return res;
}
void GridBoard::draw(Size outSize, OutputArray _img, int marginSize, int borderBits) {
_drawPlanarBoardImpl((Board*)this, outSize, _img, marginSize, borderBits);
}
Size GridBoard::getGridSize() const {
return Size(gridImpl->sizeX, gridImpl->sizeY);
}
float GridBoard::getMarkerLength() const {
return gridImpl->markerLength;
}
float GridBoard::getMarkerSeparation() const {
return gridImpl->markerSeparation;
}
struct CharucoBoard::CharucoImpl : GridBoard::GridImpl {
// size of chessboard squares side (normally in meters)
float squareLength;
// marker side length (normally in meters)
float markerLength;
};
CharucoBoard::CharucoBoard(): charucoImpl(makePtr<CharucoImpl>()) {}
void CharucoBoard::draw(Size outSize, OutputArray _img, int marginSize, int borderBits) {
CV_Assert(!outSize.empty());
CV_Assert(marginSize >= 0);
_img.create(outSize, CV_8UC1);
_img.setTo(255);
Mat out = _img.getMat();
Mat noMarginsImg =
out.colRange(marginSize, out.cols - marginSize).rowRange(marginSize, out.rows - marginSize);
double totalLengthX, totalLengthY;
totalLengthX = charucoImpl->squareLength * charucoImpl->sizeX;
totalLengthY = charucoImpl->squareLength * charucoImpl->sizeY;
// proportional transformation
double xReduction = totalLengthX / double(noMarginsImg.cols);
double yReduction = totalLengthY / double(noMarginsImg.rows);
// determine the zone where the chessboard is placed
Mat chessboardZoneImg;
if(xReduction > yReduction) {
int nRows = int(totalLengthY / xReduction);
int rowsMargins = (noMarginsImg.rows - nRows) / 2;
chessboardZoneImg = noMarginsImg.rowRange(rowsMargins, noMarginsImg.rows - rowsMargins);
} else {
int nCols = int(totalLengthX / yReduction);
int colsMargins = (noMarginsImg.cols - nCols) / 2;
chessboardZoneImg = noMarginsImg.colRange(colsMargins, noMarginsImg.cols - colsMargins);
}
// determine the margins to draw only the markers
// take the minimum just to be sure
double squareSizePixels = min(double(chessboardZoneImg.cols) / double(charucoImpl->sizeX),
double(chessboardZoneImg.rows) / double(charucoImpl->sizeY));
double diffSquareMarkerLength = (charucoImpl->squareLength - charucoImpl->markerLength) / 2;
int diffSquareMarkerLengthPixels =
int(diffSquareMarkerLength * squareSizePixels / charucoImpl->squareLength);
// draw markers
Mat markersImg;
_drawPlanarBoardImpl(this, chessboardZoneImg.size(), markersImg, diffSquareMarkerLengthPixels, borderBits);
markersImg.copyTo(chessboardZoneImg);
// now draw black squares
for(int y = 0; y < charucoImpl->sizeY; y++) {
for(int x = 0; x < charucoImpl->sizeX; x++) {
if(y % 2 != x % 2) continue; // white corner, dont do anything
double startX, startY;
startX = squareSizePixels * double(x);
startY = squareSizePixels * double(y);
Mat squareZone = chessboardZoneImg.rowRange(int(startY), int(startY + squareSizePixels))
.colRange(int(startX), int(startX + squareSizePixels));
squareZone.setTo(0);
}
}
}
/**
* Fill nearestMarkerIdx and nearestMarkerCorners arrays
*/
static inline void _getNearestMarkerCorners(CharucoBoard &board, float squareLength) {
board.nearestMarkerIdx.resize(board.chessboardCorners.size());
board.nearestMarkerCorners.resize(board.chessboardCorners.size());
unsigned int nMarkers = (unsigned int)board.getIds().size();
unsigned int nCharucoCorners = (unsigned int)board.chessboardCorners.size();
for(unsigned int i = 0; i < nCharucoCorners; i++) {
double minDist = -1; // distance of closest markers
Point3f charucoCorner = board.chessboardCorners[i];
for(unsigned int j = 0; j < nMarkers; j++) {
// calculate distance from marker center to charuco corner
Point3f center = Point3f(0, 0, 0);
for(unsigned int k = 0; k < 4; k++)
center += board.getObjPoints()[j][k];
center /= 4.;
double sqDistance;
Point3f distVector = charucoCorner - center;
sqDistance = distVector.x * distVector.x + distVector.y * distVector.y;
if(j == 0 || fabs(sqDistance - minDist) < cv::pow(0.01 * squareLength, 2)) {
// if same minimum distance (or first iteration), add to nearestMarkerIdx vector
board.nearestMarkerIdx[i].push_back(j);
minDist = sqDistance;
} else if(sqDistance < minDist) {
// if finding a closest marker to the charuco corner
board.nearestMarkerIdx[i].clear(); // remove any previous added marker
board.nearestMarkerIdx[i].push_back(j); // add the new closest marker index
minDist = sqDistance;
}
}
// for each of the closest markers, search the marker corner index closer
// to the charuco corner
for(unsigned int j = 0; j < board.nearestMarkerIdx[i].size(); j++) {
board.nearestMarkerCorners[i].resize(board.nearestMarkerIdx[i].size());
double minDistCorner = -1;
for(unsigned int k = 0; k < 4; k++) {
double sqDistance;
Point3f distVector = charucoCorner - board.getObjPoints()[board.nearestMarkerIdx[i][j]][k];
sqDistance = distVector.x * distVector.x + distVector.y * distVector.y;
if(k == 0 || sqDistance < minDistCorner) {
// if this corner is closer to the charuco corner, assing its index
// to nearestMarkerCorners
minDistCorner = sqDistance;
board.nearestMarkerCorners[i][j] = k;
}
}
}
}
}
Ptr<CharucoBoard> CharucoBoard::create(int squaresX, int squaresY, float squareLength,
float markerLength, const Ptr<Dictionary> &dictionary) {
CV_Assert(squaresX > 1 && squaresY > 1 && markerLength > 0 && squareLength > markerLength);
Ptr<CharucoBoard> res = makePtr<CharucoBoard>();
res->charucoImpl->sizeX = squaresX;
res->charucoImpl->sizeY = squaresY;
res->charucoImpl->squareLength = squareLength;
res->charucoImpl->markerLength = markerLength;
res->setDictionary(dictionary);
std::vector<std::vector<Point3f> > objPoints;
float diffSquareMarkerLength = (squareLength - markerLength) / 2;
// calculate Board objPoints
for(int y = 0; y < squaresY; y++) {
for(int x = 0; x < squaresX; x++) {
if(y % 2 == x % 2) continue; // black corner, no marker here
vector<Point3f> corners(4);
corners[0] = Point3f(x * squareLength + diffSquareMarkerLength,
y * squareLength + diffSquareMarkerLength, 0);
corners[1] = corners[0] + Point3f(markerLength, 0, 0);
corners[2] = corners[0] + Point3f(markerLength, markerLength, 0);
corners[3] = corners[0] + Point3f(0, markerLength, 0);
objPoints.push_back(corners);
// first ids in dictionary
int nextId = (int)res->ids.size();
res->ids.push_back(nextId);
}
}
res->setObjPoints(objPoints);
// now fill chessboardCorners
for(int y = 0; y < squaresY - 1; y++) {
for(int x = 0; x < squaresX - 1; x++) {
Point3f corner;
corner.x = (x + 1) * squareLength;
corner.y = (y + 1) * squareLength;
corner.z = 0;
res->chessboardCorners.push_back(corner);
}
}
res->rightBottomBorder = Point3f(squaresX * squareLength,
squaresY * squareLength, 0.f);
_getNearestMarkerCorners(*res, res->charucoImpl->squareLength);
return res;
}
Size CharucoBoard::getChessboardSize() const { return Size(charucoImpl->sizeX, charucoImpl->sizeY); }
float CharucoBoard::getSquareLength() const { return charucoImpl->squareLength; }
float CharucoBoard::getMarkerLength() const { return charucoImpl->markerLength; }
bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &_board, InputArray _charucoIds) {
unsigned int nCharucoCorners = (unsigned int)_charucoIds.getMat().total();
if (nCharucoCorners <= 2)
return true;
// only test if there are 3 or more corners
CV_Assert( _board->chessboardCorners.size() >= _charucoIds.getMat().total());
Vec<double, 3> point0( _board->chessboardCorners[_charucoIds.getMat().at< int >(0)].x,
_board->chessboardCorners[_charucoIds.getMat().at< int >(0)].y, 1);
Vec<double, 3> point1( _board->chessboardCorners[_charucoIds.getMat().at< int >(1)].x,
_board->chessboardCorners[_charucoIds.getMat().at< int >(1)].y, 1);
// create a line from the first two points.
Vec<double, 3> testLine = point0.cross(point1);
Vec<double, 3> testPoint(0, 0, 1);
double divisor = sqrt(testLine[0]*testLine[0] + testLine[1]*testLine[1]);
CV_Assert(divisor != 0.0);
// normalize the line with normal
testLine /= divisor;
double dotProduct;
for (unsigned int i = 2; i < nCharucoCorners; i++){
testPoint(0) = _board->chessboardCorners[_charucoIds.getMat().at< int >(i)].x;
testPoint(1) = _board->chessboardCorners[_charucoIds.getMat().at< int >(i)].y;
// if testPoint is on testLine, dotProduct will be zero (or very, very close)
dotProduct = testPoint.dot(testLine);
if (std::abs(dotProduct) > 1e-6){
return false;
}
}
// no points found that were off of testLine, return true that all points collinear.
return true;
}
}
}

@ -1,40 +1,6 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "precomp.hpp"
#include "opencv2/aruco/charuco.hpp"
@ -46,187 +12,6 @@ namespace cv {
namespace aruco {
using namespace std;
/**
*/
void CharucoBoard::draw(Size outSize, OutputArray _img, int marginSize, int borderBits) {
CV_Assert(!outSize.empty());
CV_Assert(marginSize >= 0);
_img.create(outSize, CV_8UC1);
_img.setTo(255);
Mat out = _img.getMat();
Mat noMarginsImg =
out.colRange(marginSize, out.cols - marginSize).rowRange(marginSize, out.rows - marginSize);
double totalLengthX, totalLengthY;
totalLengthX = _squareLength * _squaresX;
totalLengthY = _squareLength * _squaresY;
// proportional transformation
double xReduction = totalLengthX / double(noMarginsImg.cols);
double yReduction = totalLengthY / double(noMarginsImg.rows);
// determine the zone where the chessboard is placed
Mat chessboardZoneImg;
if(xReduction > yReduction) {
int nRows = int(totalLengthY / xReduction);
int rowsMargins = (noMarginsImg.rows - nRows) / 2;
chessboardZoneImg = noMarginsImg.rowRange(rowsMargins, noMarginsImg.rows - rowsMargins);
} else {
int nCols = int(totalLengthX / yReduction);
int colsMargins = (noMarginsImg.cols - nCols) / 2;
chessboardZoneImg = noMarginsImg.colRange(colsMargins, noMarginsImg.cols - colsMargins);
}
// determine the margins to draw only the markers
// take the minimum just to be sure
double squareSizePixels = min(double(chessboardZoneImg.cols) / double(_squaresX),
double(chessboardZoneImg.rows) / double(_squaresY));
double diffSquareMarkerLength = (_squareLength - _markerLength) / 2;
int diffSquareMarkerLengthPixels =
int(diffSquareMarkerLength * squareSizePixels / _squareLength);
// draw markers
Mat markersImg;
aruco::_drawPlanarBoardImpl(this, chessboardZoneImg.size(), markersImg,
diffSquareMarkerLengthPixels, borderBits);
markersImg.copyTo(chessboardZoneImg);
// now draw black squares
for(int y = 0; y < _squaresY; y++) {
for(int x = 0; x < _squaresX; x++) {
if(y % 2 != x % 2) continue; // white corner, dont do anything
double startX, startY;
startX = squareSizePixels * double(x);
startY = squareSizePixels * double(y);
Mat squareZone = chessboardZoneImg.rowRange(int(startY), int(startY + squareSizePixels))
.colRange(int(startX), int(startX + squareSizePixels));
squareZone.setTo(0);
}
}
}
/**
*/
Ptr<CharucoBoard> CharucoBoard::create(int squaresX, int squaresY, float squareLength,
float markerLength, const Ptr<Dictionary> &dictionary) {
CV_Assert(squaresX > 1 && squaresY > 1 && markerLength > 0 && squareLength > markerLength);
Ptr<CharucoBoard> res = makePtr<CharucoBoard>();
res->_squaresX = squaresX;
res->_squaresY = squaresY;
res->_squareLength = squareLength;
res->_markerLength = markerLength;
res->dictionary = dictionary;
float diffSquareMarkerLength = (squareLength - markerLength) / 2;
// calculate Board objPoints
for(int y = 0; y < squaresY; y++) {
for(int x = 0; x < squaresX; x++) {
if(y % 2 == x % 2) continue; // black corner, no marker here
vector<Point3f> corners(4);
corners[0] = Point3f(x * squareLength + diffSquareMarkerLength,
y * squareLength + diffSquareMarkerLength, 0);
corners[1] = corners[0] + Point3f(markerLength, 0, 0);
corners[2] = corners[0] + Point3f(markerLength, markerLength, 0);
corners[3] = corners[0] + Point3f(0, markerLength, 0);
res->objPoints.push_back(corners);
// first ids in dictionary
int nextId = (int)res->ids.size();
res->ids.push_back(nextId);
}
}
// now fill chessboardCorners
for(int y = 0; y < squaresY - 1; y++) {
for(int x = 0; x < squaresX - 1; x++) {
Point3f corner;
corner.x = (x + 1) * squareLength;
corner.y = (y + 1) * squareLength;
corner.z = 0;
res->chessboardCorners.push_back(corner);
}
}
res->rightBottomBorder = Point3f(squaresX * squareLength,
squaresY * squareLength, 0.f);
res->_getNearestMarkerCorners();
return res;
}
/**
* Fill nearestMarkerIdx and nearestMarkerCorners arrays
*/
void CharucoBoard::_getNearestMarkerCorners() {
nearestMarkerIdx.resize(chessboardCorners.size());
nearestMarkerCorners.resize(chessboardCorners.size());
unsigned int nMarkers = (unsigned int)ids.size();
unsigned int nCharucoCorners = (unsigned int)chessboardCorners.size();
for(unsigned int i = 0; i < nCharucoCorners; i++) {
double minDist = -1; // distance of closest markers
Point3f charucoCorner = chessboardCorners[i];
for(unsigned int j = 0; j < nMarkers; j++) {
// calculate distance from marker center to charuco corner
Point3f center = Point3f(0, 0, 0);
for(unsigned int k = 0; k < 4; k++)
center += objPoints[j][k];
center /= 4.;
double sqDistance;
Point3f distVector = charucoCorner - center;
sqDistance = distVector.x * distVector.x + distVector.y * distVector.y;
if(j == 0 || fabs(sqDistance - minDist) < cv::pow(0.01 * _squareLength, 2)) {
// if same minimum distance (or first iteration), add to nearestMarkerIdx vector
nearestMarkerIdx[i].push_back(j);
minDist = sqDistance;
} else if(sqDistance < minDist) {
// if finding a closest marker to the charuco corner
nearestMarkerIdx[i].clear(); // remove any previous added marker
nearestMarkerIdx[i].push_back(j); // add the new closest marker index
minDist = sqDistance;
}
}
// for each of the closest markers, search the marker corner index closer
// to the charuco corner
for(unsigned int j = 0; j < nearestMarkerIdx[i].size(); j++) {
nearestMarkerCorners[i].resize(nearestMarkerIdx[i].size());
double minDistCorner = -1;
for(unsigned int k = 0; k < 4; k++) {
double sqDistance;
Point3f distVector = charucoCorner - objPoints[nearestMarkerIdx[i][j]][k];
sqDistance = distVector.x * distVector.x + distVector.y * distVector.y;
if(k == 0 || sqDistance < minDistCorner) {
// if this corner is closer to the charuco corner, assing its index
// to nearestMarkerCorners
minDistCorner = sqDistance;
nearestMarkerCorners[i][j] = k;
}
}
}
}
}
/**
* Remove charuco corners if any of their minMarkers closest markers has not been detected
*/
@ -247,7 +32,7 @@ static int _filterCornersWithoutMinMarkers(const Ptr<CharucoBoard> &_board,
int totalMarkers = 0; // nomber of closest marker detected
// look for closest markers
for(unsigned int m = 0; m < _board->nearestMarkerIdx[currentCharucoId].size(); m++) {
int markerId = _board->ids[_board->nearestMarkerIdx[currentCharucoId][m]];
int markerId = _board->getIds()[_board->nearestMarkerIdx[currentCharucoId][m]];
bool found = false;
for(unsigned int k = 0; k < _allArucoIds.getMat().total(); k++) {
if(_allArucoIds.getMat().at< int >(k) == markerId) {
@ -357,7 +142,7 @@ static void _getMaximumSubPixWindowSizes(InputArrayOfArrays markerCorners, Input
// calculate the distance to each of the closest corner of each closest marker
for(unsigned int j = 0; j < board->nearestMarkerIdx[i].size(); j++) {
// find marker
int markerId = board->ids[board->nearestMarkerIdx[i][j]];
int markerId = board->getIds()[board->nearestMarkerIdx[i][j]];
int markerIdx = -1;
for(unsigned int k = 0; k < markerIds.getMat().total(); k++) {
if(markerIds.getMat().at< int >(k) == markerId) {
@ -389,7 +174,6 @@ static void _getMaximumSubPixWindowSizes(InputArrayOfArrays markerCorners, Input
}
/**
* Interpolate charuco corners using approximated pose estimation
*/
@ -433,7 +217,6 @@ static int _interpolateCornersCharucoApproxCalib(InputArrayOfArrays _markerCorne
}
/**
* Interpolate charuco corners using local homography
*/
@ -455,16 +238,18 @@ static int _interpolateCornersCharucoLocalHom(InputArrayOfArrays _markerCorners,
vector< bool > validTransform(nMarkers, false);
const auto& ids = _board->getIds();
for(unsigned int i = 0; i < nMarkers; i++) {
vector< Point2f > markerObjPoints2D;
int markerId = _markerIds.getMat().at< int >(i);
vector< int >::const_iterator it = find(_board->ids.begin(), _board->ids.end(), markerId);
if(it == _board->ids.end()) continue;
int boardIdx = (int)std::distance<std::vector<int>::const_iterator>(_board->ids.begin(), it);
vector<Point2f> markerObjPoints2D;
int markerId = _markerIds.getMat().at<int>(i);
auto it = find(ids.begin(), ids.end(), markerId);
if(it == ids.end()) continue;
auto boardIdx = it - ids.begin();
markerObjPoints2D.resize(4);
for(unsigned int j = 0; j < 4; j++)
markerObjPoints2D[j] =
Point2f(_board->objPoints[boardIdx][j].x, _board->objPoints[boardIdx][j].y);
Point2f(_board->getObjPoints()[boardIdx][j].x, _board->getObjPoints()[boardIdx][j].y);
transformations[i] = getPerspectiveTransform(markerObjPoints2D, _markerCorners.getMat(i));
@ -483,7 +268,7 @@ static int _interpolateCornersCharucoLocalHom(InputArrayOfArrays _markerCorners,
vector< Point2f > interpolatedPositions;
for(unsigned int j = 0; j < _board->nearestMarkerIdx[i].size(); j++) {
int markerId = _board->ids[_board->nearestMarkerIdx[i][j]];
int markerId = _board->getIds()[_board->nearestMarkerIdx[i][j]];
int markerIdx = -1;
for(unsigned int k = 0; k < _markerIds.getMat().total(); k++) {
if(_markerIds.getMat().at< int >(k) == markerId) {
@ -525,9 +310,6 @@ static int _interpolateCornersCharucoLocalHom(InputArrayOfArrays _markerCorners,
}
/**
*/
int interpolateCornersCharuco(InputArrayOfArrays _markerCorners, InputArray _markerIds,
InputArray _image, const Ptr<CharucoBoard> &_board,
OutputArray _charucoCorners, OutputArray _charucoIds,
@ -551,9 +333,6 @@ int interpolateCornersCharuco(InputArrayOfArrays _markerCorners, InputArray _mar
}
/**
*/
void drawDetectedCornersCharuco(InputOutputArray _image, InputArray _charucoCorners,
InputArray _charucoIds, Scalar cornerColor) {
@ -581,128 +360,10 @@ void drawDetectedCornersCharuco(InputOutputArray _image, InputArray _charucoCorn
}
/**
* Check if a set of 3d points are enough for calibration. Z coordinate is ignored.
* Only axis parallel lines are considered
*/
static bool _arePointsEnoughForPoseEstimation(const vector< Point3f > &points) {
if(points.size() < 4) return false;
vector< double > sameXValue; // different x values in points
vector< int > sameXCounter; // number of points with the x value in sameXValue
for(unsigned int i = 0; i < points.size(); i++) {
bool found = false;
for(unsigned int j = 0; j < sameXValue.size(); j++) {
if(sameXValue[j] == points[i].x) {
found = true;
sameXCounter[j]++;
}
}
if(!found) {
sameXValue.push_back(points[i].x);
sameXCounter.push_back(1);
}
}
// count how many x values has more than 2 points
int moreThan2 = 0;
for(unsigned int i = 0; i < sameXCounter.size(); i++) {
if(sameXCounter[i] >= 2) moreThan2++;
}
// if we have more than 1 two xvalues with more than 2 points, calibration is ok
if(moreThan2 > 1)
return true;
else
return false;
}
/**
*/
bool estimatePoseCharucoBoard(InputArray _charucoCorners, InputArray _charucoIds,
const Ptr<CharucoBoard> &_board, InputArray _cameraMatrix, InputArray _distCoeffs,
InputOutputArray _rvec, InputOutputArray _tvec, bool useExtrinsicGuess) {
CV_Assert((_charucoCorners.getMat().total() == _charucoIds.getMat().total()));
// need, at least, 4 corners
if(_charucoIds.getMat().total() < 4) return false;
vector< Point3f > objPoints;
objPoints.reserve(_charucoIds.getMat().total());
for(unsigned int i = 0; i < _charucoIds.getMat().total(); i++) {
int currId = _charucoIds.getMat().at< int >(i);
CV_Assert(currId >= 0 && currId < (int)_board->chessboardCorners.size());
objPoints.push_back(_board->chessboardCorners[currId]);
}
// points need to be in different lines, check if detected points are enough
if(!_arePointsEnoughForPoseEstimation(objPoints)) return false;
solvePnP(objPoints, _charucoCorners, _cameraMatrix, _distCoeffs, _rvec, _tvec, useExtrinsicGuess);
return true;
}
/**
*/
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize,
InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs,
OutputArray _stdDeviationsIntrinsics,
OutputArray _stdDeviationsExtrinsics,
OutputArray _perViewErrors,
int flags, TermCriteria criteria) {
CV_Assert(_charucoIds.total() > 0 && (_charucoIds.total() == _charucoCorners.total()));
// Join object points of charuco corners in a single vector for calibrateCamera() function
vector< vector< Point3f > > allObjPoints;
allObjPoints.resize(_charucoIds.total());
for(unsigned int i = 0; i < _charucoIds.total(); i++) {
unsigned int nCorners = (unsigned int)_charucoIds.getMat(i).total();
CV_Assert(nCorners > 0 && nCorners == _charucoCorners.getMat(i).total());
allObjPoints[i].reserve(nCorners);
for(unsigned int j = 0; j < nCorners; j++) {
int pointId = _charucoIds.getMat(i).at< int >(j);
CV_Assert(pointId >= 0 && pointId < (int)_board->chessboardCorners.size());
allObjPoints[i].push_back(_board->chessboardCorners[pointId]);
}
}
return calibrateCamera(allObjPoints, _charucoCorners, imageSize, _cameraMatrix, _distCoeffs,
_rvecs, _tvecs, _stdDeviationsIntrinsics, _stdDeviationsExtrinsics,
_perViewErrors, flags, criteria);
}
/**
*/
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize,
InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs, int flags,
TermCriteria criteria) {
return calibrateCameraCharuco(_charucoCorners, _charucoIds, _board, imageSize, _cameraMatrix, _distCoeffs, _rvecs,
_tvecs, noArray(), noArray(), noArray(), flags, criteria);
}
/**
*/
void detectCharucoDiamond(InputArray _image, InputArrayOfArrays _markerCorners,
InputArray _markerIds, float squareMarkerLengthRate,
OutputArrayOfArrays _diamondCorners, OutputArray _diamondIds,
InputArray _cameraMatrix, InputArray _distCoeffs, Ptr<Dictionary> dictionary) {
CV_Assert(_markerIds.total() > 0 && _markerIds.total() == _markerCorners.total());
const float minRepDistanceRate = 1.302455f;
@ -759,20 +420,19 @@ void detectCharucoDiamond(InputArray _image, InputArrayOfArrays _markerCorners,
}
}
if(candidates.size() < 3) break; // we need at least 3 free markers
// modify charuco layout id to make sure all the ids are different than current id
for(int k = 1; k < 4; k++)
_charucoDiamondLayout->ids[k] = currentId + 1 + k;
_charucoDiamondLayout->changeId(k, currentId + 1 + k);
// current id is assigned to [0], so it is the marker on the top
_charucoDiamondLayout->ids[0] = currentId;
_charucoDiamondLayout->changeId(0, currentId);
// try to find the rest of markers in the diamond
vector< int > acceptedIdxs;
Ptr<Board> _b = _charucoDiamondLayout.staticCast<Board>();
aruco::refineDetectedMarkers(grey, _b,
currentMarker, currentMarkerId,
candidates, noArray(), noArray(), minRepDistance, -1, false,
acceptedIdxs);
Ptr<RefineParameters> refineParameters = makePtr<RefineParameters>(minRepDistance, -1, false);
ArucoDetector detector(dictionary, DetectorParameters::create(), refineParameters);
detector.refineDetectedMarkers(grey, _b, currentMarker, currentMarkerId, candidates, noArray(), noArray(),
acceptedIdxs);
// if found, we have a diamond
if(currentMarker.size() == 4) {
@ -827,13 +487,8 @@ void detectCharucoDiamond(InputArray _image, InputArrayOfArrays _markerCorners,
}
/**
*/
void drawCharucoDiamond(const Ptr<Dictionary> &dictionary, Vec4i ids, int squareLength, int markerLength,
OutputArray _img, int marginSize, int borderBits) {
CV_Assert(squareLength > 0 && markerLength > 0 && squareLength > markerLength);
CV_Assert(marginSize >= 0 && borderBits > 0);
@ -843,19 +498,15 @@ void drawCharucoDiamond(const Ptr<Dictionary> &dictionary, Vec4i ids, int square
// assign the charuco marker ids
for(int i = 0; i < 4; i++)
board->ids[i] = ids[i];
board->changeId(i, ids[i]);
Size outSize(3 * squareLength + 2 * marginSize, 3 * squareLength + 2 * marginSize);
board->draw(outSize, _img, marginSize, borderBits);
}
/**
*/
void drawDetectedDiamonds(InputOutputArray _image, InputArrayOfArrays _corners,
InputArray _ids, Scalar borderColor) {
CV_Assert(_image.getMat().total() != 0 &&
(_image.getMat().channels() == 1 || _image.getMat().channels() == 3));
CV_Assert((_corners.total() == _ids.total()) || _ids.total() == 0);
@ -896,59 +547,5 @@ void drawDetectedDiamonds(InputOutputArray _image, InputArrayOfArrays _corners,
}
}
/**
@param board layout of ChArUco board.
* @param image charucoIds list of identifiers for each corner in charucoCorners.
* @return bool value, 1 (true) for detected corners form a line, 0 for non-linear.
solvePnP will fail if the corners are collinear (true).
* Check that the set of charuco markers in _charucoIds does not identify a straight line on
the charuco board. Axis parallel, as well as diagonal and other straight lines detected.
*/
bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &_board, InputArray _charucoIds){
unsigned int nCharucoCorners = (unsigned int)_charucoIds.getMat().total();
if (nCharucoCorners <= 2)
return true;
// only test if there are 3 or more corners
CV_Assert( _board->chessboardCorners.size() >= _charucoIds.getMat().total());
Vec<double, 3> point0( _board->chessboardCorners[_charucoIds.getMat().at< int >(0)].x,
_board->chessboardCorners[_charucoIds.getMat().at< int >(0)].y,
1);
Vec<double, 3> point1( _board->chessboardCorners[_charucoIds.getMat().at< int >(1)].x,
_board->chessboardCorners[_charucoIds.getMat().at< int >(1)].y,
1);
// create a line from the first two points.
Vec<double, 3> testLine = point0.cross(point1);
Vec<double, 3> testPoint(0, 0, 1);
double divisor = sqrt(testLine[0]*testLine[0] + testLine[1]*testLine[1]);
CV_Assert( divisor != 0);
// normalize the line with normal
testLine /= divisor;
double dotProduct;
for (unsigned int i = 2; i < nCharucoCorners; i++){
testPoint(0) = _board->chessboardCorners[_charucoIds.getMat().at< int >(i)].x;
testPoint(1) = _board->chessboardCorners[_charucoIds.getMat().at< int >(i)].y;
// if testPoint is on testLine, dotProduct will be zero (or very, very close)
dotProduct = testPoint.dot(testLine);
if (std::abs(dotProduct) > 1e-6){
return false;
}
}
// no points found that were off of testLine, return true that all points collinear.
return true;
}
}
}

@ -1,57 +1,22 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "precomp.hpp"
#include "opencv2/aruco/dictionary.hpp"
#include <opencv2/core.hpp>
#include <opencv2/imgproc.hpp>
#include "predefined_dictionaries.hpp"
#include "predefined_dictionaries_apriltag.hpp"
#include "opencv2/core/hal/hal.hpp"
#include "precomp.hpp"
#include "aruco_utils.hpp"
#include "predefined_dictionaries.hpp"
#include "apriltag/predefined_dictionaries_apriltag.hpp"
#include <opencv2/aruco/dictionary.hpp>
namespace cv {
namespace aruco {
using namespace std;
/**
*/
Dictionary::Dictionary(const Ptr<Dictionary> &_dictionary) {
markerSize = _dictionary->markerSize;
maxCorrectionBits = _dictionary->maxCorrectionBits;
@ -59,8 +24,6 @@ Dictionary::Dictionary(const Ptr<Dictionary> &_dictionary) {
}
/**
*/
Dictionary::Dictionary(const Mat &_bytesList, int _markerSize, int _maxcorr) {
markerSize = _markerSize;
maxCorrectionBits = _maxcorr;
@ -68,54 +31,40 @@ Dictionary::Dictionary(const Mat &_bytesList, int _markerSize, int _maxcorr) {
}
/**
*/
Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize, int randomSeed) {
const Ptr<Dictionary> baseDictionary = makePtr<Dictionary>();
return create(nMarkers, markerSize, baseDictionary, randomSeed);
}
/**
*/
Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize,
const Ptr<Dictionary> &baseDictionary, int randomSeed) {
return generateCustomDictionary(nMarkers, markerSize, baseDictionary, randomSeed);
}
template<typename T>
static inline bool readParameter(const FileNode& node, T& parameter)
{
if (!node.empty()) {
node >> parameter;
return true;
}
return false;
}
bool Dictionary::readDictionary(const cv::FileNode& fn)
{
bool Dictionary::readDictionary(const cv::FileNode& fn) {
int nMarkers = 0, _markerSize = 0;
if (fn.empty() || !readParameter(fn["nmarkers"], nMarkers) || !readParameter(fn["markersize"], _markerSize))
if (fn.empty() || !readParameter("nmarkers", nMarkers, fn) || !readParameter("markersize", _markerSize, fn))
return false;
Mat bytes(0, 0, CV_8UC1), marker(_markerSize, _markerSize, CV_8UC1);
std::string markerString;
for (int i = 0; i < nMarkers; i++) {
std::ostringstream ostr;
ostr << i;
if (!readParameter(fn["marker_" + ostr.str()], markerString))
if (!readParameter("marker_" + ostr.str(), markerString, fn))
return false;
for (int j = 0; j < (int) markerString.size(); j++)
marker.at<unsigned char>(j) = (markerString[j] == '0') ? 0 : 1;
bytes.push_back(Dictionary::getByteListFromBits(marker));
}
int _maxCorrectionBits = 0;
readParameter(fn["maxCorrectionBits"], _maxCorrectionBits);
readParameter("maxCorrectionBits", _maxCorrectionBits, fn);
*this = Dictionary(bytes, _markerSize, _maxCorrectionBits);
return true;
}
void Dictionary::writeDictionary(Ptr<FileStorage>& fs) {
*fs << "nmarkers" << bytesList.rows;
*fs << "markersize" << markerSize;
@ -133,18 +82,13 @@ void Dictionary::writeDictionary(Ptr<FileStorage>& fs) {
}
}
/**
*/
Ptr<Dictionary> Dictionary::get(int dict) {
return getPredefinedDictionary(dict);
}
/**
*/
bool Dictionary::identify(const Mat &onlyBits, int &idx, int &rotation,
double maxCorrectionRate) const {
bool Dictionary::identify(const Mat &onlyBits, int &idx, int &rotation, double maxCorrectionRate) const {
CV_Assert(onlyBits.rows == markerSize && onlyBits.cols == markerSize);
int maxCorrectionRecalculed = int(double(maxCorrectionBits) * maxCorrectionRate);
@ -182,8 +126,6 @@ bool Dictionary::identify(const Mat &onlyBits, int &idx, int &rotation,
}
/**
*/
int Dictionary::getDistanceToId(InputArray bits, int id, bool allRotations) const {
CV_Assert(id >= 0 && id < bytesList.rows);
@ -207,12 +149,7 @@ int Dictionary::getDistanceToId(InputArray bits, int id, bool allRotations) cons
}
/**
* @brief Draw a canonical marker image
*/
void Dictionary::drawMarker(int id, int sidePixels, OutputArray _img, int borderBits) const {
CV_Assert(sidePixels >= (markerSize + 2*borderBits));
CV_Assert(id < bytesList.rows);
CV_Assert(borderBits > 0);
@ -234,11 +171,6 @@ void Dictionary::drawMarker(int id, int sidePixels, OutputArray _img, int border
}
/**
* @brief Transform matrix of bits to list of bytes in the 4 rotations
*/
Mat Dictionary::getByteListFromBits(const Mat &bits) {
// integer ceil
int nbytes = (bits.cols * bits.rows + 8 - 1) / 8;
@ -277,10 +209,6 @@ Mat Dictionary::getByteListFromBits(const Mat &bits) {
}
/**
* @brief Transform list of bytes to matrix of bits
*/
Mat Dictionary::getBitsFromByteList(const Mat &byteList, int markerSize) {
CV_Assert(byteList.total() > 0 &&
byteList.total() >= (unsigned int)markerSize * markerSize / 8 &&
@ -315,9 +243,7 @@ Mat Dictionary::getBitsFromByteList(const Mat &byteList, int markerSize) {
}
Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name)
{
Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name) {
// DictionaryData constructors calls
// moved out of globals so construted on first use, which allows lazy-loading of opencv dll
static const Dictionary DICT_ARUCO_DATA = Dictionary(Mat(1024, (5 * 5 + 7) / 8, CV_8UC4, (uchar*)DICT_ARUCO_BYTES), 5, 0);
@ -438,8 +364,7 @@ static int _getSelfDistance(const Mat &marker) {
return minHamming;
}
/**
*/
Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize,
const Ptr<Dictionary> &baseDictionary, int randomSeed) {
RNG rng((uint64)(randomSeed));
@ -530,8 +455,6 @@ Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize,
}
/**
*/
Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize, int randomSeed) {
Ptr<Dictionary> baseDictionary = makePtr<Dictionary>();
return generateCustomDictionary(nMarkers, markerSize, baseDictionary, randomSeed);

@ -1,43 +1,6 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2014, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_CCALIB_PRECOMP__
#define __OPENCV_CCALIB_PRECOMP__

@ -1,40 +1,6 @@
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.
License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)
Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the names of the copyright holders nor the names of the contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
namespace {

@ -65,16 +65,16 @@ static inline void projectMarker(Mat& img, Ptr<aruco::Board> board, int markerIn
// canonical image
Mat markerImg;
const int markerSizePixels = 100;
aruco::drawMarker(board->dictionary, board->ids[markerIndex], markerSizePixels, markerImg, markerBorder);
aruco::drawMarker(board->getDictionary(), board->getIds()[markerIndex], markerSizePixels, markerImg, markerBorder);
// projected corners
Mat distCoeffs(5, 1, CV_64FC1, Scalar::all(0));
vector< Point2f > corners;
vector<Point2f> corners;
// get max coordinate of board
Point3f maxCoord = board->rightBottomBorder;
Point3f maxCoord = board->getRightBottomBorder();
// copy objPoints
vector<Point3f> objPoints = board->objPoints[markerIndex];
vector<Point3f> objPoints = board->getObjPoints()[markerIndex];
// move the marker to the origin
for (size_t i = 0; i < objPoints.size(); i++)
objPoints[i] -= (maxCoord / 2.f);
@ -82,7 +82,7 @@ static inline void projectMarker(Mat& img, Ptr<aruco::Board> board, int markerIn
projectPoints(objPoints, rvec, tvec, cameraMatrix, distCoeffs, corners);
// get perspective transform
vector< Point2f > originalCorners;
vector<Point2f> originalCorners;
originalCorners.push_back(Point2f(0, 0));
originalCorners.push_back(Point2f((float)markerSizePixels, 0));
originalCorners.push_back(Point2f((float)markerSizePixels, (float)markerSizePixels));
@ -115,7 +115,7 @@ static inline Mat projectBoard(Ptr<aruco::GridBoard>& board, Mat cameraMatrix, d
getSyntheticRT(yaw, pitch, distance, rvec, tvec);
Mat img = Mat(imageSize, CV_8UC1, Scalar::all(255));
for (unsigned int index = 0; index < board->ids.size(); index++) {
for (unsigned int index = 0; index < board->getIds().size(); index++) {
projectMarker(img, board.staticCast<aruco::Board>(), index, cameraMatrix, rvec, tvec, markerBorder);
}

@ -57,8 +57,7 @@ CV_ArucoDetectionSimple::CV_ArucoDetectionSimple() {}
void CV_ArucoDetectionSimple::run(int) {
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250));
// 20 images
for(int i = 0; i < 20; i++) {
@ -74,7 +73,7 @@ void CV_ArucoDetectionSimple::run(int) {
for(int x = 0; x < 2; x++) {
Mat marker;
int id = i * 4 + y * 2 + x;
aruco::drawMarker(dictionary, id, markerSidePixels, marker);
aruco::drawMarker(detector.dictionary, id, markerSidePixels, marker);
Point2f firstCorner =
Point2f(markerSidePixels / 2.f + x * (1.5f * markerSidePixels),
markerSidePixels / 2.f + y * (1.5f * markerSidePixels));
@ -95,9 +94,8 @@ void CV_ArucoDetectionSimple::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
// check detection results
for(unsigned int m = 0; m < groundTruthIds.size(); m++) {
@ -277,7 +275,9 @@ void CV_ArucoDetectionPerspective::run(int) {
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
cameraMatrix.at< double >(1, 2) = imgSize.height / 2;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 1;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
// detect from different positions
for(double distance = 0.1; distance < 0.7; distance += 0.2) {
@ -288,13 +288,11 @@ void CV_ArucoDetectionPerspective::run(int) {
iter++;
vector< Point2f > groundTruthCorners;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 1;
params->markerBorderBits = markerBorder;
/// create synthetic image
Mat img=
projectMarker(dictionary, currentId, cameraMatrix, deg2rad(yaw), deg2rad(pitch),
projectMarker(detector.dictionary, currentId, cameraMatrix, deg2rad(yaw), deg2rad(pitch),
distance, imgSize, markerBorder, groundTruthCorners, szEnclosed);
// marker :: Inverted
if(ArucoAlgParams::DETECT_INVERTED_MARKER == arucoAlgParams){
@ -314,7 +312,7 @@ void CV_ArucoDetectionPerspective::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
// check results
if(ids.size() != 1 || (ids.size() == 1 && ids[0] != currentId)) {
@ -360,8 +358,8 @@ CV_ArucoDetectionMarkerSize::CV_ArucoDetectionMarkerSize() {}
void CV_ArucoDetectionMarkerSize::run(int) {
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
int markerSide = 20;
int imageSize = 200;
@ -372,17 +370,16 @@ void CV_ArucoDetectionMarkerSize::run(int) {
// create synthetic image
Mat img = Mat(imageSize, imageSize, CV_8UC1, Scalar::all(255));
aruco::drawMarker(dictionary, id, markerSide, marker);
aruco::drawMarker(detector.dictionary, id, markerSide, marker);
Mat aux = img.colRange(30, 30 + markerSide).rowRange(50, 50 + markerSide);
marker.copyTo(aux);
vector< vector< Point2f > > corners;
vector< int > ids;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
// set a invalid minMarkerPerimeterRate
params->minMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) + 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::minMarkerPerimeterRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -391,7 +388,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
// set an valid minMarkerPerimeterRate
params->minMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) - 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::minMarkerPerimeterRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -400,7 +397,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
// set a invalid maxMarkerPerimeterRate
params->maxMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) - 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::maxMarkerPerimeterRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -409,7 +406,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
// set an valid maxMarkerPerimeterRate
params->maxMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) + 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::maxMarkerPerimeterRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -436,30 +433,32 @@ CV_ArucoBitCorrection::CV_ArucoBitCorrection() {}
void CV_ArucoBitCorrection::run(int) {
Ptr<aruco::Dictionary> _dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::Dictionary &dictionary = *_dictionary;
aruco::Dictionary dictionary2 = *_dictionary;
Ptr<aruco::Dictionary> _dictionary1 = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::Dictionary> _dictionary2 = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::Dictionary &dictionary1 = *_dictionary1;
aruco::Dictionary &dictionary2 = *_dictionary2;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
aruco::ArucoDetector detector1(_dictionary1, params);
int markerSide = 50;
int imageSize = 150;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
// 10 markers
for(int l = 0; l < 10; l++) {
Mat marker;
int id = 10 + l * 20;
Mat currentCodeBytes = dictionary.bytesList.rowRange(id, id + 1);
Mat currentCodeBytes = dictionary1.bytesList.rowRange(id, id + 1);
// 5 valid cases
for(int i = 0; i < 5; i++) {
// how many bit errors (the error is low enough so it can be corrected)
params->errorCorrectionRate = 0.2 + i * 0.1;
int errors =
(int)std::floor(dictionary.maxCorrectionBits * params->errorCorrectionRate - 1.);
(int)std::floor(dictionary1.maxCorrectionBits * params->errorCorrectionRate - 1.);
// create erroneous marker in currentCodeBits
Mat currentCodeBits =
aruco::Dictionary::getBitsFromByteList(currentCodeBytes, dictionary.markerSize);
aruco::Dictionary::getBitsFromByteList(currentCodeBytes, dictionary1.markerSize);
for(int e = 0; e < errors; e++) {
currentCodeBits.ptr< unsigned char >()[2 * e] =
!currentCodeBits.ptr< unsigned char >()[2 * e];
@ -476,7 +475,7 @@ void CV_ArucoBitCorrection::run(int) {
// try to detect using original dictionary
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::detectMarkers(img, _dictionary, corners, ids, params);
detector1.detectMarkers(img, corners, ids);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in bit correction");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -489,11 +488,11 @@ void CV_ArucoBitCorrection::run(int) {
// how many bit errors (the error is too high to be corrected)
params->errorCorrectionRate = 0.2 + i * 0.1;
int errors =
(int)std::floor(dictionary.maxCorrectionBits * params->errorCorrectionRate + 1.);
(int)std::floor(dictionary1.maxCorrectionBits * params->errorCorrectionRate + 1.);
// create erroneous marker in currentCodeBits
Mat currentCodeBits =
aruco::Dictionary::getBitsFromByteList(currentCodeBytes, dictionary.markerSize);
aruco::Dictionary::getBitsFromByteList(currentCodeBytes, dictionary1.markerSize);
for(int e = 0; e < errors; e++) {
currentCodeBits.ptr< unsigned char >()[2 * e] =
!currentCodeBits.ptr< unsigned char >()[2 * e];
@ -502,9 +501,9 @@ void CV_ArucoBitCorrection::run(int) {
// dictionary3 is only composed by the modified marker (in its original form)
Ptr<aruco::Dictionary> _dictionary3 = makePtr<aruco::Dictionary>(
dictionary2.bytesList.rowRange(id, id + 1).clone(),
dictionary.markerSize,
dictionary.maxCorrectionBits);
dictionary1.markerSize,
dictionary1.maxCorrectionBits);
aruco::ArucoDetector detector3(_dictionary3, params);
// add erroneous marker to dictionary2 in order to create the erroneous marker image
Mat currentCodeBytesError = aruco::Dictionary::getByteListFromBits(currentCodeBits);
currentCodeBytesError.copyTo(dictionary2.bytesList.rowRange(id, id + 1));
@ -516,7 +515,7 @@ void CV_ArucoBitCorrection::run(int) {
// try to detect using dictionary3, it should fail
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::detectMarkers(img, _dictionary3, corners, ids, params);
detector3.detectMarkers(img, corners, ids);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::errorCorrectionRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
@ -569,8 +568,7 @@ TEST(CV_ArucoTutorial, can_find_singlemarkersoriginal)
{
string img_path = cvtest::findDataFile("singlemarkersoriginal.jpg", false);
Mat image = imread(img_path);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250));
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
@ -584,7 +582,7 @@ TEST(CV_ArucoTutorial, can_find_singlemarkersoriginal)
for (size_t i = 0; i < N; i++)
mapGoldCorners[goldCornersIds[i]] = goldCorners[i];
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
ASSERT_EQ(N, ids.size());
for (size_t i = 0; i < N; i++)
@ -609,9 +607,10 @@ TEST(CV_ArucoTutorial, can_find_gboriginal)
FileStorage fs(dictPath, FileStorage::READ);
dictionary->aruco::Dictionary::readDictionary(fs.root()); // set marker from tutorial_dict.yml
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(dictionary, detectorParams);
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
const size_t N = 35ull;
@ -638,7 +637,7 @@ TEST(CV_ArucoTutorial, can_find_gboriginal)
for (int i = 0; i < static_cast<int>(N); i++)
mapGoldCorners[i] = goldCorners[i];
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
ASSERT_EQ(N, ids.size());
@ -657,8 +656,7 @@ TEST(CV_ArucoTutorial, can_find_gboriginal)
TEST(CV_ArucoDetectMarkers, regression_3192)
{
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_4X4_50);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_4X4_50));
vector< int > markerIds;
vector<vector<Point2f> > markerCorners;
string imgPath = cvtest::findDataFile("aruco/regression_3192.png");
@ -670,7 +668,7 @@ TEST(CV_ArucoDetectMarkers, regression_3192)
for (size_t i = 0; i < N; i++)
mapGoldCorners[goldCornersIds[i]] = goldCorners[i];
aruco::detectMarkers(image, dictionary, markerCorners, markerIds, detectorParams);
detector.detectMarkers(image, markerCorners, markerIds);
ASSERT_EQ(N, markerIds.size());
for (size_t i = 0; i < N; i++)
@ -688,9 +686,8 @@ TEST(CV_ArucoDetectMarkers, regression_3192)
TEST(CV_ArucoDetectMarkers, regression_2492)
{
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_5X5_50);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
detectorParams->minMarkerDistanceRate = 0.026;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_5X5_50));
detector.params->minMarkerDistanceRate = 0.026;
vector< int > markerIds;
vector<vector<Point2f> > markerCorners;
string imgPath = cvtest::findDataFile("aruco/regression_2492.png");
@ -705,7 +702,7 @@ TEST(CV_ArucoDetectMarkers, regression_2492)
for (size_t i = 0; i < N; i++)
mapGoldCorners[goldCornersIds[i]].push_back(goldCorners[i]);
aruco::detectMarkers(image, dictionary, markerCorners, markerIds, detectorParams);
detector.detectMarkers(image, markerCorners, markerIds);
ASSERT_EQ(N, markerIds.size());
for (size_t i = 0; i < N; i++)
@ -746,11 +743,10 @@ struct ArucoThreading: public testing::TestWithParam<cv::aruco::CornerRefineMeth
TEST_P(ArucoThreading, number_of_threads_does_not_change_results)
{
cv::Ptr<cv::aruco::DetectorParameters> params = cv::aruco::DetectorParameters::create();
// We are not testing against different dictionaries
// As we are interested mostly in small images, smaller
// markers is better -> 4x4
cv::Ptr<cv::aruco::Dictionary> dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_50);
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_4X4_50));
// Height of the test image can be chosen quite freely
// We aim to test against small images as in those the
@ -762,19 +758,19 @@ TEST_P(ArucoThreading, number_of_threads_does_not_change_results)
// Create a test image
cv::Mat img_marker;
cv::aruco::drawMarker(dictionary, 23, height_marker, img_marker, 1);
cv::aruco::drawMarker(detector.dictionary, 23, height_marker, img_marker, 1);
// Copy to bigger image to get a white border
cv::Mat img(height_img, height_img, CV_8UC1, cv::Scalar(255));
img_marker.copyTo(img(cv::Rect(shift, shift, height_marker, height_marker)));
params->cornerRefinementMethod = GetParam();
detector.params->cornerRefinementMethod = GetParam();
std::vector<std::vector<cv::Point2f> > original_corners;
std::vector<int> original_ids;
{
NumThreadsSetter thread_num_setter(1);
cv::aruco::detectMarkers(img, dictionary, original_corners, original_ids, params);
detector.detectMarkers(img, original_corners, original_ids);
}
ASSERT_EQ(original_ids.size(), 1ull);
@ -787,7 +783,7 @@ TEST_P(ArucoThreading, number_of_threads_does_not_change_results)
std::vector<std::vector<cv::Point2f> > corners;
std::vector<int> ids;
cv::aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.detectMarkers(img, corners, ids);
// If we don't find any markers, the test is broken
ASSERT_EQ(ids.size(), 1ull);

@ -55,6 +55,8 @@ class CV_ArucoBoardPose : public cvtest::BaseTest {
public:
CV_ArucoBoardPose(ArucoAlgParams arucoAlgParams)
{
Ptr<aruco::DetectorParameters> params;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3) {
@ -63,10 +65,11 @@ class CV_ArucoBoardPose : public cvtest::BaseTest {
params->minSideLengthCanonicalImg = 16;
params->errorCorrectionRate = 0.8;
}
detector = aruco::ArucoDetector(dictionary, params);
}
protected:
Ptr<aruco::DetectorParameters> params;
aruco::ArucoDetector detector;
void run(int);
};
@ -75,8 +78,7 @@ void CV_ArucoBoardPose::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, detector.dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
@ -87,41 +89,43 @@ void CV_ArucoBoardPose::run(int) {
for(double distance = 0.2; distance <= 0.4; distance += 0.15) {
for(int yaw = -55; yaw <= 50; yaw += 25) {
for(int pitch = -55; pitch <= 50; pitch += 25) {
for(unsigned int i = 0; i < gridboard->ids.size(); i++)
gridboard->ids[i] = (iter + int(i)) % 250;
vector<int> tmpIds;
for(unsigned int i = 0; i < gridboard->getIds().size(); i++)
tmpIds.push_back((iter + int(i)) % 250);
gridboard->setIds(tmpIds);
int markerBorder = iter % 2 + 1;
iter++;
// create synthetic image
Mat img = projectBoard(gridboard, cameraMatrix, deg2rad(yaw), deg2rad(pitch), distance,
imgSize, markerBorder);
vector< vector< Point2f > > corners;
vector< int > ids;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
vector<vector<Point2f> > corners;
vector<int> ids;
detector.params->markerBorderBits = markerBorder;
detector.detectMarkers(img, corners, ids);
ASSERT_EQ(ids.size(), gridboard->ids.size());
ASSERT_EQ(ids.size(), gridboard->getIds().size());
// estimate pose
Mat rvec, tvec;
aruco::estimatePoseBoard(corners, ids, board, cameraMatrix, distCoeffs, rvec, tvec);
// check axes
vector<Point2f> axes = getAxis(cameraMatrix, distCoeffs, rvec, tvec, gridboard->rightBottomBorder.x);
vector<Point2f> topLeft = getMarkerById(gridboard->ids[0], corners, ids);
vector<Point2f> axes = getAxis(cameraMatrix, distCoeffs, rvec, tvec, gridboard->getRightBottomBorder().x);
vector<Point2f> topLeft = getMarkerById(gridboard->getIds()[0], corners, ids);
ASSERT_NEAR(topLeft[0].x, axes[0].x, 2.f);
ASSERT_NEAR(topLeft[0].y, axes[0].y, 2.f);
vector<Point2f> topRight = getMarkerById(gridboard->ids[2], corners, ids);
vector<Point2f> topRight = getMarkerById(gridboard->getIds()[2], corners, ids);
ASSERT_NEAR(topRight[1].x, axes[1].x, 2.f);
ASSERT_NEAR(topRight[1].y, axes[1].y, 2.f);
vector<Point2f> bottomLeft = getMarkerById(gridboard->ids[6], corners, ids);
vector<Point2f> bottomLeft = getMarkerById(gridboard->getIds()[6], corners, ids);
ASSERT_NEAR(bottomLeft[3].x, axes[2].x, 2.f);
ASSERT_NEAR(bottomLeft[3].y, axes[2].y, 2.f);
// check estimate result
for(unsigned int i = 0; i < ids.size(); i++) {
int foundIdx = -1;
for(unsigned int j = 0; j < gridboard->ids.size(); j++) {
if(gridboard->ids[j] == ids[i]) {
for(unsigned int j = 0; j < gridboard->getIds().size(); j++) {
if(gridboard->getIds()[j] == ids[i]) {
foundIdx = int(j);
break;
}
@ -134,7 +138,7 @@ void CV_ArucoBoardPose::run(int) {
}
vector< Point2f > projectedCorners;
projectPoints(gridboard->objPoints[foundIdx], rvec, tvec, cameraMatrix, distCoeffs,
projectPoints(gridboard->getObjPoints()[foundIdx], rvec, tvec, cameraMatrix, distCoeffs,
projectedCorners);
for(int c = 0; c < 4; c++) {
@ -160,15 +164,18 @@ class CV_ArucoRefine : public cvtest::BaseTest {
public:
CV_ArucoRefine(ArucoAlgParams arucoAlgParams)
{
params = aruco::DetectorParameters::create();
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3)
params->useAruco3Detection = true;
Ptr<aruco::RefineParameters> refineParams = makePtr<aruco::RefineParameters>(10, 3., true);
detector = aruco::ArucoDetector(dictionary, params, refineParams);
}
protected:
Ptr<aruco::DetectorParameters> params;
aruco::ArucoDetector detector;
void run(int);
};
@ -178,8 +185,7 @@ void CV_ArucoRefine::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, detector.dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
@ -190,8 +196,10 @@ void CV_ArucoRefine::run(int) {
for(double distance = 0.2; distance <= 0.4; distance += 0.2) {
for(int yaw = -60; yaw < 60; yaw += 30) {
for(int pitch = -60; pitch <= 60; pitch += 30) {
for(unsigned int i = 0; i < gridboard->ids.size(); i++)
gridboard->ids[i] = (iter + int(i)) % 250;
vector<int> tmpIds;
for(unsigned int i = 0; i < gridboard->getIds().size(); i++)
tmpIds.push_back(iter + int(i) % 250);
gridboard->setIds(tmpIds);
int markerBorder = iter % 2 + 1;
iter++;
@ -199,10 +207,10 @@ void CV_ArucoRefine::run(int) {
Mat img = projectBoard(gridboard, cameraMatrix, deg2rad(yaw), deg2rad(pitch), distance,
imgSize, markerBorder);
// detect markers
vector< vector< Point2f > > corners, rejected;
vector< int > ids;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params, rejected);
vector<vector<Point2f> > corners, rejected;
vector<int> ids;
detector.params->markerBorderBits = markerBorder;
detector.detectMarkers(img, corners, ids, rejected);
// remove a marker from detection
int markersBeforeDelete = (int)ids.size();
@ -213,8 +221,8 @@ void CV_ArucoRefine::run(int) {
ids.erase(ids.begin(), ids.begin() + 1);
// try to refind the erased marker
aruco::refineDetectedMarkers(img, board, corners, ids, rejected, cameraMatrix,
distCoeffs, 10, 3., true, noArray(), params);
detector.refineDetectedMarkers(img, board, corners, ids, rejected, cameraMatrix,
distCoeffs, noArray());
// check result
if((int)ids.size() < markersBeforeDelete) {
@ -260,23 +268,22 @@ TEST(CV_ArucoBoardPose, CheckNegativeZ)
0., 0., 1 };
cv::Mat cameraMatrix = cv::Mat(3, 3, CV_64F, matrixData);
cv::Ptr<cv::aruco::Board> boardPtr(new cv::aruco::Board);
cv::Ptr<cv::aruco::Board> boardPtr = makePtr<cv::aruco::Board>();
cv::aruco::Board& board = *boardPtr;
board.ids.push_back(0);
board.ids.push_back(1);
vector<cv::Point3f> pts3d;
pts3d.push_back(cv::Point3f(0.326198f, -0.030621f, 0.303620f));
pts3d.push_back(cv::Point3f(0.325340f, -0.100594f, 0.301862f));
pts3d.push_back(cv::Point3f(0.255859f, -0.099530f, 0.293416f));
pts3d.push_back(cv::Point3f(0.256717f, -0.029557f, 0.295174f));
board.objPoints.push_back(pts3d);
pts3d.clear();
pts3d.push_back(cv::Point3f(-0.033144f, -0.034819f, 0.245216f));
pts3d.push_back(cv::Point3f(-0.035507f, -0.104705f, 0.241987f));
pts3d.push_back(cv::Point3f(-0.105289f, -0.102120f, 0.237120f));
pts3d.push_back(cv::Point3f(-0.102926f, -0.032235f, 0.240349f));
board.objPoints.push_back(pts3d);
vector<cv::Point3f> pts3d1, pts3d2;
pts3d1.push_back(cv::Point3f(0.326198f, -0.030621f, 0.303620f));
pts3d1.push_back(cv::Point3f(0.325340f, -0.100594f, 0.301862f));
pts3d1.push_back(cv::Point3f(0.255859f, -0.099530f, 0.293416f));
pts3d1.push_back(cv::Point3f(0.256717f, -0.029557f, 0.295174f));
pts3d2.push_back(cv::Point3f(-0.033144f, -0.034819f, 0.245216f));
pts3d2.push_back(cv::Point3f(-0.035507f, -0.104705f, 0.241987f));
pts3d2.push_back(cv::Point3f(-0.105289f, -0.102120f, 0.237120f));
pts3d2.push_back(cv::Point3f(-0.102926f, -0.032235f, 0.240349f));
board.setObjPoints({pts3d1, pts3d2});
board.setIds(vector<int>{0, 1});
vector<vector<Point2f> > corners;
vector<Point2f> pts2d;
@ -293,12 +300,12 @@ TEST(CV_ArucoBoardPose, CheckNegativeZ)
corners.push_back(pts2d);
Vec3d rvec, tvec;
int nUsed = cv::aruco::estimatePoseBoard(corners, board.ids, boardPtr, cameraMatrix, Mat(), rvec, tvec);
int nUsed = cv::aruco::estimatePoseBoard(corners, board.getIds(), boardPtr, cameraMatrix, Mat(), rvec, tvec);
ASSERT_EQ(nUsed, 2);
cv::Matx33d rotm; cv::Point3d out;
cv::Rodrigues(rvec, rotm);
out = cv::Point3d(tvec) + rotm*Point3d(board.objPoints[0][0]);
out = cv::Point3d(tvec) + rotm*Point3d(board.getObjPoints()[0][0]);
ASSERT_GT(out.z, 0);
corners.clear(); pts2d.clear();
@ -314,11 +321,11 @@ TEST(CV_ArucoBoardPose, CheckNegativeZ)
pts2d.push_back(cv::Point2f(586.3f, 188.5f));
corners.push_back(pts2d);
nUsed = cv::aruco::estimatePoseBoard(corners, board.ids, boardPtr, cameraMatrix, Mat(), rvec, tvec, true);
nUsed = cv::aruco::estimatePoseBoard(corners, board.getIds(), boardPtr, cameraMatrix, Mat(), rvec, tvec, true);
ASSERT_EQ(nUsed, 2);
cv::Rodrigues(rvec, rotm);
out = cv::Point3d(tvec) + rotm*Point3d(board.objPoints[0][0]);
out = cv::Point3d(tvec) + rotm*Point3d(board.getObjPoints()[0][0]);
ASSERT_GT(out.z, 0);
}

@ -93,7 +93,7 @@ static Mat projectCharucoBoard(Ptr<aruco::CharucoBoard> &board, Mat cameraMatrix
// project markers
Mat img = Mat(imageSize, CV_8UC1, Scalar::all(255));
for(unsigned int indexMarker = 0; indexMarker < board->ids.size(); indexMarker++) {
for(unsigned int indexMarker = 0; indexMarker < board->getIds().size(); indexMarker++) {
projectMarker(img, board.staticCast<aruco::Board>(), indexMarker, cameraMatrix, rvec,
tvec, markerBorder);
}
@ -132,12 +132,14 @@ void CV_CharucoDetection::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 600;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
cameraMatrix.at< double >(1, 2) = imgSize.height / 2;
cameraMatrix.at<double>(0, 0) = cameraMatrix.at<double>(1, 1) = 600;
cameraMatrix.at<double>(0, 2) = imgSize.width / 2;
cameraMatrix.at<double>(1, 2) = imgSize.height / 2;
Mat distCoeffs(5, 1, CV_64FC1, Scalar::all(0));
@ -155,12 +157,11 @@ void CV_CharucoDetection::run(int) {
distance, imgSize, markerBorder, rvec, tvec);
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
vector<vector<Point2f> > corners;
vector<int> ids;
detector.params->markerBorderBits = markerBorder;
detector.detectMarkers(img, corners, ids);
if(ids.size() == 0) {
ts->printf(cvtest::TS::LOG, "Marker detection failed");
@ -169,8 +170,8 @@ void CV_CharucoDetection::run(int) {
}
// interpolate charuco corners
vector< Point2f > charucoCorners;
vector< int > charucoIds;
vector<Point2f> charucoCorners;
vector<int> charucoIds;
if(iter % 2 == 0) {
aruco::interpolateCornersCharuco(corners, ids, img, board, charucoCorners,
@ -187,7 +188,7 @@ void CV_CharucoDetection::run(int) {
vector<Point3f> copyChessboardCorners = board->chessboardCorners;
// move copyChessboardCorners points
for (size_t i = 0; i < copyChessboardCorners.size(); i++)
copyChessboardCorners[i] -= board->rightBottomBorder / 2.f;
copyChessboardCorners[i] -= board->getRightBottomBorder() / 2.f;
projectPoints(copyChessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectedCharucoCorners);
@ -237,8 +238,10 @@ void CV_CharucoPoseEstimation::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
@ -261,12 +264,10 @@ void CV_CharucoPoseEstimation::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.params->markerBorderBits = markerBorder;
detector.detectMarkers(img, corners, ids);
ASSERT_EQ(ids.size(), board->ids.size());
ASSERT_EQ(ids.size(), board->getIds().size());
// interpolate charuco corners
vector< Point2f > charucoCorners;
@ -290,10 +291,10 @@ void CV_CharucoPoseEstimation::run(int) {
// check axes
const float offset = (board->getSquareLength() - board->getMarkerLength()) / 2.f;
vector<Point2f> axes = getAxis(cameraMatrix, distCoeffs, rvec, tvec, board->getSquareLength(), offset);
vector<Point2f> topLeft = getMarkerById(board->ids[0], corners, ids);
vector<Point2f> topLeft = getMarkerById(board->getIds()[0], corners, ids);
ASSERT_NEAR(topLeft[0].x, axes[1].x, 3.f);
ASSERT_NEAR(topLeft[0].y, axes[1].y, 3.f);
vector<Point2f> bottomLeft = getMarkerById(board->ids[2], corners, ids);
vector<Point2f> bottomLeft = getMarkerById(board->getIds()[2], corners, ids);
ASSERT_NEAR(bottomLeft[0].x, axes[2].x, 3.f);
ASSERT_NEAR(bottomLeft[0].y, axes[2].y, 3.f);
@ -348,11 +349,13 @@ void CV_CharucoDiamondDetection::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 0;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
float squareLength = 0.03f;
float markerLength = 0.015f;
Ptr<aruco::CharucoBoard> board =
aruco::CharucoBoard::create(3, 3, squareLength, markerLength, dictionary);
aruco::CharucoBoard::create(3, 3, squareLength, markerLength, detector.dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
@ -365,8 +368,10 @@ void CV_CharucoDiamondDetection::run(int) {
for(int pitch = -50; pitch <= 50; pitch += 25) {
int markerBorder = iter % 2 + 1;
vector<int> idsTmp;
for(int i = 0; i < 4; i++)
board->ids[i] = 4 * iter + i;
idsTmp.push_back(4 * iter + i);
board->setIds(idsTmp);
iter++;
// get synthetic image
@ -377,22 +382,19 @@ void CV_CharucoDiamondDetection::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 0;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
detector.params->markerBorderBits = markerBorder;
detector.detectMarkers(img, corners, ids);
if(ids.size() != 4) {
ts->printf(cvtest::TS::LOG, "Not enough markers for diamond detection");
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
return;
}
// detect diamonds
vector< vector< Point2f > > diamondCorners;
vector< Vec4i > diamondIds;
aruco::detectCharucoDiamond(img, corners, ids, squareLength / markerLength,
diamondCorners, diamondIds, cameraMatrix, distCoeffs);
aruco::detectCharucoDiamond(img, corners, ids, squareLength / markerLength, diamondCorners, diamondIds,
cameraMatrix, distCoeffs, detector.dictionary);
// check results
if(diamondIds.size() != 1) {
@ -402,7 +404,7 @@ void CV_CharucoDiamondDetection::run(int) {
}
for(int i = 0; i < 4; i++) {
if(diamondIds[0][i] != board->ids[i]) {
if(diamondIds[0][i] != board->getIds()[i]) {
ts->printf(cvtest::TS::LOG, "Incorrect diamond ids");
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
return;
@ -416,7 +418,7 @@ void CV_CharucoDiamondDetection::run(int) {
vector<Point3f> copyChessboardCorners = board->chessboardCorners;
// move copyChessboardCorners points
for (size_t i = 0; i < copyChessboardCorners.size(); i++)
copyChessboardCorners[i] -= board->rightBottomBorder / 2.f;
copyChessboardCorners[i] -= board->getRightBottomBorder() / 2.f;
projectPoints(copyChessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectedDiamondCorners);
@ -439,10 +441,12 @@ void CV_CharucoDiamondDetection::run(int) {
}
}
Ptr<aruco::EstimateParameters> estimateParameters = aruco::EstimateParameters::create();
estimateParameters->pattern = aruco::ARUCO_CW_TOP_LEFT_CORNER;
// estimate diamond pose
vector< Vec3d > estimatedRvec, estimatedTvec;
aruco::estimatePoseSingleMarkers(diamondCorners, squareLength, cameraMatrix,
distCoeffs, estimatedRvec, estimatedTvec);
aruco::estimatePoseSingleMarkers(diamondCorners, squareLength, cameraMatrix, distCoeffs, estimatedRvec,
estimatedTvec, noArray(), estimateParameters);
// check result
vector< Point2f > projectedDiamondCornersPose;
@ -644,10 +648,12 @@ TEST(Charuco, testBoardSubpixelCoords)
auto params = cv::aruco::DetectorParameters::create();
params->cornerRefinementMethod = cv::aruco::CORNER_REFINE_APRILTAG;
aruco::ArucoDetector detector(dict, params);
std::vector<int> ids;
std::vector<std::vector<cv::Point2f>> corners, rejected;
cv::aruco::detectMarkers(gray, dict, corners, ids, params, rejected);
detector.detectMarkers(gray, corners, ids, rejected);
ASSERT_EQ(ids.size(), size_t(8));
@ -669,8 +675,7 @@ TEST(CV_ArucoTutorial, can_find_choriginal)
{
string imgPath = cvtest::findDataFile("choriginal.jpg", false);
Mat image = imread(imgPath);
cv::Ptr<cv::aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250));
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
@ -689,7 +694,7 @@ TEST(CV_ArucoTutorial, can_find_choriginal)
for (int i = 0; i < static_cast<int>(N); i++)
mapGoldCorners[i] = goldCorners[i];
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
ASSERT_EQ(N, ids.size());
for (size_t i = 0; i < N; i++)
@ -709,8 +714,7 @@ TEST(CV_ArucoTutorial, can_find_chocclusion)
{
string imgPath = cvtest::findDataFile("chocclusion_original.jpg", false);
Mat image = imread(imgPath);
cv::Ptr<cv::aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250));
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
@ -728,7 +732,7 @@ TEST(CV_ArucoTutorial, can_find_chocclusion)
for (int i = 0; i < static_cast<int>(N); i++)
mapGoldCorners[goldCornersIds[i]] = goldCorners[i];
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
ASSERT_EQ(N, ids.size());
for (size_t i = 0; i < N; i++)
@ -760,6 +764,8 @@ TEST(CV_ArucoTutorial, can_find_diamondmarkers)
detectorParams->readDetectorParameters(fs.root());
detectorParams->cornerRefinementMethod = 3;
aruco::ArucoDetector detector(dictionary, detectorParams);
vector< int > ids;
vector< vector< Point2f > > corners, rejected;
const size_t N = 12ull;
@ -769,7 +775,7 @@ TEST(CV_ArucoTutorial, can_find_diamondmarkers)
for (int i = 0; i < static_cast<int>(N); i++)
counterGoldCornersIds[goldCornersIds[i]]++;
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
map<int, int> counterRes;
for (size_t i = 0; i < N; i++)
{
@ -786,16 +792,16 @@ TEST(Charuco, issue_14014)
string imgPath = cvtest::findDataFile("aruco/recover.png");
Mat img = imread(imgPath);
Ptr<aruco::Dictionary> dict = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(cv::aruco::DICT_7X7_250));
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(8, 5, 0.03455f, 0.02164f, dict);
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
detectorParams->cornerRefinementMinAccuracy = 0.01;
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_7X7_250), detectorParams);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(8, 5, 0.03455f, 0.02164f, detector.dictionary);
vector<Mat> corners, rejectedPoints;
vector<int> ids;
aruco::detectMarkers(img, dict, corners, ids, detectorParams, rejectedPoints);
detector.detectMarkers(img, corners, ids, rejectedPoints);
ASSERT_EQ(corners.size(), 19ull);
EXPECT_EQ(Size(4, 1), corners[0].size()); // check dimension of detected corners
@ -804,7 +810,7 @@ TEST(Charuco, issue_14014)
ASSERT_EQ(rejectedPoints.size(), 26ull); // optional check to track regressions
EXPECT_EQ(Size(4, 1), rejectedPoints[0].size()); // check dimension of detected corners
aruco::refineDetectedMarkers(img, board, corners, ids, rejectedPoints);
detector.refineDetectedMarkers(img, board, corners, ids, rejectedPoints);
ASSERT_EQ(corners.size(), 20ull);
EXPECT_EQ(Size(4, 1), corners[0].size()); // check dimension of rejected corners after successfully refine

@ -7,7 +7,6 @@
#include "opencv2/ts.hpp"
#include "opencv2/imgproc.hpp"
#include "opencv2/3d.hpp"
#include "opencv2/aruco.hpp"
#include <opencv2/aruco/charuco.hpp>
#endif

@ -156,7 +156,7 @@ In this case the margin is 10.
The output image will be something like this:
![](images/board.jpg)
![](images/board.png)
A full working example of board creation is included in the `create_board.cpp` inside the `modules/aruco/samples/`.

Binary file not shown.

After

Width:  |  Height:  |  Size: 78 KiB

@ -286,8 +286,9 @@ translation vectors of the estimated poses will be in the same unit
- The output parameters `rvecs` and `tvecs` are the rotation and translation vectors respectively, for each of the markers
in `markerCorners`.
The marker coordinate system that is assumed by this function is placed at the center of the marker
with the Z axis pointing out, as in the following image. Axis-color correspondences are X: red, Y: green, Z: blue. Note the axis directions of the rotated markers in this image.
The marker coordinate system that is assumed by this function is placed in the center (by default) or
in the top left corner of the marker with the Z axis pointing out, as in the following image.
Axis-color correspondences are X: red, Y: green, Z: blue. Note the axis directions of the rotated markers in this image.
![Image with axes drawn](images/singlemarkersaxes.jpg)

@ -88,7 +88,7 @@ In this case the margin is 10.
The output image will be something like this:
![](images/charucoboard.jpg)
![](images/charucoboard.png)
A full working example is included in the `create_board_charuco.cpp` inside the `modules/aruco/samples/`.

@ -251,7 +251,7 @@ public:
/** @brief Outputs a string showing the used parameters setup
@return a string which contains formated parameters information
*/
CV_WRAP virtual const String printSetup()=0;
CV_WRAP virtual String printSetup()=0;
/** @brief Write xml/yml formated parameters information
@param fs the filename of the xml file that will be open and writen with formatted parameters
@ -389,9 +389,9 @@ public:
CV_WRAP virtual void getMagnoRAW(OutputArray retinaOutput_magno)=0;
/** @overload */
CV_WRAP virtual const Mat getMagnoRAW() const=0;
CV_WRAP virtual Mat getMagnoRAW() const=0;
/** @overload */
CV_WRAP virtual const Mat getParvoRAW() const=0;
CV_WRAP virtual Mat getParvoRAW() const=0;
/** @brief Activate color saturation as the final step of the color demultiplexing process -\> this
saturation is a sigmoide function applied to each channel of the demultiplexed image.

@ -161,7 +161,7 @@ public:
/** @brief parameters setup display method
@return a string which contains formatted parameters information
*/
CV_WRAP virtual const String printSetup()=0;
CV_WRAP virtual String printSetup()=0;
/** @brief write xml/yml formated parameters information
@param fs : the filename of the xml file that will be open and writen with formatted parameters information

@ -148,7 +148,7 @@ public:
* parameters setup display method
* @return a string which contains formatted parameters information
*/
const String printSetup() CV_OVERRIDE;
String printSetup() CV_OVERRIDE;
/**
* write xml/yml formated parameters information
@ -233,8 +233,8 @@ public:
void getMagnoRAW(OutputArray retinaOutput_magno) CV_OVERRIDE;
// original API level data accessors : get buffers addresses from a Mat header, similar to getParvoRAW and getMagnoRAW...
const Mat getMagnoRAW() const CV_OVERRIDE;
const Mat getParvoRAW() const CV_OVERRIDE;
Mat getMagnoRAW() const CV_OVERRIDE;
Mat getParvoRAW() const CV_OVERRIDE;
/**
* activate color saturation as the final step of the color demultiplexing process
@ -445,7 +445,7 @@ void RetinaImpl::setup(RetinaParameters newConfiguration)
}
const String RetinaImpl::printSetup()
String RetinaImpl::printSetup()
{
std::stringstream outmessage;
@ -692,14 +692,14 @@ void RetinaImpl::getParvoRAW(OutputArray parvoOutputBufferCopy)
}
// original API level data accessors : get buffers addresses...
const Mat RetinaImpl::getMagnoRAW() const {
Mat RetinaImpl::getMagnoRAW() const {
CV_Assert(!_wasOCLRunCalled);
// create a cv::Mat header for the valarray
return Mat((int)_retinaFilter->getMovingContours().size(),1, CV_32F, (void*)get_data(_retinaFilter->getMovingContours()));
}
const Mat RetinaImpl::getParvoRAW() const {
Mat RetinaImpl::getParvoRAW() const {
CV_Assert(!_wasOCLRunCalled);
if (_retinaFilter->getColorMode()) // check if color mode is enabled
{

@ -203,7 +203,7 @@ void RetinaOCLImpl::setup(cv::bioinspired::RetinaParameters newConfiguration)
setupIPLMagnoChannel(_retinaParameters.IplMagno.normaliseOutput, _retinaParameters.IplMagno.parasolCells_beta, _retinaParameters.IplMagno.parasolCells_tau, _retinaParameters.IplMagno.parasolCells_k, _retinaParameters.IplMagno.amacrinCellsTemporalCutFrequency, _retinaParameters.IplMagno.V0CompressionParameter, _retinaParameters.IplMagno.localAdaptintegration_tau, _retinaParameters.IplMagno.localAdaptintegration_k);
}
const String RetinaOCLImpl::printSetup()
String RetinaOCLImpl::printSetup()
{
std::stringstream outmessage;
@ -448,8 +448,8 @@ void RetinaOCLImpl::getMagnoRAW(OutputArray retinaOutput_magno)
// unimplemented interfaces:
void RetinaOCLImpl::applyFastToneMapping(InputArray /*inputImage*/, OutputArray /*outputToneMappedImage*/) { NOT_IMPLEMENTED; }
const Mat RetinaOCLImpl::getMagnoRAW() const { NOT_IMPLEMENTED; }
const Mat RetinaOCLImpl::getParvoRAW() const { NOT_IMPLEMENTED; }
Mat RetinaOCLImpl::getMagnoRAW() const { NOT_IMPLEMENTED; }
Mat RetinaOCLImpl::getParvoRAW() const { NOT_IMPLEMENTED; }
///////////////////////////////////////
///////// BasicRetinaFilter ///////////

@ -643,7 +643,7 @@ public:
RetinaParameters getParameters() CV_OVERRIDE;
const String printSetup() CV_OVERRIDE;
String printSetup() CV_OVERRIDE;
virtual void write(String fs) const CV_OVERRIDE;
virtual void write(FileStorage& fs) const CV_OVERRIDE;
@ -663,8 +663,8 @@ public:
void applyFastToneMapping(InputArray /*inputImage*/, OutputArray /*outputToneMappedImage*/) CV_OVERRIDE;
void getParvoRAW(OutputArray /*retinaOutput_parvo*/) CV_OVERRIDE;
void getMagnoRAW(OutputArray /*retinaOutput_magno*/) CV_OVERRIDE;
const Mat getMagnoRAW() const CV_OVERRIDE;
const Mat getParvoRAW() const CV_OVERRIDE;
Mat getMagnoRAW() const CV_OVERRIDE;
Mat getParvoRAW() const CV_OVERRIDE;
protected:
RetinaParameters _retinaParameters;

@ -142,7 +142,7 @@ public:
* parameters setup display method
* @return a string which contains formatted parameters information
*/
const String printSetup();
String printSetup();
/**
* write xml/yml formated parameters information
@ -232,7 +232,7 @@ public:
inline virtual void setup(String segmentationParameterFile, const bool applyDefaultSetupOnFailure) CV_OVERRIDE { _segmTool.setup(segmentationParameterFile, applyDefaultSetupOnFailure); }
inline virtual void setup(cv::FileStorage &fs, const bool applyDefaultSetupOnFailure) CV_OVERRIDE { _segmTool.setup(fs, applyDefaultSetupOnFailure); }
inline virtual void setup(SegmentationParameters newParameters) CV_OVERRIDE { _segmTool.setup(newParameters); }
inline virtual const String printSetup() CV_OVERRIDE { return _segmTool.printSetup(); }
inline virtual String printSetup() CV_OVERRIDE { return _segmTool.printSetup(); }
inline virtual struct SegmentationParameters getParameters() CV_OVERRIDE { return _segmTool.getParameters(); }
inline virtual void write( String fs ) const CV_OVERRIDE { _segmTool.write(fs); }
inline virtual void run(InputArray inputToSegment, const int channelIndex) CV_OVERRIDE { _segmTool.run(inputToSegment, channelIndex); }
@ -368,7 +368,7 @@ void TransientAreasSegmentationModuleImpl::setup(cv::bioinspired::SegmentationPa
}
const String TransientAreasSegmentationModuleImpl::printSetup()
String TransientAreasSegmentationModuleImpl::printSetup()
{
std::stringstream outmessage;

@ -30,7 +30,7 @@ values of the two squares with the picker tool.
In this image I've cropped a little piece of the A and B squares and I've put them side-by-side.
It should be quite evident they have the same luminance.
![Adelson checkerboard proof](images/checkershadow_illusion4med_proof.jpg)
![Adelson checkerboard proof](images/checkershadow_illusion4med_proof.png)
It's worth to know that this illusion works because the checkerboard image, as you may see it
on your laptop, casts on your retina with dimensions that cause the retina local adaptation to take
@ -184,4 +184,4 @@ opportunity of writing this tutorial, and for reviewing it.
**Edward Adelson** - for allowing me to freely use his checkerboard image.
**Antonio Cuni** - for reviewing this tutorial and for writing the Python code.
**Antonio Cuni** - for reviewing this tutorial and for writing the Python code.

@ -321,17 +321,20 @@ enum class VideoReaderProps {
PROP_RAW_MODE = 4, //!< Status of raw mode.
PROP_LRF_HAS_KEY_FRAME = 5, //!< FFmpeg source only - Indicates whether the Last Raw Frame (LRF), output from VideoReader::retrieve() when VideoReader is initialized in raw mode, contains encoded data for a key frame.
PROP_COLOR_FORMAT = 6, //!< Set the ColorFormat of the decoded frame. This can be changed before every call to nextFrame() and retrieve().
PROP_UDP_SOURCE = 7, //!< Status of VideoReaderInitParams::udpSource initialization.
PROP_ALLOW_FRAME_DROP = 8, //!< Status of VideoReaderInitParams::allowFrameDrop initialization.
#ifndef CV_DOXYGEN
PROP_NOT_SUPPORTED
#endif
};
/** @brief ColorFormat for the frame returned by the decoder.
/** @brief ColorFormat for the frame returned by nextFrame()/retrieve().
*/
enum class ColorFormat {
BGRA = 1,
BGR = 2,
GRAY = 3,
YUV = 4,
#ifndef CV_DOXYGEN
PROP_NOT_SUPPORTED
#endif
@ -350,8 +353,12 @@ public:
/** @brief Grabs, decodes and returns the next video frame.
If no frames has been grabbed (there are no more frames in video file), the methods return false .
The method throws Exception if error occurs.
@param [out] frame The video frame.
@param stream Stream for the asynchronous version.
@return `false` if no frames have been grabbed.
If no frames have been grabbed (there are no more frames in video file), the methods return false.
The method throws an Exception if error occurs.
*/
CV_WRAP virtual bool nextFrame(CV_OUT GpuMat& frame, Stream &stream = Stream::Null()) = 0;
@ -361,6 +368,7 @@ public:
/** @brief Grabs the next frame from the video source.
@param stream Stream for the asynchronous version.
@return `true` (non-zero) in the case of success.
The method/function grabs the next frame from video file or camera and returns true (non-zero) in
@ -373,17 +381,44 @@ public:
/** @brief Returns previously grabbed video data.
@param [out] frame The returned data which depends on the provided idx. If there is no new data since the last call to grab() the image will be empty.
@param idx Determins the returned data inside image. The returned data can be the:
Decoded frame, idx = get(PROP_DECODED_FRAME_IDX).
Extra data if available, idx = get(PROP_EXTRA_DATA_INDEX).
Raw encoded data package. To retrieve package i, idx = get(PROP_RAW_PACKAGES_BASE_INDEX) + i with i < get(PROP_NUMBER_OF_RAW_PACKAGES_SINCE_LAST_GRAB)
@return `false` if no frames has been grabbed
@param [out] frame The returned data which depends on the provided idx.
@param idx Determines the returned data inside image. The returned data can be the:
- Decoded frame, idx = get(PROP_DECODED_FRAME_IDX).
- Extra data if available, idx = get(PROP_EXTRA_DATA_INDEX).
- Raw encoded data package. To retrieve package i, idx = get(PROP_RAW_PACKAGES_BASE_INDEX) + i with i < get(PROP_NUMBER_OF_RAW_PACKAGES_SINCE_LAST_GRAB)
@return `false` if no frames have been grabbed
The method returns data associated with the current video source since the last call to grab() or the creation of the VideoReader. If no data is present
the method returns false and the function returns an empty image.
*/
virtual bool retrieve(OutputArray frame, const size_t idx = static_cast<size_t>(VideoReaderProps::PROP_DECODED_FRAME_IDX)) const = 0;
/** @brief Returns previously grabbed encoded video data.
@param [out] frame The encoded video data.
@param idx Determines the returned data inside image. The returned data can be the:
- Extra data if available, idx = get(PROP_EXTRA_DATA_INDEX).
- Raw encoded data package. To retrieve package i, idx = get(PROP_RAW_PACKAGES_BASE_INDEX) + i with i < get(PROP_NUMBER_OF_RAW_PACKAGES_SINCE_LAST_GRAB)
@return `false` if no frames have been grabbed
The method returns data associated with the current video source since the last call to grab() or the creation of the VideoReader. If no data is present
the method returns false and the function returns an empty image.
*/
CV_WRAP virtual bool retrieve(CV_OUT OutputArray frame, const size_t idx = static_cast<size_t>(VideoReaderProps::PROP_DECODED_FRAME_IDX)) const = 0;
CV_WRAP inline bool retrieve(CV_OUT Mat& frame, const size_t idx) const {
return retrieve(OutputArray(frame), idx);
}
/** @brief Returns the next video frame.
@param [out] frame The video frame. If grab() has not been called then this will be empty().
@return `false` if no frames have been grabbed
The method returns data associated with the current video source since the last call to grab(). If no data is present
the method returns false and the function returns an empty image.
*/
CV_WRAP inline bool retrieve(CV_OUT GpuMat& frame) const {
return retrieve(OutputArray(frame));
}
/** @brief Sets a property in the VideoReader.
@ -392,20 +427,28 @@ public:
@param propertyVal Value of the property.
@return `true` if the property has been set.
*/
CV_WRAP virtual bool set(const VideoReaderProps propertyId, const double propertyVal) = 0;
virtual bool set(const VideoReaderProps propertyId, const double propertyVal) = 0;
CV_WRAP inline bool setVideoReaderProps(const VideoReaderProps propertyId, double propertyVal) {
return set(propertyId, propertyVal);
}
CV_WRAP virtual void set(const ColorFormat _colorFormat) = 0;
/** @brief Set the desired ColorFormat for the frame returned by nextFrame()/retrieve().
@param colorFormat Value of the ColorFormat.
*/
CV_WRAP virtual void set(const ColorFormat colorFormat) = 0;
/** @brief Returns the specified VideoReader property
@param propertyId Property identifier from cv::cudacodec::VideoReaderProps (eg. cv::cudacodec::VideoReaderProps::PROP_DECODED_FRAME_IDX,
cv::cudacodec::VideoReaderProps::PROP_EXTRA_DATA_INDEX, ...).
@param propertyVal
In - Optional value required for querying specific propertyId's, e.g. the index of the raw package to be checked for a key frame (cv::cudacodec::VideoReaderProps::PROP_LRF_HAS_KEY_FRAME).
Out - Value of the property.
- In: Optional value required for querying specific propertyId's, e.g. the index of the raw package to be checked for a key frame (cv::cudacodec::VideoReaderProps::PROP_LRF_HAS_KEY_FRAME).
- Out: Value of the property.
@return `true` unless the property is not supported.
*/
CV_WRAP virtual bool get(const VideoReaderProps propertyId, CV_IN_OUT double& propertyVal) const = 0;
virtual bool get(const VideoReaderProps propertyId, double& propertyVal) const = 0;
CV_WRAP virtual bool getVideoReaderProps(const VideoReaderProps propertyId, CV_OUT double& propertyValOut, double propertyValIn = 0) const = 0;
/** @brief Retrieves the specified property used by the VideoSource.
@ -463,32 +506,43 @@ public:
virtual bool get(const int propertyId, double& propertyVal) const = 0;
};
/** @brief VideoReader initialization parameters
@param udpSource Remove validation which can cause VideoReader() to throw exceptions when reading from a UDP source.
@param allowFrameDrop Allow frames to be dropped when ingesting from a live capture source to prevent delay and eventual disconnection
when calls to nextFrame()/grab() cannot keep up with the source's fps. Only use if delay and disconnection are a problem, i.e. not when decoding from
video files where setting this flag will cause frames to be unnecessarily discarded.
@param minNumDecodeSurfaces Minimum number of internal decode surfaces used by the hardware decoder. NVDEC will automatically determine the minimum number of
surfaces it requires for correct functionality and optimal video memory usage but not necessarily for best performance, which depends on the design of the
overall application. The optimal number of decode surfaces (in terms of performance and memory utilization) should be decided by experimentation for each application,
but it cannot go below the number determined by NVDEC.
@param rawMode Allow the raw encoded data which has been read up until the last call to grab() to be retrieved by calling retrieve(rawData,RAW_DATA_IDX).
*/
struct CV_EXPORTS_W_SIMPLE VideoReaderInitParams {
CV_WRAP VideoReaderInitParams() : udpSource(false), allowFrameDrop(false), minNumDecodeSurfaces(0), rawMode(0) {};
CV_PROP_RW bool udpSource;
CV_PROP_RW bool allowFrameDrop;
CV_PROP_RW int minNumDecodeSurfaces;
CV_PROP_RW bool rawMode;
};
/** @brief Creates video reader.
@param filename Name of the input video file.
@param params Pass through parameters for VideoCapure. VideoCapture with the FFMpeg back end (CAP_FFMPEG) is used to parse the video input.
The `params` parameter allows to specify extra parameters encoded as pairs `(paramId_1, paramValue_1, paramId_2, paramValue_2, ...)`.
@param sourceParams Pass through parameters for VideoCapure. VideoCapture with the FFMpeg back end (CAP_FFMPEG) is used to parse the video input.
The `sourceParams` parameter allows to specify extra parameters encoded as pairs `(paramId_1, paramValue_1, paramId_2, paramValue_2, ...)`.
See cv::VideoCaptureProperties
e.g. when streaming from an RTSP source CAP_PROP_OPEN_TIMEOUT_MSEC may need to be set.
@param rawMode Allow the raw encoded data which has been read up until the last call to grab() to be retrieved by calling retrieve(rawData,RAW_DATA_IDX).
@param minNumDecodeSurfaces Minimum number of internal decode surfaces used by the hardware decoder. NVDEC will automatically determine the minimum number of
surfaces it requires for correct functionality and optimal video memory usage but not necessarily for best performance, which depends on the design of the
overall application. The optimal number of decode surfaces (in terms of performance and memory utilization) should be decided by experimentation for each application,
but it cannot go below the number determined by NVDEC.
@param params Initializaton parameters. See cv::cudacodec::VideoReaderInitParams.
FFMPEG is used to read videos. User can implement own demultiplexing with cudacodec::RawVideoSource
*/
CV_EXPORTS_W Ptr<VideoReader> createVideoReader(const String& filename, const std::vector<int>& params = {}, const bool rawMode = false, const int minNumDecodeSurfaces = 0);
CV_EXPORTS_W Ptr<VideoReader> createVideoReader(const String& filename, const std::vector<int>& sourceParams = {}, const VideoReaderInitParams params = VideoReaderInitParams());
/** @overload
@param source RAW video source implemented by user.
@param rawMode Allow the raw encoded data which has been read up until the last call to grab() to be retrieved by calling retrieve(rawData,RAW_DATA_IDX).
@param minNumDecodeSurfaces Minimum number of internal decode surfaces used by the hardware decoder. NVDEC will automatically determine the minimum number of
surfaces it requires for correct functionality and optimal video memory usage but not necessarily for best performance, which depends on the design of the
overall application. The optimal number of decode surfaces (in terms of performance and memory utilization) should be decided by experimentation for each application,
but it cannot go below the number determined by NVDEC.
@param params Initializaton parameters. See cv::cudacodec::VideoReaderInitParams.
*/
CV_EXPORTS_W Ptr<VideoReader> createVideoReader(const Ptr<RawVideoSource>& source, const bool rawMode = false, const int minNumDecodeSurfaces = 0);
CV_EXPORTS_W Ptr<VideoReader> createVideoReader(const Ptr<RawVideoSource>& source, const VideoReaderInitParams params = VideoReaderInitParams());
//! @}

@ -34,6 +34,35 @@ class cudacodec_test(NewOpenCVTests):
ret, _gpu_mat2 = reader.nextFrame(gpu_mat)
#TODO: self.assertTrue(gpu_mat == gpu_mat2)
self.assertTrue(ret)
params = cv.cudacodec.VideoReaderInitParams()
params.rawMode = True
ms_gs = 1234
reader = cv.cudacodec.createVideoReader(vid_path,[cv.CAP_PROP_OPEN_TIMEOUT_MSEC, ms_gs], params)
ret, ms = reader.get(cv.CAP_PROP_OPEN_TIMEOUT_MSEC)
self.assertTrue(ret and ms == ms_gs)
ret, raw_mode = reader.getVideoReaderProps(cv.cudacodec.VideoReaderProps_PROP_RAW_MODE)
self.assertTrue(ret and raw_mode)
ret, colour_code = reader.getVideoReaderProps(cv.cudacodec.VideoReaderProps_PROP_COLOR_FORMAT)
self.assertTrue(ret and colour_code == cv.cudacodec.ColorFormat_BGRA)
colour_code_gs = cv.cudacodec.ColorFormat_GRAY
reader.set(colour_code_gs)
ret, colour_code = reader.getVideoReaderProps(cv.cudacodec.VideoReaderProps_PROP_COLOR_FORMAT)
self.assertTrue(ret and colour_code == colour_code_gs)
ret, i_base = reader.getVideoReaderProps(cv.cudacodec.VideoReaderProps_PROP_RAW_PACKAGES_BASE_INDEX)
self.assertTrue(ret and i_base == 2.0)
self.assertTrue(reader.grab())
ret, gpu_mat3 = reader.retrieve()
self.assertTrue(ret and isinstance(gpu_mat3,cv.cuda.GpuMat) and not gpu_mat3.empty())
ret = reader.retrieve(gpu_mat3)
self.assertTrue(ret and isinstance(gpu_mat3,cv.cuda.GpuMat) and not gpu_mat3.empty())
ret, n_raw_packages_since_last_grab = reader.getVideoReaderProps(cv.cudacodec.VideoReaderProps_PROP_NUMBER_OF_RAW_PACKAGES_SINCE_LAST_GRAB)
self.assertTrue(ret and n_raw_packages_since_last_grab > 0)
ret, raw_data = reader.retrieve(int(i_base))
self.assertTrue(ret and isinstance(raw_data,np.ndarray) and np.any(raw_data))
except cv.error as e:
notSupported = (e.code == cv.Error.StsNotImplemented or e.code == cv.Error.StsUnsupportedFormat or e.code == cv.Error.GPU_API_CALL_ERROR)
self.assertTrue(notSupported)

@ -57,16 +57,20 @@ cv::cudacodec::detail::FrameQueue::~FrameQueue() {
void cv::cudacodec::detail::FrameQueue::init(const int _maxSz) {
AutoLock autoLock(mtx_);
if (isFrameInUse_)
return;
maxSz = _maxSz;
displayQueue_ = std::vector<CUVIDPARSERDISPINFO>(maxSz, CUVIDPARSERDISPINFO());
isFrameInUse_ = new volatile int[maxSz];
std::memset((void*)isFrameInUse_, 0, sizeof(*isFrameInUse_) * maxSz);
}
bool cv::cudacodec::detail::FrameQueue::waitUntilFrameAvailable(int pictureIndex)
bool cv::cudacodec::detail::FrameQueue::waitUntilFrameAvailable(int pictureIndex, const bool allowFrameDrop)
{
while (isInUse(pictureIndex))
{
if (allowFrameDrop && dequeueUntil(pictureIndex))
break;
// Decoder is getting too far ahead from display
Thread::sleep(1);
@ -110,6 +114,20 @@ void cv::cudacodec::detail::FrameQueue::enqueue(const CUVIDPARSERDISPINFO* picPa
} while (!isEndOfDecode());
}
bool cv::cudacodec::detail::FrameQueue::dequeueUntil(const int pictureIndex) {
AutoLock autoLock(mtx_);
if (isFrameInUse_[pictureIndex] != 1)
return false;
for (int i = 0; i < framesInQueue_; i++) {
const bool found = displayQueue_.at(readPosition_).picture_index == pictureIndex;
isFrameInUse_[displayQueue_.at(readPosition_).picture_index] = 0;
framesInQueue_--;
readPosition_ = (readPosition_ + 1) % maxSz;
if (found) return true;
}
return false;
}
bool cv::cudacodec::detail::FrameQueue::dequeue(CUVIDPARSERDISPINFO& displayInfo, std::vector<RawPacket>& rawPackets)
{
AutoLock autoLock(mtx_);
@ -124,6 +142,7 @@ bool cv::cudacodec::detail::FrameQueue::dequeue(CUVIDPARSERDISPINFO& displayInfo
}
readPosition_ = (entry + 1) % maxSz;
framesInQueue_--;
isFrameInUse_[displayInfo.picture_index] = 2;
return true;
}

@ -72,7 +72,9 @@ public:
// If the requested frame is available the method returns true.
// If decoding was interrupted before the requested frame becomes
// available, the method returns false.
bool waitUntilFrameAvailable(int pictureIndex);
// If allowFrameDrop == true, spin is disabled and n > 0 frames are discarded
// to ensure a frame is available.
bool waitUntilFrameAvailable(int pictureIndex, const bool allowFrameDrop = false);
void enqueue(const CUVIDPARSERDISPINFO* picParams, const std::vector<RawPacket> rawPackets);
@ -84,8 +86,16 @@ public:
// false, if the queue was empty and no new frame could be returned.
bool dequeue(CUVIDPARSERDISPINFO& displayInfo, std::vector<RawPacket>& rawPackets);
void releaseFrame(const CUVIDPARSERDISPINFO& picParams) { isFrameInUse_[picParams.picture_index] = false; }
// Deque all frames up to and including the frame with index pictureIndex - must only
// be called in the same thread as enqueue.
// Parameters:
// pictureIndex - Display index of the frame.
// Returns:
// true, if successful,
// false, if no frames are dequed.
bool dequeueUntil(const int pictureIndex);
void releaseFrame(const CUVIDPARSERDISPINFO& picParams) { isFrameInUse_[picParams.picture_index] = 0; }
private:
bool isInUse(int pictureIndex) const { return isFrameInUse_[pictureIndex] != 0; }

@ -45,14 +45,39 @@
#ifdef HAVE_NVCUVID
static const char* GetVideoChromaFormatString(cudaVideoChromaFormat eChromaFormat) {
static struct {
cudaVideoChromaFormat eChromaFormat;
const char* name;
} aChromaFormatName[] = {
{ cudaVideoChromaFormat_Monochrome, "YUV 400 (Monochrome)" },
{ cudaVideoChromaFormat_420, "YUV 420" },
{ cudaVideoChromaFormat_422, "YUV 422" },
{ cudaVideoChromaFormat_444, "YUV 444" },
};
if (eChromaFormat >= 0 && eChromaFormat < sizeof(aChromaFormatName) / sizeof(aChromaFormatName[0])) {
return aChromaFormatName[eChromaFormat].name;
}
return "Unknown";
}
void cv::cudacodec::detail::VideoDecoder::create(const FormatInfo& videoFormat)
{
if (videoFormat.nBitDepthMinus8 > 0 || videoFormat.chromaFormat == YUV444)
CV_Error(Error::StsUnsupportedFormat, "NV12 output currently supported for 8 bit YUV420, YUV422 and Monochrome inputs.");
videoFormat_ = videoFormat;
{
AutoLock autoLock(mtx_);
videoFormat_ = videoFormat;
}
const cudaVideoCodec _codec = static_cast<cudaVideoCodec>(videoFormat.codec);
const cudaVideoChromaFormat _chromaFormat = static_cast<cudaVideoChromaFormat>(videoFormat.chromaFormat);
if (videoFormat.nBitDepthMinus8 > 0) {
std::ostringstream warning;
warning << "NV12 (8 bit luma, 4 bit chroma) is currently the only supported decoder output format. Video input is " << videoFormat.nBitDepthMinus8 + 8 << " bit " \
<< std::string(GetVideoChromaFormatString(_chromaFormat)) << ". Truncating luma to 8 bits";
if (videoFormat.chromaFormat != YUV420)
warning << " and chroma to 4 bits";
CV_LOG_WARNING(NULL, warning.str());
}
const cudaVideoCreateFlags videoCreateFlags = (_codec == cudaVideoCodec_JPEG || _codec == cudaVideoCodec_MPEG2) ?
cudaVideoCreate_PreferCUDA :
cudaVideoCreate_PreferCUVID;
@ -98,9 +123,10 @@ void cv::cudacodec::detail::VideoDecoder::create(const FormatInfo& videoFormat)
cuSafeCall(cuCtxPushCurrent(ctx_));
cuSafeCall(cuvidGetDecoderCaps(&decodeCaps));
cuSafeCall(cuCtxPopCurrent(NULL));
if (!decodeCaps.bIsSupported)
if (!(decodeCaps.bIsSupported && (decodeCaps.nOutputFormatMask & (1 << cudaVideoSurfaceFormat_NV12)))){
CV_Error(Error::StsUnsupportedFormat, "Video source is not supported by hardware video decoder");
CV_LOG_ERROR(NULL, "Video source is not supported by hardware video decoder.");
}
CV_Assert(videoFormat.ulWidth >= decodeCaps.nMinWidth &&
videoFormat.ulHeight >= decodeCaps.nMinHeight &&
videoFormat.ulWidth <= decodeCaps.nMaxWidth &&
@ -115,6 +141,7 @@ void cv::cudacodec::detail::VideoDecoder::create(const FormatInfo& videoFormat)
createInfo_.ulHeight = videoFormat.ulHeight;
createInfo_.ulNumDecodeSurfaces = videoFormat.ulNumDecodeSurfaces;
createInfo_.ChromaFormat = _chromaFormat;
createInfo_.bitDepthMinus8 = videoFormat.nBitDepthMinus8;
createInfo_.OutputFormat = cudaVideoSurfaceFormat_NV12;
createInfo_.DeinterlaceMode = static_cast<cudaVideoDeinterlaceMode>(videoFormat.deinterlaceMode);
createInfo_.ulTargetWidth = videoFormat.width;

@ -45,9 +45,10 @@
#ifdef HAVE_NVCUVID
cv::cudacodec::detail::VideoParser::VideoParser(VideoDecoder* videoDecoder, FrameQueue* frameQueue) :
videoDecoder_(videoDecoder), frameQueue_(frameQueue), unparsedPackets_(0), hasError_(false)
cv::cudacodec::detail::VideoParser::VideoParser(VideoDecoder* videoDecoder, FrameQueue* frameQueue, const bool allowFrameDrop, const bool udpSource) :
videoDecoder_(videoDecoder), frameQueue_(frameQueue), allowFrameDrop_(allowFrameDrop)
{
if (udpSource) maxUnparsedPackets_ = 0;
CUVIDPARSERPARAMS params;
std::memset(&params, 0, sizeof(CUVIDPARSERPARAMS));
@ -78,16 +79,17 @@ bool cv::cudacodec::detail::VideoParser::parseVideoData(const unsigned char* dat
if (cuvidParseVideoData(parser_, &packet) != CUDA_SUCCESS)
{
CV_LOG_ERROR(NULL, "Call to cuvidParseVideoData failed!");
hasError_ = true;
frameQueue_->endDecode();
return false;
}
constexpr int maxUnparsedPackets = 20;
++unparsedPackets_;
if (unparsedPackets_ > maxUnparsedPackets)
if (maxUnparsedPackets_ && unparsedPackets_ > maxUnparsedPackets_)
{
CV_LOG_ERROR(NULL, "Maxium number of packets (" << maxUnparsedPackets_ << ") parsed without decoding a frame or reconfiguring the decoder, if reading from \
a live source consider initializing with VideoReaderInitParams::udpSource == true.");
hasError_ = true;
frameQueue_->endDecode();
return false;
@ -122,7 +124,8 @@ int CUDAAPI cv::cudacodec::detail::VideoParser::HandleVideoSequence(void* userDa
newFormat.height = format->coded_height;
newFormat.displayArea = Rect(Point(format->display_area.left, format->display_area.top), Point(format->display_area.right, format->display_area.bottom));
newFormat.fps = format->frame_rate.numerator / static_cast<float>(format->frame_rate.denominator);
newFormat.ulNumDecodeSurfaces = max(thiz->videoDecoder_->nDecodeSurfaces(), static_cast<int>(format->min_num_decode_surfaces));
newFormat.ulNumDecodeSurfaces = min(!thiz->allowFrameDrop_ ? max(thiz->videoDecoder_->nDecodeSurfaces(), static_cast<int>(format->min_num_decode_surfaces)) :
format->min_num_decode_surfaces * 2, 32);
if (format->progressive_sequence)
newFormat.deinterlaceMode = Weave;
else
@ -149,6 +152,7 @@ int CUDAAPI cv::cudacodec::detail::VideoParser::HandleVideoSequence(void* userDa
}
catch (const cv::Exception&)
{
CV_LOG_ERROR(NULL, "Attempt to reconfigure Nvidia decoder failed!");
thiz->hasError_ = true;
return false;
}
@ -163,13 +167,13 @@ int CUDAAPI cv::cudacodec::detail::VideoParser::HandlePictureDecode(void* userDa
thiz->unparsedPackets_ = 0;
bool isFrameAvailable = thiz->frameQueue_->waitUntilFrameAvailable(picParams->CurrPicIdx);
bool isFrameAvailable = thiz->frameQueue_->waitUntilFrameAvailable(picParams->CurrPicIdx, thiz->allowFrameDrop_);
if (!isFrameAvailable)
return false;
if (!thiz->videoDecoder_->decodePicture(picParams))
{
CV_LOG_ERROR(NULL, "Decoding failed!");
thiz->hasError_ = true;
return false;
}

@ -52,7 +52,7 @@ namespace cv { namespace cudacodec { namespace detail {
class VideoParser
{
public:
VideoParser(VideoDecoder* videoDecoder, FrameQueue* frameQueue);
VideoParser(VideoDecoder* videoDecoder, FrameQueue* frameQueue, const bool allowFrameDrop = false, const bool udpSource = false);
~VideoParser()
{
@ -63,13 +63,19 @@ public:
bool hasError() const { return hasError_; }
bool udpSource() const { return maxUnparsedPackets_ == 0; }
bool allowFrameDrops() const { return allowFrameDrop_; }
private:
VideoDecoder* videoDecoder_;
FrameQueue* frameQueue_;
VideoDecoder* videoDecoder_ = 0;
FrameQueue* frameQueue_ = 0;
CUvideoparser parser_;
int unparsedPackets_;
int unparsedPackets_ = 0;
int maxUnparsedPackets_ = 20;
std::vector<RawPacket> currentFramePackets;
volatile bool hasError_;
volatile bool hasError_ = false;
bool allowFrameDrop_ = false;
// Called when the decoder encounters a video format change (or initial sequence header)
// This particular implementation of the callback returns 0 in case the video format changes

@ -48,18 +48,18 @@ using namespace cv::cudacodec;
#ifndef HAVE_NVCUVID
Ptr<VideoReader> cv::cudacodec::createVideoReader(const String&, const std::vector<int>&, const bool, const int) { throw_no_cuda(); return Ptr<VideoReader>(); }
Ptr<VideoReader> cv::cudacodec::createVideoReader(const Ptr<RawVideoSource>&, const bool, const int) { throw_no_cuda(); return Ptr<VideoReader>(); }
Ptr<VideoReader> cv::cudacodec::createVideoReader(const String&, const std::vector<int>&, const VideoReaderInitParams) { throw_no_cuda(); return Ptr<VideoReader>(); }
Ptr<VideoReader> cv::cudacodec::createVideoReader(const Ptr<RawVideoSource>&, const VideoReaderInitParams) { throw_no_cuda(); return Ptr<VideoReader>(); }
#else // HAVE_NVCUVID
void nv12ToBgra(const GpuMat& decodedFrame, GpuMat& outFrame, int width, int height, cudaStream_t stream);
void videoDecPostProcessFrame(const GpuMat& decodedFrame, GpuMat& outFrame, int width, int height, const ColorFormat colorFormat,
cudaStream_t stream)
Stream stream)
{
if (colorFormat == ColorFormat::BGRA) {
nv12ToBgra(decodedFrame, outFrame, width, height, stream);
nv12ToBgra(decodedFrame, outFrame, width, height, StreamAccessor::getStream(stream));
}
else if (colorFormat == ColorFormat::BGR) {
outFrame.create(height, width, CV_8UC3);
@ -67,12 +67,15 @@ void videoDecPostProcessFrame(const GpuMat& decodedFrame, GpuMat& outFrame, int
NppiSize oSizeROI = { width,height };
NppStreamContext nppStreamCtx;
nppSafeCall(nppGetStreamContext(&nppStreamCtx));
nppStreamCtx.hStream = stream;
nppStreamCtx.hStream = StreamAccessor::getStream(stream);
nppSafeCall(nppiNV12ToBGR_8u_P2C3R_Ctx(pSrc, decodedFrame.step, outFrame.data, outFrame.step, oSizeROI, nppStreamCtx));
}
else if (colorFormat == ColorFormat::GRAY) {
outFrame.create(height, width, CV_8UC1);
cudaMemcpy2DAsync(outFrame.ptr(), outFrame.step, decodedFrame.ptr(), decodedFrame.step, width, height, cudaMemcpyDeviceToDevice, stream);
cudaMemcpy2DAsync(outFrame.ptr(), outFrame.step, decodedFrame.ptr(), decodedFrame.step, width, height, cudaMemcpyDeviceToDevice, StreamAccessor::getStream(stream));
}
else if (colorFormat == ColorFormat::YUV) {
decodedFrame.copyTo(outFrame, stream);
}
}
@ -83,7 +86,7 @@ namespace
class VideoReaderImpl : public VideoReader
{
public:
explicit VideoReaderImpl(const Ptr<VideoSource>& source, const int minNumDecodeSurfaces);
explicit VideoReaderImpl(const Ptr<VideoSource>& source, const int minNumDecodeSurfaces, const bool allowFrameDrop = false , const bool udpSource = false);
~VideoReaderImpl();
bool nextFrame(GpuMat& frame, Stream& stream) CV_OVERRIDE;
@ -96,9 +99,10 @@ namespace
bool set(const VideoReaderProps propertyId, const double propertyVal) CV_OVERRIDE;
void VideoReaderImpl::set(const ColorFormat _colorFormat) CV_OVERRIDE;
void set(const ColorFormat _colorFormat) CV_OVERRIDE;
bool get(const VideoReaderProps propertyId, double& propertyVal) const CV_OVERRIDE;
bool getVideoReaderProps(const VideoReaderProps propertyId, double& propertyValOut, double propertyValIn) const CV_OVERRIDE;
bool get(const int propertyId, double& propertyVal) const CV_OVERRIDE;
@ -127,7 +131,7 @@ namespace
return videoSource_->format();
}
VideoReaderImpl::VideoReaderImpl(const Ptr<VideoSource>& source, const int minNumDecodeSurfaces) :
VideoReaderImpl::VideoReaderImpl(const Ptr<VideoSource>& source, const int minNumDecodeSurfaces, const bool allowFrameDrop, const bool udpSource) :
videoSource_(source),
lock_(0)
{
@ -140,7 +144,7 @@ namespace
cuSafeCall( cuvidCtxLockCreate(&lock_, ctx) );
frameQueue_.reset(new FrameQueue());
videoDecoder_.reset(new VideoDecoder(videoSource_->format().codec, minNumDecodeSurfaces, ctx, lock_));
videoParser_.reset(new VideoParser(videoDecoder_, frameQueue_));
videoParser_.reset(new VideoParser(videoDecoder_, frameQueue_, allowFrameDrop, udpSource));
videoSource_->setVideoParser(videoParser_);
videoSource_->start();
}
@ -217,7 +221,7 @@ namespace
// perform post processing on the CUDA surface (performs colors space conversion and post processing)
// comment this out if we include the line of code seen above
videoDecPostProcessFrame(decodedFrame, frame, videoDecoder_->targetWidth(), videoDecoder_->targetHeight(), colorFormat, StreamAccessor::getStream(stream));
videoDecPostProcessFrame(decodedFrame, frame, videoDecoder_->targetWidth(), videoDecoder_->targetHeight(), colorFormat, stream);
// unmap video frame
// unmapFrame() synchronizes with the VideoDecode API (ensures the frame has finished decoding)
@ -243,13 +247,13 @@ namespace
}
else if (idx == extraDataIdx) {
if (!frame.isMat())
CV_Error(Error::StsUnsupportedFormat, "Extra data is stored on the host and must be retrueved using a cv::Mat");
CV_Error(Error::StsUnsupportedFormat, "Extra data is stored on the host and must be retrieved using a cv::Mat");
videoSource_->getExtraData(frame.getMatRef());
}
else{
if (idx >= rawPacketsBaseIdx && idx < rawPacketsBaseIdx + rawPackets.size()) {
if (!frame.isMat())
CV_Error(Error::StsUnsupportedFormat, "Raw data is stored on the host and must retrievd using a cv::Mat");
CV_Error(Error::StsUnsupportedFormat, "Raw data is stored on the host and must be retrieved using a cv::Mat");
Mat tmp(1, rawPackets.at(idx - rawPacketsBaseIdx).size, CV_8UC1, rawPackets.at(idx - rawPacketsBaseIdx).Data(), rawPackets.at(idx - rawPacketsBaseIdx).size);
frame.getMatRef() = tmp;
}
@ -261,8 +265,9 @@ namespace
switch (propertyId) {
case VideoReaderProps::PROP_RAW_MODE :
videoSource_->SetRawMode(static_cast<bool>(propertyVal));
return true;
}
return true;
return false;
}
void VideoReaderImpl::set(const ColorFormat _colorFormat) {
@ -288,10 +293,10 @@ namespace
case VideoReaderProps::PROP_NUMBER_OF_RAW_PACKAGES_SINCE_LAST_GRAB:
propertyVal = rawPackets.size();
return true;
case::VideoReaderProps::PROP_RAW_MODE:
case VideoReaderProps::PROP_RAW_MODE:
propertyVal = videoSource_->RawModeEnabled();
return true;
case::VideoReaderProps::PROP_LRF_HAS_KEY_FRAME: {
case VideoReaderProps::PROP_LRF_HAS_KEY_FRAME: {
const int iPacket = propertyVal - rawPacketsBaseIdx;
if (videoSource_->RawModeEnabled() && iPacket >= 0 && iPacket < rawPackets.size()) {
propertyVal = rawPackets.at(iPacket).containsKeyFrame;
@ -300,12 +305,28 @@ namespace
else
break;
}
case VideoReaderProps::PROP_ALLOW_FRAME_DROP:
propertyVal = videoParser_->allowFrameDrops();
return true;
case VideoReaderProps::PROP_UDP_SOURCE:
propertyVal = videoParser_->udpSource();
return true;
case VideoReaderProps::PROP_COLOR_FORMAT:
propertyVal = static_cast<double>(colorFormat);
return true;
default:
break;
}
return false;
}
bool VideoReaderImpl::getVideoReaderProps(const VideoReaderProps propertyId, double& propertyValOut, double propertyValIn) const {
double propertyValInOut = propertyValIn;
const bool ret = get(propertyId, propertyValInOut);
propertyValOut = propertyValInOut;
return ret;
}
bool VideoReaderImpl::get(const int propertyId, double& propertyVal) const {
return videoSource_->get(propertyId, propertyVal);
}
@ -318,7 +339,7 @@ namespace
}
}
Ptr<VideoReader> cv::cudacodec::createVideoReader(const String& filename, const std::vector<int>& params, const bool rawMode, const int minNumDecodeSurfaces)
Ptr<VideoReader> cv::cudacodec::createVideoReader(const String& filename, const std::vector<int>& sourceParams, const VideoReaderInitParams params)
{
CV_Assert(!filename.empty());
@ -327,22 +348,22 @@ Ptr<VideoReader> cv::cudacodec::createVideoReader(const String& filename, const
try
{
// prefer ffmpeg to cuvidGetSourceVideoFormat() which doesn't always return the corrct raw pixel format
Ptr<RawVideoSource> source(new FFmpegVideoSource(filename, params));
videoSource.reset(new RawVideoSourceWrapper(source, rawMode));
Ptr<RawVideoSource> source(new FFmpegVideoSource(filename, sourceParams));
videoSource.reset(new RawVideoSourceWrapper(source, params.rawMode));
}
catch (...)
{
if (params.size()) throw;
if (sourceParams.size()) throw;
videoSource.reset(new CuvidVideoSource(filename));
}
return makePtr<VideoReaderImpl>(videoSource, minNumDecodeSurfaces);
return makePtr<VideoReaderImpl>(videoSource, params.minNumDecodeSurfaces, params.allowFrameDrop, params.udpSource);
}
Ptr<VideoReader> cv::cudacodec::createVideoReader(const Ptr<RawVideoSource>& source, const bool rawMode, const int minNumDecodeSurfaces)
Ptr<VideoReader> cv::cudacodec::createVideoReader(const Ptr<RawVideoSource>& source, const VideoReaderInitParams params)
{
Ptr<VideoSource> videoSource(new RawVideoSourceWrapper(source, rawMode));
return makePtr<VideoReaderImpl>(videoSource, minNumDecodeSurfaces);
Ptr<VideoSource> videoSource(new RawVideoSourceWrapper(source, params.rawMode));
return makePtr<VideoReaderImpl>(videoSource, params.minNumDecodeSurfaces);
}
#endif // HAVE_NVCUVID

@ -70,6 +70,10 @@ PARAM_TEST_CASE(CheckDecodeSurfaces, cv::cuda::DeviceInfo, std::string)
{
};
PARAM_TEST_CASE(CheckInitParams, cv::cuda::DeviceInfo, std::string, bool, bool, bool)
{
};
struct CheckParams : testing::TestWithParam<cv::cuda::DeviceInfo>
{
cv::cuda::DeviceInfo devInfo;
@ -127,10 +131,9 @@ CUDA_TEST_P(CheckExtraData, Reader)
const string path = get<0>(GET_PARAM(1));
const int sz = get<1>(GET_PARAM(1));
std::string inputFile = std::string(cvtest::TS::ptr()->get_data_path()) + "../" + path;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, true);
double rawModeVal = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_MODE, rawModeVal));
ASSERT_TRUE(rawModeVal);
cv::cudacodec::VideoReaderInitParams params;
params.rawMode = true;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
double extraDataIdx = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_EXTRA_DATA_INDEX, extraDataIdx));
ASSERT_EQ(extraDataIdx, 1 );
@ -151,10 +154,9 @@ CUDA_TEST_P(CheckKeyFrame, Reader)
const string path = GET_PARAM(1);
std::string inputFile = std::string(cvtest::TS::ptr()->get_data_path()) + "../" + path;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, true);
double rawModeVal = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_MODE, rawModeVal));
ASSERT_TRUE(rawModeVal);
cv::cudacodec::VideoReaderInitParams params;
params.rawMode = true;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
double rawIdxBase = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_PACKAGES_BASE_INDEX, rawIdxBase));
ASSERT_EQ(rawIdxBase, 2);
@ -187,6 +189,7 @@ CUDA_TEST_P(Video, Reader)
{cudacodec::ColorFormat::GRAY,1},
{cudacodec::ColorFormat::BGR,3},
{cudacodec::ColorFormat::BGRA,4},
{cudacodec::ColorFormat::YUV,1}
};
std::string inputFile = std::string(cvtest::TS::ptr()->get_data_path()) + "../" + GET_PARAM(1);
@ -198,10 +201,13 @@ CUDA_TEST_P(Video, Reader)
// request a different colour format for each frame
const std::pair< cudacodec::ColorFormat, int>& formatToChannels = formatsToChannels[i % formatsToChannels.size()];
reader->set(formatToChannels.first);
double colorFormat;
ASSERT_TRUE(reader->get(cudacodec::VideoReaderProps::PROP_COLOR_FORMAT, colorFormat) && static_cast<cudacodec::ColorFormat>(colorFormat) == formatToChannels.first);
ASSERT_TRUE(reader->nextFrame(frame));
if(!fmt.valid)
fmt = reader->format();
ASSERT_TRUE(frame.cols == fmt.width && frame.rows == fmt.height);
const int height = formatToChannels.first == cudacodec::ColorFormat::YUV ? 1.5 * fmt.height : fmt.height;
ASSERT_TRUE(frame.cols == fmt.width && frame.rows == height);
ASSERT_FALSE(frame.empty());
ASSERT_TRUE(frame.channels() == formatToChannels.second);
}
@ -220,10 +226,9 @@ CUDA_TEST_P(VideoReadRaw, Reader)
{
std::ofstream file(fileNameOut, std::ios::binary);
ASSERT_TRUE(file.is_open());
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, true);
double rawModeVal = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_MODE, rawModeVal));
ASSERT_TRUE(rawModeVal);
cv::cudacodec::VideoReaderInitParams params;
params.rawMode = true;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
double rawIdxBase = -1;
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_PACKAGES_BASE_INDEX, rawIdxBase));
ASSERT_EQ(rawIdxBase, 2);
@ -248,7 +253,9 @@ CUDA_TEST_P(VideoReadRaw, Reader)
{
cv::Ptr<cv::cudacodec::VideoReader> readerReference = cv::cudacodec::createVideoReader(inputFile);
cv::Ptr<cv::cudacodec::VideoReader> readerActual = cv::cudacodec::createVideoReader(fileNameOut, {}, true);
cv::cudacodec::VideoReaderInitParams params;
params.rawMode = true;
cv::Ptr<cv::cudacodec::VideoReader> readerActual = cv::cudacodec::createVideoReader(fileNameOut, {}, params);
double decodedFrameIdx = -1;
ASSERT_TRUE(readerActual->get(cv::cudacodec::VideoReaderProps::PROP_DECODED_FRAME_IDX, decodedFrameIdx));
ASSERT_EQ(decodedFrameIdx, 0);
@ -321,7 +328,9 @@ CUDA_TEST_P(CheckDecodeSurfaces, Reader)
}
{
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, false, ulNumDecodeSurfaces - 1);
cv::cudacodec::VideoReaderInitParams params;
params.minNumDecodeSurfaces = ulNumDecodeSurfaces - 1;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
cv::cudacodec::FormatInfo fmt = reader->format();
if (!fmt.valid) {
reader->grab();
@ -333,7 +342,9 @@ CUDA_TEST_P(CheckDecodeSurfaces, Reader)
}
{
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, false, ulNumDecodeSurfaces + 1);
cv::cudacodec::VideoReaderInitParams params;
params.minNumDecodeSurfaces = ulNumDecodeSurfaces + 1;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
cv::cudacodec::FormatInfo fmt = reader->format();
if (!fmt.valid) {
reader->grab();
@ -344,6 +355,22 @@ CUDA_TEST_P(CheckDecodeSurfaces, Reader)
for (int i = 0; i < 100; i++) ASSERT_TRUE(reader->grab());
}
}
CUDA_TEST_P(CheckInitParams, Reader)
{
cv::cuda::setDevice(GET_PARAM(0).deviceID());
const std::string inputFile = std::string(cvtest::TS::ptr()->get_data_path()) + "../" + GET_PARAM(1);
cv::cudacodec::VideoReaderInitParams params;
params.udpSource = GET_PARAM(2);
params.allowFrameDrop = GET_PARAM(3);
params.rawMode = GET_PARAM(4);
double udpSource = 0, allowFrameDrop = 0, rawMode = 0;
cv::Ptr<cv::cudacodec::VideoReader> reader = cv::cudacodec::createVideoReader(inputFile, {}, params);
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_UDP_SOURCE, udpSource) && static_cast<bool>(udpSource) == params.udpSource);
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_ALLOW_FRAME_DROP, allowFrameDrop) && static_cast<bool>(allowFrameDrop) == params.allowFrameDrop);
ASSERT_TRUE(reader->get(cv::cudacodec::VideoReaderProps::PROP_RAW_MODE, rawMode) && static_cast<bool>(rawMode) == params.rawMode);
}
#endif // HAVE_NVCUVID
#if defined(_WIN32) && defined(HAVE_NVCUVENC)
@ -431,5 +458,10 @@ INSTANTIATE_TEST_CASE_P(CUDA_Codec, CheckDecodeSurfaces, testing::Combine(
ALL_DEVICES,
testing::Values("highgui/video/big_buck_bunny.mp4")));
INSTANTIATE_TEST_CASE_P(CUDA_Codec, CheckInitParams, testing::Combine(
ALL_DEVICES,
testing::Values("highgui/video/big_buck_bunny.mp4"),
testing::Values(true,false), testing::Values(true,false), testing::Values(true,false)));
#endif // HAVE_NVCUVID || HAVE_NVCUVENC
}} // namespace

@ -471,12 +471,36 @@ public:
int fastThreshold=20,
bool blurForDescriptor=false);
//! if true, image will be blurred before descriptors calculation
CV_WRAP virtual void setBlurForDescriptor(bool blurForDescriptor) = 0;
CV_WRAP virtual bool getBlurForDescriptor() const = 0;
CV_WRAP virtual void setMaxFeatures(int maxFeatures) = 0;
CV_WRAP virtual int getMaxFeatures() const = 0;
CV_WRAP virtual void setScaleFactor(double scaleFactor) = 0;
CV_WRAP virtual double getScaleFactor() const = 0;
CV_WRAP virtual void setNLevels(int nlevels) = 0;
CV_WRAP virtual int getNLevels() const = 0;
CV_WRAP virtual void setEdgeThreshold(int edgeThreshold) = 0;
CV_WRAP virtual int getEdgeThreshold() const = 0;
CV_WRAP virtual void setFirstLevel(int firstLevel) = 0;
CV_WRAP virtual int getFirstLevel() const = 0;
CV_WRAP virtual void setWTA_K(int wta_k) = 0;
CV_WRAP virtual int getWTA_K() const = 0;
CV_WRAP virtual void setScoreType(int scoreType) = 0;
CV_WRAP virtual int getScoreType() const = 0;
CV_WRAP virtual void setPatchSize(int patchSize) = 0;
CV_WRAP virtual int getPatchSize() const = 0;
CV_WRAP virtual void setFastThreshold(int fastThreshold) = 0;
CV_WRAP virtual int getFastThreshold() const = 0;
//! if true, image will be blurred before descriptors calculation
CV_WRAP virtual void setBlurForDescriptor(bool blurForDescriptor) = 0;
CV_WRAP virtual bool getBlurForDescriptor() const = 0;
};
//! @}

@ -27,6 +27,18 @@ class cudafeatures2d_test(NewOpenCVTests):
_kps = fast.detectAsync(cuMat1)
orb = cv.cuda_ORB.create()
orb.setMaxFeatures(500)
orb.setScaleFactor(1.2)
orb.setNLevels(8)
orb.setEdgeThreshold(31)
orb.setFirstLevel(0)
orb.setWTA_K(2)
orb.setScoreType(cv.ORB_HARRIS_SCORE)
orb.setPatchSize(31)
orb.setFastThreshold(20)
orb.setBlurForDescriptor(True)
_kps1, descs1 = orb.detectAndComputeAsync(cuMat1, None)
_kps2, descs2 = orb.detectAndComputeAsync(cuMat2, None)

@ -373,13 +373,13 @@ namespace
virtual void setFirstLevel(int firstLevel) { firstLevel_ = firstLevel; }
virtual int getFirstLevel() const { return firstLevel_; }
virtual void setWTA_K(int wta_k) { WTA_K_ = wta_k; }
virtual void setWTA_K(int wta_k) { CV_Assert( wta_k == 2 || wta_k == 3 || wta_k == 4 ); WTA_K_ = wta_k; }
virtual int getWTA_K() const { return WTA_K_; }
virtual void setScoreType(int scoreType) { scoreType_ = scoreType; }
virtual int getScoreType() const { return scoreType_; }
virtual void setPatchSize(int patchSize) { patchSize_ = patchSize; }
virtual void setPatchSize(int patchSize) { CV_Assert( patchSize >= 2 ); patchSize_ = patchSize; }
virtual int getPatchSize() const { return patchSize_; }
virtual void setFastThreshold(int fastThreshold) { fastThreshold_ = fastThreshold; }

@ -87,25 +87,22 @@ namespace cv { namespace cuda { namespace device
}
}
int findCorners_gpu(const cudaTextureObject_t &eigTex, const int &rows, const int &cols, float threshold, PtrStepSzb mask, float2* corners, int max_count, cudaStream_t stream)
int findCorners_gpu(const cudaTextureObject_t &eigTex, const int &rows, const int &cols, float threshold, PtrStepSzb mask, float2* corners, int max_count, int* counterPtr, cudaStream_t stream)
{
int* counter_ptr;
cudaSafeCall( cudaMalloc(&counter_ptr, sizeof(int)) );
cudaSafeCall( cudaMemsetAsync(counter_ptr, 0, sizeof(int), stream) );
cudaSafeCall( cudaMemsetAsync(counterPtr, 0, sizeof(int), stream) );
dim3 block(16, 16);
dim3 grid(divUp(cols, block.x), divUp(rows, block.y));
if (mask.data)
findCorners<<<grid, block, 0, stream>>>(threshold, SingleMask(mask), corners, max_count, rows, cols, eigTex, counter_ptr);
findCorners<<<grid, block, 0, stream>>>(threshold, SingleMask(mask), corners, max_count, rows, cols, eigTex, counterPtr);
else
findCorners<<<grid, block, 0, stream>>>(threshold, WithOutMask(), corners, max_count, rows, cols, eigTex, counter_ptr);
findCorners<<<grid, block, 0, stream>>>(threshold, WithOutMask(), corners, max_count, rows, cols, eigTex, counterPtr);
cudaSafeCall( cudaGetLastError() );
int count;
cudaSafeCall( cudaMemcpyAsync(&count, counter_ptr, sizeof(int), cudaMemcpyDeviceToHost, stream) );
cudaSafeCall( cudaMemcpyAsync(&count, counterPtr, sizeof(int), cudaMemcpyDeviceToHost, stream) );
if (stream)
cudaSafeCall(cudaStreamSynchronize(stream));
else

@ -55,7 +55,7 @@ namespace cv { namespace cuda { namespace device
{
namespace gfft
{
int findCorners_gpu(const cudaTextureObject_t &eigTex_, const int &rows, const int &cols, float threshold, PtrStepSzb mask, float2* corners, int max_count, cudaStream_t stream);
int findCorners_gpu(const cudaTextureObject_t &eigTex_, const int &rows, const int &cols, float threshold, PtrStepSzb mask, float2* corners, int max_count, int* counterPtr, cudaStream_t stream);
void sortCorners_gpu(const cudaTextureObject_t &eigTex_, float2* corners, int count, cudaStream_t stream);
}
}}}
@ -67,7 +67,7 @@ namespace
public:
GoodFeaturesToTrackDetector(int srcType, int maxCorners, double qualityLevel, double minDistance,
int blockSize, bool useHarrisDetector, double harrisK);
~GoodFeaturesToTrackDetector();
void detect(InputArray image, OutputArray corners, InputArray mask, Stream& stream);
private:
@ -82,6 +82,8 @@ namespace
GpuMat buf_;
GpuMat eig_;
GpuMat tmpCorners_;
int* counterPtr_;
};
GoodFeaturesToTrackDetector::GoodFeaturesToTrackDetector(int srcType, int maxCorners, double qualityLevel, double minDistance,
@ -93,6 +95,12 @@ namespace
cornerCriteria_ = useHarrisDetector ?
cuda::createHarrisCorner(srcType, blockSize, 3, harrisK) :
cuda::createMinEigenValCorner(srcType, blockSize, 3);
cudaSafeCall(cudaMalloc(&counterPtr_, sizeof(int)));
}
GoodFeaturesToTrackDetector::~GoodFeaturesToTrackDetector()
{
cudaSafeCall(cudaFree(counterPtr_));
}
void GoodFeaturesToTrackDetector::detect(InputArray _image, OutputArray _corners, InputArray _mask, Stream& stream)
@ -125,17 +133,19 @@ namespace
PtrStepSzf eig = eig_;
cv::cuda::device::createTextureObjectPitch2D<float>(&eigTex_, eig, texDesc);
int total = findCorners_gpu(eigTex_, eig_.rows, eig_.cols, static_cast<float>(maxVal * qualityLevel_), mask, tmpCorners_.ptr<float2>(), tmpCorners_.cols, stream_);
int total = findCorners_gpu(eigTex_, eig_.rows, eig_.cols, static_cast<float>(maxVal * qualityLevel_), mask, tmpCorners_.ptr<float2>(), tmpCorners_.cols, counterPtr_, stream_);
if (total == 0)
{
_corners.release();
cudaSafeCall( cudaDestroyTextureObject(eigTex_) );
return;
}
sortCorners_gpu(eigTex_, tmpCorners_.ptr<float2>(), total, stream_);
cudaSafeCall( cudaDestroyTextureObject(eigTex_) );
if (minDistance_ < 1)
{
tmpCorners_.colRange(0, maxCorners_ > 0 ? std::min(maxCorners_, total) : total).copyTo(_corners, stream);

@ -356,7 +356,10 @@ disparity map.
@sa reprojectImageTo3D
*/
CV_EXPORTS_W void reprojectImageTo3D(InputArray disp, OutputArray xyzw, InputArray Q, int dst_cn = 4, Stream& stream = Stream::Null());
CV_EXPORTS void reprojectImageTo3D(InputArray disp, OutputArray xyzw, InputArray Q, int dst_cn = 4, Stream& stream = Stream::Null());
CV_EXPORTS_W inline void reprojectImageTo3D(GpuMat disp, CV_OUT GpuMat& xyzw, Mat Q, int dst_cn = 4, Stream& stream = Stream::Null()) {
reprojectImageTo3D((InputArray)disp, (OutputArray)xyzw, (InputArray)Q, dst_cn, stream);
}
/** @brief Colors a disparity image.

@ -0,0 +1,28 @@
#!/usr/bin/env python
import os
import cv2 as cv
import numpy as np
from tests_common import NewOpenCVTests, unittest
class cudastereo_test(NewOpenCVTests):
def setUp(self):
super(cudastereo_test, self).setUp()
if not cv.cuda.getCudaEnabledDeviceCount():
self.skipTest("No CUDA-capable device is detected")
def test_reprojectImageTo3D(self):
# Test's the functionality but not the results from reprojectImageTo3D
sz = (128,128)
np_disparity = np.random.randint(0, 64, sz, dtype=np.int16)
cu_disparity = cv.cuda_GpuMat(np_disparity)
np_q = np.random.randint(0, 100, (4, 4)).astype(np.float32)
stream = cv.cuda.Stream()
cu_xyz = cv.cuda.reprojectImageTo3D(cu_disparity, np_q, stream = stream)
self.assertTrue(cu_xyz.type() == cv.CV_32FC4 and cu_xyz.size() == sz)
cu_xyz1 = cv.cuda.GpuMat(sz, cv.CV_32FC3)
cv.cuda.reprojectImageTo3D(cu_disparity, np_q, cu_xyz1, 3, stream)
self.assertTrue(cu_xyz1.type() == cv.CV_32FC3 and cu_xyz1.size() == sz)
if __name__ == '__main__':
NewOpenCVTests.bootstrap()

@ -281,7 +281,7 @@ namespace cv { namespace cuda { namespace device
InitColSSD<RADIUS>(x_tex, y_tex, img_step, left, right, d, col_ssd);
if (col_ssd_extra > 0)
if (col_ssd_extra != nullptr)
if (x_tex + BLOCK_W < cwidth)
InitColSSD<RADIUS>(x_tex + BLOCK_W, y_tex, img_step, left, right, d, col_ssd_extra);

@ -79,10 +79,10 @@ public:
The function loadFontData loads font data.
@param fontFileName FontFile Name
@param id face_index to select a font faces in a single file.
@param idx face_index to select a font faces in a single file.
*/
CV_WRAP virtual void loadFontData(String fontFileName, int id) = 0;
CV_WRAP virtual void loadFontData(String fontFileName, int idx) = 0;
/** @brief Set Split Number from Bezier-curve to line
@ -99,7 +99,7 @@ If you want to draw small glyph, small is better.
The function putText renders the specified text string in the image. Symbols that cannot be rendered using the specified font are replaced by "Tofu" or non-drawn.
@param img Image. (Only 8UC3 image is supported.)
@param img Image. (Only 8UC1/8UC3/8UC4 2D mat is supported.)
@param text Text string to be drawn.
@param org Bottom-left/Top-left corner of the text string in the image.
@param fontHeight Drawing font size by pixel unit.
@ -123,7 +123,7 @@ That is, the following code renders some text, the tight box surrounding it, and
String text = "Funny text inside the box";
int fontHeight = 60;
int thickness = -1;
int linestyle = 8;
int linestyle = LINE_8;
Mat img(600, 800, CV_8UC3, Scalar::all(0));

@ -66,7 +66,7 @@ class CV_EXPORTS_W FreeType2Impl CV_FINAL : public FreeType2
public:
FreeType2Impl();
~FreeType2Impl();
void loadFontData(String fontFileName, int id) CV_OVERRIDE;
void loadFontData(String fontFileName, int idx) CV_OVERRIDE;
void setSplitNumber( int num ) CV_OVERRIDE;
void putText(
InputOutputArray img, const String& text, Point org,
@ -92,17 +92,28 @@ private:
int fontHeight, Scalar color,
int thickness, int line_type, bool bottomLeftOrigin
);
void putTextBitmapBlend(
InputOutputArray img, const String& text, Point org,
int fontHeight, Scalar color,
int thickness, int line_type, bool bottomLeftOrigin
);
void putTextOutline(
InputOutputArray img, const String& text, Point org,
int fontHeight, Scalar color,
int thickness, int line_type, bool bottomLeftOrigin
);
typedef void (putPixel_mono_fn)( Mat& _dst, const int _py, const int _px, const uint8_t *_col);
putPixel_mono_fn putPixel_8UC1_mono;
putPixel_mono_fn putPixel_8UC3_mono;
putPixel_mono_fn putPixel_8UC4_mono;
typedef void (putPixel_blend_fn)( Mat& _dst, const int _py, const int _px, const uint8_t *_col, const uint8_t alpha);
putPixel_blend_fn putPixel_8UC1_blend;
putPixel_blend_fn putPixel_8UC3_blend;
putPixel_blend_fn putPixel_8UC4_blend;
static int mvFn( const FT_Vector *to, void * user);
static int lnFn( const FT_Vector *to, void * user);
@ -158,7 +169,8 @@ FreeType2Impl::FreeType2Impl()
FreeType2Impl::~FreeType2Impl()
{
if( mIsFaceAvailable == true ){
if( mIsFaceAvailable == true )
{
hb_font_destroy (mHb_font);
CV_Assert(!FT_Done_Face(mFace));
mIsFaceAvailable = false;
@ -168,12 +180,22 @@ FreeType2Impl::~FreeType2Impl()
void FreeType2Impl::loadFontData(String fontFileName, int idx)
{
if( mIsFaceAvailable == true ){
CV_Assert( idx >= 0 );
if( mIsFaceAvailable == true )
{
hb_font_destroy (mHb_font);
CV_Assert(!FT_Done_Face(mFace));
}
CV_Assert(!FT_New_Face( mLibrary, fontFileName.c_str(), idx, &(mFace) ) );
mIsFaceAvailable = false;
CV_Assert( !FT_New_Face( mLibrary, fontFileName.c_str(), static_cast<FT_Long>(idx), &(mFace) ) );
mHb_font = hb_ft_font_create (mFace, NULL);
if ( mHb_font == NULL )
{
CV_Assert(!FT_Done_Face(mFace));
return;
}
CV_Assert( mHb_font != NULL );
mIsFaceAvailable = true;
}
@ -189,16 +211,17 @@ void FreeType2Impl::putText(
int _thickness, int _line_type, bool _bottomLeftOrigin
)
{
CV_Assert( mIsFaceAvailable == true );
CV_Assert( ( _img.empty() == false ) &&
( _img.isMat() == true ) &&
( _img.depth() == CV_8U ) &&
( _img.dims() == 2 ) &&
( _img.channels() == 3 ) );
CV_Assert( ( _line_type == CV_AA) ||
( _line_type == 4 ) ||
( _line_type == 8 ) );
CV_Assert( _fontHeight >= 0 );
CV_Assert ( mIsFaceAvailable == true );
CV_Assert ( _img.empty() == false );
CV_Assert ( _img.isMat() == true );
CV_Assert ( _img.dims() == 2 );
CV_Assert( ( _img.type() == CV_8UC1 ) ||
( _img.type() == CV_8UC3 ) ||
( _img.type() == CV_8UC4 ) );
CV_Assert( ( _line_type == LINE_AA) ||
( _line_type == LINE_4 ) ||
( _line_type == LINE_8 ) );
CV_Assert ( _fontHeight >= 0 );
if ( _text.empty() )
{
@ -209,15 +232,11 @@ void FreeType2Impl::putText(
return;
}
if( _line_type == CV_AA && _img.depth() != CV_8U ){
_line_type = 8;
}
CV_Assert(!FT_Set_Pixel_Sizes( mFace, _fontHeight, _fontHeight ));
if( _thickness < 0 ) // CV_FILLED
{
if ( _line_type == CV_AA ) {
if ( _line_type == LINE_AA ) {
putTextBitmapBlend( _img, _text, _org, _fontHeight, _color,
_thickness, _line_type, _bottomLeftOrigin );
}else{
@ -292,13 +311,36 @@ void FreeType2Impl::putTextOutline(
hb_buffer_destroy (hb_buffer);
}
void FreeType2Impl::putPixel_8UC1_mono( Mat& _dst, const int _py, const int _px, const uint8_t *_col)
{
uint8_t* ptr = _dst.ptr<uint8_t>( _py, _px );
(*ptr) = _col[0];
}
void FreeType2Impl::putPixel_8UC3_mono ( Mat& _dst, const int _py, const int _px, const uint8_t *_col)
{
cv::Vec3b* ptr = _dst.ptr<cv::Vec3b>( _py, _px );
(*ptr)[0] = _col[0];
(*ptr)[1] = _col[1];
(*ptr)[2] = _col[2];
}
void FreeType2Impl::putPixel_8UC4_mono( Mat& _dst, const int _py, const int _px, const uint8_t *_col)
{
cv::Vec4b* ptr = _dst.ptr<cv::Vec4b>( _py, _px );
(*ptr)[0] = _col[0];
(*ptr)[1] = _col[1];
(*ptr)[2] = _col[2];
(*ptr)[3] = _col[3];
}
void FreeType2Impl::putTextBitmapMono(
InputOutputArray _img, const String& _text, Point _org,
int _fontHeight, Scalar _color,
int _thickness, int _line_type, bool _bottomLeftOrigin )
{
CV_Assert( _thickness < 0 );
CV_Assert( _line_type == 4 || _line_type == 8);
CV_Assert( _line_type == LINE_4 || _line_type == LINE_8);
Mat dst = _img.getMat();
hb_buffer_t *hb_buffer = hb_buffer_create ();
@ -318,6 +360,17 @@ void FreeType2Impl::putTextBitmapMono(
_org.y -= _fontHeight;
}
const uint8_t _colorUC8n[4] = {
static_cast<uint8_t>(_color[0]),
static_cast<uint8_t>(_color[1]),
static_cast<uint8_t>(_color[2]),
static_cast<uint8_t>(_color[3]) };
void (cv::freetype::FreeType2Impl::*putPixel)( Mat&, const int, const int, const uint8_t*) =
(_img.type() == CV_8UC4)?(&FreeType2Impl::putPixel_8UC4_mono):
(_img.type() == CV_8UC3)?(&FreeType2Impl::putPixel_8UC3_mono):
(&FreeType2Impl::putPixel_8UC1_mono);
for( unsigned int i = 0 ; i < textLen ; i ++ ){
CV_Assert( !FT_Load_Glyph(mFace, info[i].codepoint, 0 ) );
CV_Assert( !FT_Render_Glyph( mFace->glyph, FT_RENDER_MODE_MONO ) );
@ -351,10 +404,7 @@ void FreeType2Impl::putTextBitmapMono(
}
if ( ( (cl >> bit) & 0x01 ) == 1 ) {
cv::Vec3b* ptr = dst.ptr<cv::Vec3b>( gPos.y + row, gPos.x + col * 8 + (7 - bit) );
(*ptr)[0] = _color[0];
(*ptr)[1] = _color[1];
(*ptr)[2] = _color[2];
(this->*putPixel)( dst, gPos.y + row, gPos.x + col * 8 + (7 - bit), _colorUC8n );
}
}
}
@ -366,6 +416,80 @@ void FreeType2Impl::putTextBitmapMono(
hb_buffer_destroy (hb_buffer);
}
// Alpha composite algorithm is porting from imgproc.
// See https://github.com/opencv/opencv/blob/4.6.0/modules/imgproc/src/drawing.cpp
// static void LineAA( Mat& img, Point2l pt1, Point2l pt2, const void* color )
// ICV_PUT_POINT Macro.
void FreeType2Impl::putPixel_8UC1_blend( Mat& _dst, const int _py, const int _px, const uint8_t *_col, const uint8_t alpha)
{
const int a = alpha;
const int cb = _col[0];
uint8_t* tptr = _dst.ptr<uint8_t>( _py, _px );
int _cb = static_cast<int>(tptr[0]);
_cb += ((cb - _cb)*a + 127)>> 8;
_cb += ((cb - _cb)*a + 127)>> 8;
tptr[0] = static_cast<uint8_t>(_cb);
}
void FreeType2Impl::putPixel_8UC3_blend ( Mat& _dst, const int _py, const int _px, const uint8_t *_col, const uint8_t alpha)
{
const int a = alpha;
const int cb = _col[0];
const int cg = _col[1];
const int cr = _col[2];
uint8_t* tptr = _dst.ptr<uint8_t>( _py, _px );
int _cb = static_cast<int>(tptr[0]);
_cb += ((cb - _cb)*a + 127)>> 8;
_cb += ((cb - _cb)*a + 127)>> 8;
int _cg = static_cast<int>(tptr[1]);
_cg += ((cg - _cg)*a + 127)>> 8;
_cg += ((cg - _cg)*a + 127)>> 8;
int _cr = static_cast<int>(tptr[2]);
_cr += ((cr - _cr)*a + 127)>> 8;
_cr += ((cr - _cr)*a + 127)>> 8;
tptr[0] = static_cast<uint8_t>(_cb);
tptr[1] = static_cast<uint8_t>(_cg);
tptr[2] = static_cast<uint8_t>(_cr);
}
void FreeType2Impl::putPixel_8UC4_blend( Mat& _dst, const int _py, const int _px, const uint8_t *_col, const uint8_t alpha)
{
const uint8_t a = alpha;
const int cb = _col[0];
const int cg = _col[1];
const int cr = _col[2];
const int ca = _col[3];
uint8_t* tptr = _dst.ptr<uint8_t>( _py, _px );
int _cb = static_cast<int>(tptr[0]);
_cb += ((cb - _cb)*a + 127)>> 8;
_cb += ((cb - _cb)*a + 127)>> 8;
int _cg = static_cast<int>(tptr[1]);
_cg += ((cg - _cg)*a + 127)>> 8;
_cg += ((cg - _cg)*a + 127)>> 8;
int _cr = static_cast<int>(tptr[2]);
_cr += ((cr - _cr)*a + 127)>> 8;
_cr += ((cr - _cr)*a + 127)>> 8;
int _ca = static_cast<int>(tptr[3]);
_ca += ((ca - _ca)*a + 127)>> 8;
_ca += ((ca - _ca)*a + 127)>> 8;
tptr[0] = static_cast<uint8_t>(_cb);
tptr[1] = static_cast<uint8_t>(_cg);
tptr[2] = static_cast<uint8_t>(_cr);
tptr[3] = static_cast<uint8_t>(_ca);
}
void FreeType2Impl::putTextBitmapBlend(
InputOutputArray _img, const String& _text, Point _org,
int _fontHeight, Scalar _color,
@ -373,7 +497,7 @@ void FreeType2Impl::putTextBitmapBlend(
{
CV_Assert( _thickness < 0 );
CV_Assert( _line_type == 16 );
CV_Assert( _line_type == LINE_AA );
Mat dst = _img.getMat();
hb_buffer_t *hb_buffer = hb_buffer_create ();
@ -393,6 +517,17 @@ void FreeType2Impl::putTextBitmapBlend(
_org.y -= _fontHeight;
}
const uint8_t _colorUC8n[4] = {
static_cast<uint8_t>(_color[0]),
static_cast<uint8_t>(_color[1]),
static_cast<uint8_t>(_color[2]),
static_cast<uint8_t>(_color[3]) };
void (cv::freetype::FreeType2Impl::*putPixel)( Mat&, const int, const int, const uint8_t*, const uint8_t) =
(_img.type() == CV_8UC4)?(&FreeType2Impl::putPixel_8UC4_blend):
(_img.type() == CV_8UC3)?(&FreeType2Impl::putPixel_8UC3_blend):
(&FreeType2Impl::putPixel_8UC1_blend);
for( unsigned int i = 0 ; i < textLen ; i ++ ){
CV_Assert( !FT_Load_Glyph(mFace, info[i].codepoint, 0 ) );
CV_Assert( !FT_Render_Glyph( mFace->glyph, FT_RENDER_MODE_NORMAL ) );
@ -411,7 +546,7 @@ void FreeType2Impl::putTextBitmapBlend(
}
for (int col = 0; col < bmp->pitch; col ++) {
int cl = bmp->buffer[ row * bmp->pitch + col ];
uint8_t cl = bmp->buffer[ row * bmp->pitch + col ];
if ( cl == 0 ) {
continue;
}
@ -424,12 +559,7 @@ void FreeType2Impl::putTextBitmapBlend(
break;
}
cv::Vec3b* ptr = dst.ptr<cv::Vec3b>( gPos.y + row , gPos.x + col);
double blendAlpha = (double ) cl / 255.0;
(*ptr)[0] = (double) _color[0] * blendAlpha + (*ptr)[0] * (1.0 - blendAlpha );
(*ptr)[1] = (double) _color[1] * blendAlpha + (*ptr)[1] * (1.0 - blendAlpha );
(*ptr)[2] = (double) _color[2] * blendAlpha + (*ptr)[2] * (1.0 - blendAlpha );
(this->*putPixel)( dst, gPos.y + row, gPos.x + col, _colorUC8n, cl );
}
}
_org.x += ( mFace->glyph->advance.x ) >> 6;

@ -0,0 +1,250 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "test_precomp.hpp"
namespace opencv_test { namespace {
struct MattypeParams
{
string title;
int mattype;
bool expect_success;
};
::std::ostream& operator<<(::std::ostream& os, const MattypeParams& prm) {
return os << prm.title;
}
const MattypeParams mattype_list[] =
{
{ "CV_8UC1", CV_8UC1, true}, { "CV_8UC2", CV_8UC2, false},
{ "CV_8UC3", CV_8UC3, true}, { "CV_8UC4", CV_8UC4, true},
{ "CV_8SC1", CV_8SC1, false}, { "CV_8SC2", CV_8SC2, false},
{ "CV_8SC3", CV_8SC3, false}, { "CV_8SC4", CV_8SC4, false},
{ "CV_16UC1", CV_16UC1, false}, { "CV_16UC2", CV_16UC2, false},
{ "CV_16UC3", CV_16UC3, false}, { "CV_16UC4", CV_16UC4, false},
{ "CV_16SC1", CV_16SC1, false}, { "CV_16SC2", CV_16SC2, false},
{ "CV_16SC3", CV_16SC3, false}, { "CV_16SC4", CV_16SC4, false},
{ "CV_32SC1", CV_32SC1, false}, { "CV_32SC2", CV_32SC2, false},
{ "CV_32SC3", CV_32SC3, false}, { "CV_32SC4", CV_32SC4, false},
{ "CV_32FC1", CV_32FC1, false}, { "CV_32FC2", CV_32FC2, false},
{ "CV_32FC3", CV_32FC3, false}, { "CV_32FC4", CV_32FC4, false},
{ "CV_64FC1", CV_64FC1, false}, { "CV_64FC2", CV_64FC2, false},
{ "CV_64FC3", CV_64FC3, false}, { "CV_64FC4", CV_64FC4, false},
{ "CV_16FC1", CV_16FC1, false}, { "CV_16FC2", CV_16FC2, false},
{ "CV_16FC3", CV_16FC3, false}, { "CV_16FC4", CV_16FC4, false},
};
/******************
* Basically usage
*****************/
TEST(Freetype_Basic, success )
{
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Mat dst(600,600, CV_8UC3, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_NO_THROW( ft2->putText(dst, "Basic,success", Point( 0, 50), 50, col, -1, LINE_AA, true ) );
}
/******************
* loadFontData()
*****************/
TEST(Freetype_loadFontData, nonexist_file)
{
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "UNEXITSTFONT"; /* NON EXISTS FONT DATA */
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_THROW( ft2->loadFontData( fontdata, 0 ), cv::Exception );
Mat dst(600,600, CV_8UC3, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_THROW( ft2->putText(dst, "nonexist_file", Point( 0, 50), 50, col, -1, LINE_AA, true ), cv::Exception );
}
TEST(Freetype_loadFontData, forget_calling)
{
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
// EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Mat dst(600,600, CV_8UC3, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_THROW( ft2->putText(dst, "forget_calling", Point( 0, 50), 50, col, -1, LINE_AA, true ), cv::Exception );
}
TEST(Freetype_loadFontData, call_multiple)
{
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
for( int i = 0 ; i < 100 ; i ++ )
{
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
}
Mat dst(600,600, CV_8UC3, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_NO_THROW( ft2->putText(dst, "call_mutilple", Point( 0, 50), 50, col, -1, LINE_AA, true ) );
}
typedef testing::TestWithParam<int> idx_range;
TEST_P(idx_range, failed )
{
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
EXPECT_THROW( ft2->loadFontData( fontdata, GetParam() ), cv::Exception );
}
const int idx_failed_list[] =
{
INT_MIN,
INT_MIN + 1,
-1,
1,
2,
INT_MAX - 1,
INT_MAX
};
INSTANTIATE_TEST_CASE_P(Freetype_loadFontData, idx_range,
testing::ValuesIn(idx_failed_list));
/******************
* setSplitNumber()
*****************/
typedef testing::TestWithParam<int> ctol_range;
TEST_P(ctol_range, success)
{
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
EXPECT_NO_THROW( ft2->setSplitNumber(GetParam()) );
Mat dst(600,600, CV_8UC3, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_NO_THROW( ft2->putText(dst, "CtoL", Point( 0, 50), 50, col, 1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_4: oOpPqQ", Point( 40, 100), 50, col, 1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_8: oOpPqQ", Point( 40, 150), 50, col, 1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_AA:oOpPqQ", Point( 40, 150), 50, col, 1, LINE_AA, true ) );
}
const int ctol_list[] =
{
1,
8,
16,
32,
64,
128,
// INT_MAX -1, // Hang-up
// INT_MAX // Hang-up
};
INSTANTIATE_TEST_CASE_P(Freetype_setSplitNumber, ctol_range,
testing::ValuesIn(ctol_list));
/********************
* putText()::common
*******************/
TEST(Freetype_putText, invalid_img )
{
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Scalar col(128,64,255,192);
{ /* empty mat */
Mat dst;
EXPECT_THROW( ft2->putText(dst, "Invalid_img(empty Mat)", Point( 0, 50), 50, col, -1, LINE_AA, true ), cv::Exception );
}
{ /* not mat(scalar) */
Scalar dst;
EXPECT_THROW( ft2->putText(dst, "Invalid_img(Scalar)", Point( 0, 50), 50, col, -1, LINE_AA, true ), cv::Exception );
}
}
typedef testing::TestWithParam<MattypeParams> MatType_Test;
TEST_P(MatType_Test, default)
{
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + "freetype/mplus/Mplus1-Regular.ttf";
const MattypeParams params = static_cast<MattypeParams>(GetParam());
const string title = params.title;
const int mattype = params.mattype;
const bool expect_success = params.expect_success;
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Mat dst(600,600, mattype, Scalar::all(255) );
Scalar col(128,64,255,192);
if ( expect_success == false )
{
EXPECT_THROW( ft2->putText(dst, title, Point( 0, 50), 50, col, -1, LINE_AA, true ), cv::Exception );
return;
}
EXPECT_NO_THROW( ft2->putText(dst, title, Point( 0, 50), 50, col, -1, LINE_AA, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_4 FILL(mono)", Point(40, 100), 50, col, -1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_8 FILL(mono)", Point(40, 150), 50, col, -1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_AA FILL(blend)",Point(40, 200), 50, col, -1, LINE_AA, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_4 OUTLINE(1)", Point(40, 250), 50, col, 1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_8 OUTLINE(1)", Point(40, 300), 50, col, 1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_AA OUTLINE(1)", Point(40, 350), 50, col, 1, LINE_AA, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_4 OUTLINE(5)", Point(40, 400), 50, col, 5, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_8 OUTLINE(5)", Point(40, 450), 50, col, 5, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, "LINE_AA OUTLINE(5)", Point(40, 500), 50, col, 5, LINE_AA, true ) );
putText(dst, "LINE_4 putText(th=1)" , Point( 40,550), FONT_HERSHEY_SIMPLEX, 0.5, col, 1, LINE_4);
putText(dst, "LINE_8 putText(th=1)" , Point( 40,565), FONT_HERSHEY_SIMPLEX, 0.5, col, 1, LINE_8);
putText(dst, "LINE_AA putText(th=1)", Point( 40,580), FONT_HERSHEY_SIMPLEX, 0.5, col, 1, LINE_AA);
putText(dst, "LINE_4 putText(th=2)" , Point( 240,550),FONT_HERSHEY_SIMPLEX, 0.5, col, 2, LINE_4);
putText(dst, "LINE_8 putText(th=2)" , Point( 240,565),FONT_HERSHEY_SIMPLEX, 0.5, col, 2, LINE_8);
putText(dst, "LINE_AA putText(th=2)", Point( 240,580),FONT_HERSHEY_SIMPLEX, 0.5, col, 2, LINE_AA);
if (cvtest::debugLevel > 0 )
{
imwrite( cv::format("%s-MatType.png", title.c_str()), dst );
}
}
INSTANTIATE_TEST_CASE_P(Freetype_putText, MatType_Test,
testing::ValuesIn(mattype_list));
}} // namespace

@ -0,0 +1,6 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "test_precomp.hpp"
CV_TEST_MAIN("cv")

@ -0,0 +1,10 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#ifndef __OPENCV_TEST_PRECOMP_HPP__
#define __OPENCV_TEST_PRECOMP_HPP__
#include "opencv2/freetype.hpp"
#include "opencv2/ts.hpp"
#endif

@ -0,0 +1,201 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "test_precomp.hpp"
namespace opencv_test { namespace {
struct DrawingParams
{
string title;
int mattype;
string fontname;
};
::std::ostream& operator<<(::std::ostream& os, const DrawingParams& prm) {
return os << prm.title;
}
const DrawingParams drawing_list[] =
{
{ "CV_8UC1-Mplus1-Regular", CV_8UC1, "freetype/mplus/Mplus1-Regular.ttf"},
{ "CV_8UC3-Mplus1-Regular", CV_8UC3, "freetype/mplus/Mplus1-Regular.ttf"},
{ "CV_8UC4-Mplus1-Regular", CV_8UC4, "freetype/mplus/Mplus1-Regular.ttf"},
};
/********************
* putText()::boundry
*******************/
typedef testing::TestWithParam<DrawingParams> BoundaryTest;
TEST_P(BoundaryTest, default)
{
const DrawingParams params = GetParam();
const string title = params.title;
const int mattype = params.mattype;
const string fontname = params.fontname;
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + fontname;
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Mat dst(600,600, mattype, Scalar::all(255) );
Scalar col(128,64,255,192);
EXPECT_NO_THROW( ft2->putText(dst, title, Point( 100, 200), 20, col, -1, LINE_AA, true ) );
const int textHeight = 30;
for ( int iy = -50 ; iy <= +50 ; iy++ )
{
Point textOrg( 50, iy );
const string text = "top boundary";
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_AA, true ) );
}
for ( int iy = -50 ; iy <= +50 ; iy++ )
{
Point textOrg( 400, dst.cols + iy );
const string text = "bottom boundary";
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_AA, true ) );
}
for ( int ix = -50 ; ix <= +50 ; ix++ )
{
Point textOrg( ix, 100 );
const string text = "left boundary";
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_AA, true ) );
}
for ( int ix = -50 ; ix <= +50 ; ix++ )
{
Point textOrg( dst.rows + ix, 500 );
const string text = "bottom boundary";
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_4, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_8, true ) );
EXPECT_NO_THROW( ft2->putText(dst, text, textOrg, textHeight, col, -1, LINE_AA, true ) );
}
if (cvtest::debugLevel > 0 )
{
imwrite( cv::format("%s-boundary.png", title.c_str()), dst );
}
}
INSTANTIATE_TEST_CASE_P(Freetype_putText, BoundaryTest,
testing::ValuesIn(drawing_list)) ;
/*********************
* putText()::Ligature
*********************/
// See https://github.com/opencv/opencv_contrib/issues/2627
static Mat clipRoiAs8UC1( Mat &dst, Rect roi_rect )
{
Mat roi = Mat(dst, roi_rect).clone();
switch( roi.type() ){
case CV_8UC4: cvtColor(roi,roi,COLOR_BGRA2GRAY); break;
case CV_8UC3: cvtColor(roi,roi,COLOR_BGR2GRAY); break;
case CV_8UC1: default: break; // Do nothing
}
return roi;
}
typedef testing::TestWithParam<DrawingParams> LigatureTest;
TEST_P(LigatureTest, regression2627)
{
const DrawingParams params = GetParam();
const string title = params.title;
const int mattype = params.mattype;
const string fontname = params.fontname;
const string root = cvtest::TS::ptr()->get_data_path();
const string fontdata = root + fontname;
cv::Ptr<cv::freetype::FreeType2> ft2;
EXPECT_NO_THROW( ft2 = cv::freetype::createFreeType2() );
EXPECT_NO_THROW( ft2->loadFontData( fontdata, 0 ) );
Mat dst(600,600, mattype, Scalar(0,0,0,255) );
Scalar col(255,255,255,255);
EXPECT_NO_THROW( ft2->putText(dst, title, Point( 0, 50), 30, col, -1, LINE_AA, true ) );
vector<string> texts = {
"ffi", // ff will be combined to single glyph.
"fs",
"fi",
"ff",
"ae",
"tz",
"oe",
"\xE3\x81\xAF", // HA ( HIRAGANA )
"\xE3\x81\xAF\xE3\x82\x99", // BA ( HA + VOICED SOUND MARK )
"\xE3\x81\xAF\xE3\x82\x9A", // PA ( HA + SEMI-VOICED SOUND MARK )
"\xE3\x83\x8F", // HA ( KATAKANA )
"\xE3\x83\x8F\xE3\x82\x99", // BA ( HA + VOICED SOUND MARK )
"\xE3\x83\x8F\xE3\x82\x9A", // PA ( HA + SEMI-VOICED SOUND MARK )
};
const int fontHeight = 20;
const int margin = fontHeight / 2; // for current glyph right edgeto next glyph left edge
const int start_x = 40;
const int start_y = 100;
const int skip_x = 100;
const int skip_y = 25;
int tx = start_x;
int ty = start_y;
for (auto it = texts.begin(); it != texts.end(); it++ )
{
if ( ty + fontHeight * 3 > dst.rows ) {
ty = start_y;
tx = tx + skip_x;
}
EXPECT_NO_THROW( ft2->putText(dst, *it, Point(tx,ty), fontHeight, col, -1, LINE_4, true ) );
{ // Check for next glyph area.
const Rect roi_rect = Rect( tx + fontHeight + margin, ty - fontHeight, fontHeight, fontHeight );
const Mat roi = clipRoiAs8UC1(dst, roi_rect);
EXPECT_EQ(0, countNonZero(roi) );
}
ty += skip_y;
EXPECT_NO_THROW( ft2->putText(dst, *it, Point(tx,ty), fontHeight, col, -1, LINE_8, true ) );
{ // Check for next glyph area.
const Rect roi_rect = Rect( tx + fontHeight + margin, ty - fontHeight, fontHeight, fontHeight );
const Mat roi = clipRoiAs8UC1(dst, roi_rect);
EXPECT_EQ(0, countNonZero(roi) );
}
ty += skip_y;
EXPECT_NO_THROW( ft2->putText(dst, *it, Point(tx,ty), fontHeight, col, 1, LINE_AA, true ) );
{ // Check for next glyph area.
const Rect roi_rect = Rect( tx + fontHeight + margin, ty - fontHeight, fontHeight, fontHeight );
const Mat roi = clipRoiAs8UC1(dst, roi_rect);
EXPECT_EQ(0, countNonZero(roi) );
}
ty += skip_y;
}
if (cvtest::debugLevel > 0 )
{
imwrite( cv::format("%s-contrib2627.png", title.c_str()), dst );
}
}
INSTANTIATE_TEST_CASE_P(Freetype_putText, LigatureTest,
testing::ValuesIn(drawing_list));
}} // namespace

@ -3,7 +3,7 @@
#include <opencv2/videoio.hpp>
#include <opencv2/ovis.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>

@ -453,7 +453,8 @@ public:
if(tus->getTextureName() != name)
{
RTShader::ShaderGenerator::getSingleton().invalidateMaterial(
RTShader::ShaderGenerator::DEFAULT_SCHEME_NAME, *bgplane->getMaterial());
RTShader::ShaderGenerator::DEFAULT_SCHEME_NAME, bgplane->getMaterial()->getName(),
RESOURCEGROUP_NAME);
tus->setTextureName(name);
tus->setTextureAddressingMode(TAM_CLAMP);

@ -256,7 +256,7 @@ public:
CV_WRAP virtual void reset() = 0;
/** @brief Get current pose in voxel space */
virtual const Affine3f getPose() const = 0;
virtual Affine3f getPose() const = 0;
/** @brief Process next depth frame
@param depth input Mat of depth frame

@ -95,7 +95,7 @@ public:
CV_WRAP virtual void reset() = 0;
/** @brief Get current pose in voxel space */
virtual const Affine3f getPose() const = 0;
virtual Affine3f getPose() const = 0;
/** @brief Process next depth frame

@ -308,7 +308,7 @@ public:
CV_WRAP virtual void reset() = 0;
/** @brief Get current pose in voxel space */
virtual const Affine3f getPose() const = 0;
virtual Affine3f getPose() const = 0;
/** @brief Process next depth frame

@ -208,7 +208,7 @@ class CV_EXPORTS_W LargeKinfu
CV_WRAP virtual void reset() = 0;
virtual const Affine3f getPose() const = 0;
virtual Affine3f getPose() const = 0;
CV_WRAP virtual bool update(InputArray depth) = 0;
};

@ -147,7 +147,7 @@ public:
void reset() CV_OVERRIDE;
const Affine3f getPose() const CV_OVERRIDE;
Affine3f getPose() const CV_OVERRIDE;
bool update(InputArray depth, InputArray rgb) CV_OVERRIDE;
@ -219,7 +219,7 @@ const Params& ColoredKinFuImpl<MatType>::getParams() const
}
template< typename MatType >
const Affine3f ColoredKinFuImpl<MatType>::getPose() const
Affine3f ColoredKinFuImpl<MatType>::getPose() const
{
return pose;
}

@ -97,7 +97,7 @@ public:
void reset() CV_OVERRIDE;
const Affine3f getPose() const CV_OVERRIDE;
Affine3f getPose() const CV_OVERRIDE;
bool update(InputArray depth) CV_OVERRIDE;
@ -260,7 +260,7 @@ const Params& DynaFuImpl<T>::getParams() const
}
template< typename T >
const Affine3f DynaFuImpl<T>::getPose() const
Affine3f DynaFuImpl<T>::getPose() const
{
return pose;
}

@ -135,7 +135,7 @@ public:
void reset() CV_OVERRIDE;
const Affine3f getPose() const CV_OVERRIDE;
Affine3f getPose() const CV_OVERRIDE;
bool update(InputArray depth) CV_OVERRIDE;
@ -205,7 +205,7 @@ const Params& KinFuImpl<MatType>::getParams() const
}
template< typename MatType >
const Affine3f KinFuImpl<MatType>::getPose() const
Affine3f KinFuImpl<MatType>::getPose() const
{
return pose;
}

@ -197,7 +197,7 @@ class LargeKinfuImpl : public LargeKinfu
void reset() CV_OVERRIDE;
const Affine3f getPose() const CV_OVERRIDE;
Affine3f getPose() const CV_OVERRIDE;
bool update(InputArray depth) CV_OVERRIDE;
@ -270,7 +270,7 @@ const Params& LargeKinfuImpl<MatType>::getParams() const
}
template<typename MatType>
const Affine3f LargeKinfuImpl<MatType>::getPose() const
Affine3f LargeKinfuImpl<MatType>::getPose() const
{
return pose;
}

@ -9,17 +9,17 @@ find_package(Ceres QUIET)
if(NOT Gflags_FOUND) # Ceres find gflags on the own, so separate search isn't necessary
find_package(Gflags QUIET)
endif()
if(NOT Glog_FOUND) # Ceres find glog on the own, so separate search isn't necessary
if(NOT (Glog_FOUND OR glog_FOUND)) # Ceres find glog on the own, so separate search isn't necessary
find_package(Glog QUIET)
endif()
if(NOT Gflags_FOUND OR NOT Glog_FOUND)
if(NOT Gflags_FOUND OR NOT (Glog_FOUND OR glog_FOUND))
# try local search scripts
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")
if(NOT Gflags_FOUND)
find_package(Gflags QUIET)
endif()
if(NOT Glog_FOUND)
if(NOT (Glog_FOUND OR glog_FOUND))
find_package(Glog QUIET)
endif()
endif()

@ -54,10 +54,10 @@ class MLEScorer {
double threshold_;
};
static uint IterationsRequired(int min_samples,
static unsigned int IterationsRequired(int min_samples,
double outliers_probability,
double inlier_ratio) {
return static_cast<uint>(
return static_cast<unsigned int>(
log(outliers_probability) / log(1.0 - pow(inlier_ratio, min_samples)));
}

@ -24,6 +24,7 @@
#include "ceres/ceres.h"
#include "ceres/rotation.h"
#include "ceres/version.h"
#include "libmv/base/vector.h"
#include "libmv/logging/logging.h"
#include "libmv/multiview/fundamental.h"
@ -485,7 +486,11 @@ void EuclideanBundleCommonIntrinsics(
PackCamerasRotationAndTranslation(tracks, *reconstruction);
// Parameterization used to restrict camera motion for modal solvers.
#if CERES_VERSION_MAJOR >= 3 || (CERES_VERSION_MAJOR >= 2 && CERES_VERSION_MINOR >= 1)
ceres::SubsetManifold *constant_translation_manifold = NULL;
#else
ceres::SubsetParameterization *constant_translation_parameterization = NULL;
#endif
if (bundle_constraints & BUNDLE_NO_TRANSLATION) {
std::vector<int> constant_translation;
@ -494,8 +499,13 @@ void EuclideanBundleCommonIntrinsics(
constant_translation.push_back(4);
constant_translation.push_back(5);
#if CERES_VERSION_MAJOR >= 3 || (CERES_VERSION_MAJOR >= 2 && CERES_VERSION_MINOR >= 1)
constant_translation_manifold =
new ceres::SubsetManifold(6, constant_translation);
#else
constant_translation_parameterization =
new ceres::SubsetParameterization(6, constant_translation);
#endif
}
// Add residual blocks to the problem.
@ -538,8 +548,13 @@ void EuclideanBundleCommonIntrinsics(
}
if (bundle_constraints & BUNDLE_NO_TRANSLATION) {
#if CERES_VERSION_MAJOR >= 3 || (CERES_VERSION_MAJOR >= 2 && CERES_VERSION_MINOR >= 1)
problem.SetManifold(current_camera_R_t,
constant_translation_manifold);
#else
problem.SetParameterization(current_camera_R_t,
constant_translation_parameterization);
#endif
}
zero_weight_tracks_flags[marker.track] = false;
@ -586,10 +601,17 @@ void EuclideanBundleCommonIntrinsics(
// Always set K3 constant, it's not used at the moment.
constant_intrinsics.push_back(OFFSET_K3);
#if CERES_VERSION_MAJOR >= 3 || (CERES_VERSION_MAJOR >= 2 && CERES_VERSION_MINOR >= 1)
ceres::SubsetManifold *subset_manifold =
new ceres::SubsetManifold(OFFSET_MAX, constant_intrinsics);
problem.SetManifold(ceres_intrinsics, subset_manifold);
#else
ceres::SubsetParameterization *subset_parameterization =
new ceres::SubsetParameterization(OFFSET_MAX, constant_intrinsics);
problem.SetParameterization(ceres_intrinsics, subset_parameterization);
#endif
}
// Configure the solver.

@ -273,7 +273,6 @@ int PoseCluster3D::readPoseCluster(FILE* f)
status = fread(&id, sizeof(int), 1, f);
status = fread(&numVotes, sizeof(int), 1, f);
status = fread(&numPoses, sizeof(int), 1, f);
fclose(f);
poseList.clear();
poseList.resize(numPoses);
@ -283,6 +282,7 @@ int PoseCluster3D::readPoseCluster(FILE* f)
poseList[i]->readPose(f);
}
fclose(f);
return 0;
}

@ -10,7 +10,7 @@ print('Select 3 tracking targets')
cv.namedWindow("tracking")
camera = cv.VideoCapture(sys.argv[1])
tracker = cv.MultiTracker_create()
tracker = cv.legacy.MultiTracker_create()
init_once = False
ok, image=camera.read()
@ -25,17 +25,17 @@ bbox3 = cv.selectROI('tracking', image)
while camera.isOpened():
ok, image=camera.read()
if not ok:
print 'no image to read'
print('no image to read')
break
if not init_once:
ok = tracker.add(cv.TrackerMIL_create(), image, bbox1)
ok = tracker.add(cv.TrackerMIL_create(), image, bbox2)
ok = tracker.add(cv.TrackerMIL_create(), image, bbox3)
ok = tracker.add(cv.legacy.TrackerMIL_create(), image, bbox1)
ok = tracker.add(cv.legacy.TrackerMIL_create(), image, bbox2)
ok = tracker.add(cv.legacy.TrackerMIL_create(), image, bbox3)
init_once = True
ok, boxes = tracker.update(image)
print ok, boxes
print(ok, boxes)
for newbox in boxes:
p1 = (int(newbox[0]), int(newbox[1]))

@ -19,7 +19,7 @@ init_once = False
while camera.isOpened():
ok, image=camera.read()
if not ok:
print 'no image to read'
print('no image to read')
break
if not init_once:
@ -27,7 +27,7 @@ while camera.isOpened():
init_once = True
ok, newbox = tracker.update(image)
print ok, newbox
print(ok, newbox)
if ok:
p1 = (int(newbox[0]), int(newbox[1]))

@ -37,7 +37,7 @@ else:
cap = cv2.VideoCapture(camIdx)
while True:
res, img = cap.read()
if img.empty():
if img is None:
break
res, points = detector.detectAndDecode(img)
for t in res:

@ -5,4 +5,4 @@ Extra 2D Features Framework
2. Non-free 2D feature algorithms
Extra 2D Features Framework containing experimental and non-free 2D feature detector/descriptor algorithms:
SURF, BRIEF, Censure, Freak, LUCID, Daisy, BEBLID, Self-similar.
SURF, BRIEF, Censure, Freak, LUCID, Daisy, BEBLID, TEBLID, Self-similar.

@ -154,6 +154,18 @@
author = {Iago Su\'arez and Ghesn Sfeir and Jos\'e M. Buenaposada and Luis Baumela},
}
@article{Suarez2021TEBLID,
title = {Revisiting Binary Local Image Description for Resource Limited Devices},
journal = {IEEE Robotics and Automation Letters},
volume = {6},
pages = {8317--8324},
year = {2021},
number = {4},
doi = {https://doi.org/10.1109/LRA.2021.3107024},
url = {https://arxiv.org/pdf/2108.08380.pdf},
author = {Iago Su\'arez and Jos\'e M. Buenaposada and Luis Baumela},
}
@inproceedings{winder2007learning,
title= {Learning Local Image Descriptors},
author= {Winder, Simon AJ and Brown, Matthew},

@ -224,6 +224,49 @@ public:
CV_WRAP static Ptr<BEBLID> create(float scale_factor, int n_bits = BEBLID::SIZE_512_BITS);
};
/** @brief Class implementing TEBLID (Triplet-based Efficient Binary Local Image Descriptor),
* described in @cite Suarez2021TEBLID.
TEBLID stands for Triplet-based Efficient Binary Local Image Descriptor, although originally it was called BAD
\cite Suarez2021TEBLID. It is an improvement over BEBLID \cite Suarez2020BEBLID, that uses triplet loss,
hard negative mining, and anchor swap to improve the image matching results.
It is able to describe keypoints from any detector just by changing the scale_factor parameter.
TEBLID is as efficient as ORB, BEBLID or BRISK, but the triplet-based training objective selected more
discriminative features that explain the accuracy gain. It is also more compact than BEBLID,
when running the [AKAZE example](https://github.com/opencv/opencv/blob/4.x/samples/cpp/tutorial_code/features2D/AKAZE_match.cpp)
with 10000 keypoints detected by ORB, BEBLID obtains 561 inliers (75%) with 512 bits, whereas
TEBLID obtains 621 (75.2%) with 256 bits. ORB obtains only 493 inliers (63%).
If you find this code useful, please add a reference to the following paper:
<BLOCKQUOTE> Iago Suárez, José M. Buenaposada, and Luis Baumela.
Revisiting Binary Local Image Description for Resource Limited Devices.
IEEE Robotics and Automation Letters, vol. 6, no. 4, pp. 8317-8324, Oct. 2021. </BLOCKQUOTE>
The descriptor was trained in Liberty split of the UBC datasets \cite winder2007learning .
*/
class CV_EXPORTS_W TEBLID : public Feature2D
{
public:
/**
* @brief Descriptor number of bits, each bit is a box average difference.
* The user can choose between 256 or 512 bits.
*/
enum TeblidSize
{
SIZE_256_BITS = 102, SIZE_512_BITS = 103,
};
/** @brief Creates the TEBLID descriptor.
@param scale_factor Adjust the sampling window around detected keypoints:
- <b> 1.00f </b> should be the scale for ORB keypoints
- <b> 6.75f </b> should be the scale for SIFT detected keypoints
- <b> 6.25f </b> is default and fits for KAZE, SURF detected keypoints
- <b> 5.00f </b> should be the scale for AKAZE, MSD, AGAST, FAST, BRISK keypoints
@param n_bits Determine the number of bits in the descriptor. Should be either
TEBLID::SIZE_256_BITS or TEBLID::SIZE_512_BITS.
*/
CV_WRAP static Ptr<TEBLID> create(float scale_factor, int n_bits = TEBLID::SIZE_256_BITS);
};
/** @brief Class implementing DAISY descriptor, described in @cite Tola10
@param radius radius of the descriptor at the initial scale

@ -0,0 +1,36 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "perf_precomp.hpp"
namespace opencv_test { namespace {
typedef perf::TestBaseWithParam<std::string> teblid;
#define TEBLID_IMAGES \
"cv/detectors_descriptors_evaluation/images_datasets/leuven/img1.png",\
"stitching/a3.png"
#ifdef OPENCV_ENABLE_NONFREE
PERF_TEST_P(teblid, extract, testing::Values(TEBLID_IMAGES))
{
string filename = getDataPath(GetParam());
Mat frame = imread(filename, IMREAD_GRAYSCALE);
ASSERT_FALSE(frame.empty()) << "Unable to load source image " << filename;
Mat mask;
declare.in(frame).time(90);
Ptr<SURF> detector = SURF::create();
vector<KeyPoint> points;
detector->detect(frame, points, mask);
Ptr<TEBLID> descriptor = TEBLID::create(6.25f);
cv::Mat descriptors;
TEST_CYCLE() descriptor->compute(frame, points, descriptors);
SANITY_CHECK_NOTHING();
}
#endif // NONFREE
}} // namespace

@ -30,14 +30,21 @@ struct ABWLParams
{
int x1, y1, x2, y2, boxRadius, th;
};
// Same as previous with floating point threshold
struct ABWLParamsFloatTh
{
int x1, y1, x2, y2, boxRadius;
float th;
};
// BEBLID implementation
template <class WeakLearnerT>
class BEBLID_Impl CV_FINAL: public BEBLID
{
public:
// constructor
explicit BEBLID_Impl(float scale_factor, int n_bits = SIZE_512_BITS);
explicit BEBLID_Impl(float scale_factor, const std::vector<WeakLearnerT>& wl_params);
// destructor
~BEBLID_Impl() CV_OVERRIDE = default;
@ -55,15 +62,65 @@ public:
void compute(InputArray image, vector<KeyPoint> &keypoints, OutputArray descriptors) CV_OVERRIDE;
private:
std::vector<ABWLParams> wl_params_;
std::vector<WeakLearnerT> wl_params_;
float scale_factor_;
cv::Size patch_size_;
void computeBEBLID(const cv::Mat &integralImg,
const std::vector<cv::KeyPoint> &keypoints,
cv::Mat &descriptors);
void computeBoxDiffsDescriptor(const cv::Mat &integralImg,
const std::vector<cv::KeyPoint> &keypoints,
cv::Mat &descriptors);
}; // END BEBLID_Impl CLASS
// TEBLID implementation
class TEBLID_Impl CV_FINAL: public TEBLID
{
public:
// constructor
explicit TEBLID_Impl(float scale_factor, const std::vector<ABWLParamsFloatTh>& wl_params) :
impl(scale_factor, wl_params){}
// destructor
~TEBLID_Impl() CV_OVERRIDE = default;
// returns the descriptor length in bytes
int descriptorSize() const CV_OVERRIDE { return impl.descriptorSize(); }
// returns the descriptor type
int descriptorType() const CV_OVERRIDE { return impl.descriptorType(); }
// returns the default norm type
int defaultNorm() const CV_OVERRIDE { return impl.defaultNorm(); }
// compute descriptors given keypoints
void compute(InputArray image, vector<KeyPoint> &keypoints, OutputArray descriptors) CV_OVERRIDE
{
impl.compute(image, keypoints, descriptors);
}
private:
BEBLID_Impl<ABWLParamsFloatTh> impl;
}; // END TEBLID_Impl CLASS
Ptr<TEBLID> TEBLID::create(float scale_factor, int n_bits)
{
if (n_bits == TEBLID::SIZE_512_BITS)
{
#include "teblid.p512.hpp"
return makePtr<TEBLID_Impl>(scale_factor, teblid_wl_params_512);
}
else if(n_bits == TEBLID::SIZE_256_BITS)
{
#include "teblid.p256.hpp"
return makePtr<TEBLID_Impl>(scale_factor, teblid_wl_params_256);
}
else
{
CV_Error(Error::StsBadArg, "n_bits should be either TEBLID::SIZE_512_BITS or TEBLID::SIZE_256_BITS");
}
}
/**
* @brief Function that determines if a keypoint is close to the image border.
* @param kp The detected keypoint
@ -100,8 +157,9 @@ static inline bool isKeypointInTheBorder(const cv::KeyPoint &kp,
* @param scaleFactor A scale factor that magnifies the measurement functions w.r.t. the keypoint.
* @param patchSize The size of the normalized patch where the measurement functions were learnt.
*/
static inline void rectifyABWL(const std::vector<ABWLParams> &wlPatchParams,
std::vector<ABWLParams> &wlImageParams,
template< typename WeakLearnerT>
static inline void rectifyABWL(const std::vector<WeakLearnerT> &wlPatchParams,
std::vector<WeakLearnerT> &wlImageParams,
const cv::KeyPoint &kp,
float scaleFactor = 1,
const cv::Size &patchSize = cv::Size(32, 32))
@ -151,7 +209,8 @@ static inline void rectifyABWL(const std::vector<ABWLParams> &wlPatchParams,
* @param integralImage The integral image used to compute the average gray value in the square regions.
* @return The difference of gray level in the two squares defined by wlImageParams
*/
static inline float computeABWLResponse(const ABWLParams &wlImageParams,
template <typename WeakLearnerT>
static inline float computeABWLResponse(const WeakLearnerT &wlImageParams,
const cv::Mat &integralImage)
{
CV_DbgAssert(!integralImage.empty());
@ -239,7 +298,8 @@ static inline float computeABWLResponse(const ABWLParams &wlImageParams,
}
// descriptor computation using keypoints
void BEBLID_Impl::compute(InputArray _image, vector<KeyPoint> &keypoints, OutputArray _descriptors)
template <class WeakLearnerT>
void BEBLID_Impl<WeakLearnerT>::compute(InputArray _image, vector<KeyPoint> &keypoints, OutputArray _descriptors)
{
Mat image = _image.getMat();
@ -281,27 +341,21 @@ void BEBLID_Impl::compute(InputArray _image, vector<KeyPoint> &keypoints, Output
CV_DbgAssert(descriptors.type() == CV_8UC1);
// Compute the BEBLID descriptors
computeBEBLID(integralImg, keypoints, descriptors);
computeBoxDiffsDescriptor(integralImg, keypoints, descriptors);
}
// constructor
BEBLID_Impl::BEBLID_Impl(float scale_factor, int n_bits)
: scale_factor_(scale_factor), patch_size_(32, 32)
template <class WeakLearnerT>
BEBLID_Impl<WeakLearnerT>::BEBLID_Impl(float scale_factor, const std::vector<WeakLearnerT>& wl_params)
: wl_params_(wl_params), scale_factor_(scale_factor),patch_size_(32, 32)
{
#include "beblid.p512.hpp"
#include "beblid.p256.hpp"
if (n_bits == SIZE_512_BITS)
wl_params_.assign(wl_params_512, wl_params_512 + sizeof(wl_params_512) / sizeof(wl_params_512[0]));
else if(n_bits == SIZE_256_BITS)
wl_params_.assign(wl_params_256, wl_params_256 + sizeof(wl_params_256) / sizeof(wl_params_256[0]));
else
CV_Error(Error::StsBadArg, "n_wls should be either SIZE_512_BITS or SIZE_256_BITS");
}
// Internal function that implements the core of BEBLID descriptor
void BEBLID_Impl::computeBEBLID(const cv::Mat &integralImg,
const std::vector<cv::KeyPoint> &keypoints,
cv::Mat &descriptors)
template<class WeakLearnerT>
void BEBLID_Impl<WeakLearnerT>::computeBoxDiffsDescriptor(const cv::Mat &integralImg,
const std::vector<cv::KeyPoint> &keypoints,
cv::Mat &descriptors)
{
CV_DbgAssert(!integralImg.empty());
CV_DbgAssert(size_t(descriptors.rows) == keypoints.size());
@ -316,13 +370,13 @@ void BEBLID_Impl::computeBEBLID(const cv::Mat &integralImg,
#endif
{
// Get a pointer to the first element in the range
ABWLParams *wl;
WeakLearnerT *wl;
float responseFun;
int areaResponseFun, kpIdx;
size_t wlIdx;
int box1x1, box1y1, box1x2, box1y2, box2x1, box2y1, box2x2, box2y2, bit_idx, side;
uchar byte = 0;
std::vector<ABWLParams> imgWLParams(wl_params_.size());
std::vector<WeakLearnerT> imgWLParams(wl_params_.size());
uchar *d = &descriptors.at<uchar>(range.start, 0);
for (kpIdx = range.start; kpIdx < range.end; kpIdx++)
@ -397,7 +451,20 @@ void BEBLID_Impl::computeBEBLID(const cv::Mat &integralImg,
Ptr<BEBLID> BEBLID::create(float scale_factor, int n_bits)
{
return makePtr<BEBLID_Impl>(scale_factor, n_bits);
if (n_bits == BEBLID::SIZE_512_BITS)
{
#include "beblid.p512.hpp"
return makePtr<BEBLID_Impl<ABWLParams>>(scale_factor, beblid_wl_params_512);
}
else if(n_bits == BEBLID::SIZE_256_BITS)
{
#include "beblid.p256.hpp"
return makePtr<BEBLID_Impl<ABWLParams>>(scale_factor, beblid_wl_params_256);
}
else
{
CV_Error(Error::StsBadArg, "n_bits should be either BEBLID::SIZE_512_BITS or BEBLID::SIZE_256_BITS");
}
}
} // END NAMESPACE XFEATURES2D
} // END NAMESPACE CV

@ -12,7 +12,7 @@
// Pre-trained parameters of BEBLID-256 trained in Liberty data set with
// a million of patch pairs, 20% positives and 80% negatives
static const ABWLParams wl_params_256[] = {
static const ABWLParams beblid_wl_params_256_[] = {
{26, 20, 14, 16, 5, 16}, {17, 17, 15, 15, 2, 7}, {18, 16, 8, 13, 3, 18},
{19, 15, 13, 14, 3, 17}, {16, 16, 5, 15, 4, 10}, {25, 10, 16, 16, 6, 11},
{16, 15, 12, 15, 1, 12}, {18, 17, 14, 17, 1, 13}, {15, 14, 5, 21, 5, 6}, {14, 14, 11, 7, 4, 2},
@ -79,3 +79,5 @@ static const ABWLParams wl_params_256[] = {
{2, 14, 1, 9, 1, 1}, {6, 25, 6, 21, 1, 1}, {6, 2, 2, 1, 1, 1}, {30, 19, 29, 20, 1, 0},
{25, 21, 23, 20, 1, 0}, {16, 10, 16, 9, 1, 0}
};
static const std::vector<ABWLParams> beblid_wl_params_256(std::begin(beblid_wl_params_256_),
std::end(beblid_wl_params_256_));

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save