10 #ifndef CVTrackedAruco_H
11 #define CVTrackedAruco_H
25 #include <opencv2/aruco.hpp>
34 filename(
"aruco_detector_params.yml")
36 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
37 arucoParams = cv::aruco::DetectorParameters::create();
45 string path = calibIniPath +
filename;
48 CVFileStorage fs(paramString, CVFileStorage::READ | CVFileStorage::MEMORY);
51 cout <<
"Could not find parameter file for ArUco tracking!" << endl;
52 cout <<
"Tried " << path << endl;
56 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
57 fs[
"adaptiveThreshWinSizeMin"] >>
arucoParams->adaptiveThreshWinSizeMin;
58 fs[
"adaptiveThreshWinSizeMax"] >>
arucoParams->adaptiveThreshWinSizeMax;
59 fs[
"adaptiveThreshWinSizeStep"] >>
arucoParams->adaptiveThreshWinSizeStep;
60 fs[
"adaptiveThreshConstant"] >>
arucoParams->adaptiveThreshConstant;
61 fs[
"minMarkerPerimeterRate"] >>
arucoParams->minMarkerPerimeterRate;
62 fs[
"maxMarkerPerimeterRate"] >>
arucoParams->maxMarkerPerimeterRate;
63 fs[
"polygonalApproxAccuracyRate"] >>
arucoParams->polygonalApproxAccuracyRate;
64 fs[
"minCornerDistanceRate"] >>
arucoParams->minCornerDistanceRate;
65 fs[
"minDistanceToBorder"] >>
arucoParams->minDistanceToBorder;
66 fs[
"cornerRefinementMethod"] >>
arucoParams->cornerRefinementMethod;
67 fs[
"cornerRefinementWinSize"] >>
arucoParams->cornerRefinementWinSize;
68 fs[
"cornerRefinementMaxIterations"] >>
arucoParams->cornerRefinementMaxIterations;
69 fs[
"cornerRefinementMinAccuracy"] >>
arucoParams->cornerRefinementMinAccuracy;
70 fs[
"markerBorderBits"] >>
arucoParams->markerBorderBits;
71 fs[
"perspectiveRemovePixelPerCell"] >>
arucoParams->perspectiveRemovePixelPerCell;
72 fs[
"perspectiveRemoveIgnoredMarginPerCell"] >>
arucoParams->perspectiveRemoveIgnoredMarginPerCell;
73 fs[
"maxErroneousBitsInBorderRate"] >>
arucoParams->maxErroneousBitsInBorderRate;
77 fs[
"adaptiveThreshWinSizeMin"] >>
arucoParams.adaptiveThreshWinSizeMin;
78 fs[
"adaptiveThreshWinSizeMax"] >>
arucoParams.adaptiveThreshWinSizeMax;
79 fs[
"adaptiveThreshWinSizeStep"] >>
arucoParams.adaptiveThreshWinSizeStep;
80 fs[
"adaptiveThreshConstant"] >>
arucoParams.adaptiveThreshConstant;
81 fs[
"minMarkerPerimeterRate"] >>
arucoParams.minMarkerPerimeterRate;
82 fs[
"maxMarkerPerimeterRate"] >>
arucoParams.maxMarkerPerimeterRate;
83 fs[
"polygonalApproxAccuracyRate"] >>
arucoParams.polygonalApproxAccuracyRate;
84 fs[
"minCornerDistanceRate"] >>
arucoParams.minCornerDistanceRate;
85 fs[
"minDistanceToBorder"] >>
arucoParams.minDistanceToBorder;
86 fs[
"cornerRefinementMethod"] >>
arucoParams.cornerRefinementMethod;
87 fs[
"cornerRefinementWinSize"] >>
arucoParams.cornerRefinementWinSize;
88 fs[
"cornerRefinementMaxIterations"] >>
arucoParams.cornerRefinementMaxIterations;
89 fs[
"cornerRefinementMinAccuracy"] >>
arucoParams.cornerRefinementMinAccuracy;
90 fs[
"markerBorderBits"] >>
arucoParams.markerBorderBits;
91 fs[
"perspectiveRemovePixelPerCell"] >>
arucoParams.perspectiveRemovePixelPerCell;
92 fs[
"perspectiveRemoveIgnoredMarginPerCell"] >>
arucoParams.perspectiveRemoveIgnoredMarginPerCell;
93 fs[
"maxErroneousBitsInBorderRate"] >>
arucoParams.maxErroneousBitsInBorderRate;
98 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
107 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
146 float markerEdgeLengthM,
148 const string& imgName,
150 bool showImage =
false);
156 int markerSizePX = 200);
static SLint dpi
Dot per inch resolution of screen.
cv::FileStorage CVFileStorage
vector< cv::Matx44f > CVVMatx44f
ArUco Parameters loaded from configuration file.
int arucoDictionaryId
id of aruco dictionary
bool loadFromFile(string calibIniPath)
cv::Ptr< cv::aruco::DetectorParameters > arucoParams
detector parameter structure for aruco detection function
string arucoDetectorParams
todo: put in one file
float edgeLength
marker edge length
string filename
parameter filename
cv::Ptr< cv::aruco::Dictionary > dictionary
predefined dictionary
Live video camera calibration class with OpenCV an OpenCV calibration.
OpenCV ArUco marker tracker class derived from CVTracked.
const CVArucoParams & params() const
bool track(CVMat imageGray, CVMat imageBgr, CVCalibration *calib)
Tracks the all Aruco markers in the given image for the first sceneview.
static void drawArucoMarkerBoard(int dictionaryId, int numMarkersX, int numMarkersY, float markerEdgeLengthM, float markerSepaM, const string &imgName, float dpi=254.0f, bool showImage=false)
Helper function to draw and save an aruco marker board image.
CVArucoParams _params
Aruco parameters.
int _arucoID
Aruco Marker ID for this node.
static void drawArucoMarker(int dictionaryId, int minMarkerId, int maxMarkerId, int markerSizePX=200)
Helper function to draw and save an aruco marker set.
CVTrackedAruco(int arucoID, string calibIniPath)
bool trackAll(CVMat imageGray, CVMat imageBgr, CVCalibration *calib, CVRect roi=CVRect(0, 0, 0, 0))
vector< int > arucoIDs
detected Aruco marker IDs
CVVMatx44f objectViewMats
object view matrices for all found markers
CVTracked is the pure virtual base class for tracking features in video.
std::string readIntoString(std::string path, SLIOStreamKind kind)
Reads an entire file into a string.