OpenCV ArUco marker tracker class derived from CVTracked.
More...
#include <CVTrackedAruco.h>
|
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. More...
|
|
static void | drawArucoMarker (int dictionaryId, int minMarkerId, int maxMarkerId, int markerSizePX=200) |
| Helper function to draw and save an aruco marker set. More...
|
|
static cv::Matx44f | createGLMatrix (const CVMat &tVec, const CVMat &rVec) |
| Create an OpenGL 4x4 matrix from an OpenCV translation & rotation vector. More...
|
|
static void | createRvecTvec (const CVMatx44f &glMat, CVMat &tVec, CVMat &rVec) |
| Creates the OpenCV rvec & tvec vectors from an column major OpenGL 4x4 matrix. More...
|
|
static CVMatx44f | calcObjectMatrix (const CVMatx44f &cameraObjectMat, const CVMatx44f &objectViewMat) |
|
static CVVec3f | averageVector (vector< CVVec3f > vectors, vector< float > weights) |
|
static SLQuat4f | averageQuaternion (vector< SLQuat4f > quaternions, vector< float > weights) |
|
static void | resetTimes () |
| Resets all static variables. More...
|
|
OpenCV ArUco marker tracker class derived from CVTracked.
Tracking class for ArUco markers tracking. See the official OpenCV docs on ArUco markers: http://docs.opencv.org/3.1.0/d5/dae/tutorial_aruco_detection.html The aruco marker used in the SLProject are printed in a PDF stored in the data/Calibration folder. They use the dictionary 0 and where generated with the functions CVTrackedAruco::drawArucoMarkerBoard and CVTrackedAruco::drawArucoMarker.
Definition at line 130 of file CVTrackedAruco.h.
◆ CVTrackedAruco()
CVTrackedAruco::CVTrackedAruco |
( |
int |
arucoID, |
|
|
string |
calibIniPath |
|
) |
| |
|
explicit |
Definition at line 23 of file CVTrackedAruco.cpp.
31 "CVTrackedAruco::track: Failed to load Aruco parameters.",
bool loadFromFile(string calibIniPath)
CVArucoParams _params
Aruco parameters.
int _arucoID
Aruco Marker ID for this node.
void exitMsg(const char *tag, const char *msg, const int line, const char *file)
Terminates the application with a message. No leak checking.
◆ drawArucoMarker()
void CVTrackedAruco::drawArucoMarker |
( |
int |
dictionaryId, |
|
|
int |
minMarkerId, |
|
|
int |
maxMarkerId, |
|
|
int |
markerSizePX = 200 |
|
) |
| |
|
static |
Helper function to draw and save an aruco marker set.
Definition at line 249 of file CVTrackedAruco.cpp.
254 assert(dictionaryId > 0);
255 assert(minMarkerId > 0);
256 assert(minMarkerId < maxMarkerId);
258 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
259 cv::Ptr<cv::aruco::Dictionary> dict = getPredefinedDictionary(cv::aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
260 if (maxMarkerId > dict->bytesList.rows)
261 maxMarkerId = dict->bytesList.rows;
265 for (
int i = minMarkerId; i < maxMarkerId; ++i)
267 cv::aruco::drawMarker(dict, i, markerSizePX, markerImg, 1);
268 # ifndef __EMSCRIPTEN__
277 cv::aruco::Dictionary dict = getPredefinedDictionary(cv::aruco::PredefinedDictionaryType(dictionaryId));
278 if (maxMarkerId > dict.bytesList.rows)
279 maxMarkerId = dict.bytesList.rows;
283 for (
int i = minMarkerId; i < maxMarkerId; ++i)
285 cv::aruco::generateImageMarker(dict,
290 # ifndef __EMSCRIPTEN__
string formatString(string fmt_str,...)
Returns a formatted string as sprintf.
◆ drawArucoMarkerBoard()
void CVTrackedAruco::drawArucoMarkerBoard |
( |
int |
dictionaryId, |
|
|
int |
numMarkersX, |
|
|
int |
numMarkersY, |
|
|
float |
markerEdgeM, |
|
|
float |
markerSepaM, |
|
|
const string & |
imgName, |
|
|
float |
dpi = 254.0f , |
|
|
bool |
showImage = false |
|
) |
| |
|
static |
Helper function to draw and save an aruco marker board image.
CVTrackedAruco::drawArucoMarkerBoard draws and saves an aruco board into an image.
- Parameters
-
dictionaryId | integer id of the dictionary |
numMarkersX | NO. of markers in x-direction |
numMarkersY | NO. of markers in y-direction |
markerEdgeM | Length of one marker in meters |
markerSepaM | Separation between markers in meters |
imgName | Image filename inklusive format extension |
dpi | Dots per inch (default 256) |
showImage | Shows image in window (default false) |
Definition at line 182 of file CVTrackedAruco.cpp.
191 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
192 cv::Ptr<cv::aruco::Dictionary> dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
193 cv::Ptr<cv::aruco::GridBoard> board = cv::aruco::GridBoard::create(numMarkersX,
199 imageSize.width = (int)((markerEdgeM + markerSepaM) * 100.0f / 2.54f *
dpi * (float)numMarkersX);
200 imageSize.height = (int)((markerEdgeM + markerSepaM) * 100.0f / 2.54f *
dpi * (float)numMarkersY);
202 imageSize.width -= (imageSize.width % 4);
203 imageSize.height -= (imageSize.height % 4);
207 board->draw(imageSize, boardImage, 0, 1);
211 imshow(
"board", boardImage);
215 cv::aruco::Dictionary dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::PredefinedDictionaryType(dictionaryId));
216 cv::aruco::GridBoard board = cv::aruco::GridBoard(cv::Size(numMarkersX, numMarkersY),
222 imageSize.width = (int)((markerEdgeM + markerSepaM) * 100.0f / 2.54f *
dpi * (float)numMarkersX);
223 imageSize.height = (int)((markerEdgeM + markerSepaM) * 100.0f / 2.54f *
dpi * (float)numMarkersY);
225 imageSize.width -= (imageSize.width % 4);
226 imageSize.height -= (imageSize.height % 4);
230 cv::aruco::drawPlanarBoard(&board,
235 # ifndef __EMSCRIPTEN__
238 imshow(
"board", boardImage);
244 #ifndef __EMSCRIPTEN__
245 imwrite(imgName, boardImage);
static SLint dpi
Dot per inch resolution of screen.
◆ params()
◆ track()
Tracks the all Aruco markers in the given image for the first sceneview.
Implements CVTracked.
Reimplemented in CVTrackedArucoCube.
Definition at line 37 of file CVTrackedAruco.cpp.
41 if (!
trackAll(imageGray, imageBgr, calib))
49 for (
size_t i = 0; i <
arucoIDs.size(); ++i)
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
CVMatx44f _objectViewMat
view transformation matrix
◆ trackAll()
Definition at line 62 of file CVTrackedAruco.cpp.
69 assert(!imageGray.empty() &&
"ImageGray is empty");
70 assert(!imageBgr.empty() &&
"ImageBGR is empty");
71 assert(!calib->
cameraMat().empty() &&
"Calibration is empty");
73 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
77 "CVTrackedAruco::track: Aruco paramters are empty.",
88 CVMat croppedImageGray = roi.empty() ? imageGray : imageGray(roi);
96 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 7
97 cv::aruco::detectMarkers(croppedImageGray,
105 detector.detectMarkers(croppedImageGray,
111 for (
auto& corner : corners)
113 for (
auto& j : corner)
125 cv::aruco::drawDetectedMarkers(imageBgr,
128 cv::Scalar(0, 0, 255));
138 cv::aruco::estimatePoseSingleMarkers(corners,
148 for (
size_t i = 0; i <
arucoIDs.size(); ++i)
155 #if CV_MAJOR_VERSION < 4 || CV_MINOR_VERSION < 6
157 cv::drawFrameAxes(imageBgr,
vector< cv::Point3d > CVVPoint3d
vector< vector< cv::Point2f > > CVVVPoint2f
#define PROFILE_FUNCTION()
cv::Ptr< cv::aruco::DetectorParameters > arucoParams
detector parameter structure for aruco detection function
float edgeLength
marker edge length
cv::Ptr< cv::aruco::Dictionary > dictionary
predefined dictionary
const CVMat & cameraMat() const
const CVMat & distortion() const
static AvgFloat detectTimesMS
Averaged time for video feature detection & description in ms.
bool _drawDetection
Flag if detection should be drawn into image.
static cv::Matx44f createGLMatrix(const CVMat &tVec, const CVMat &rVec)
Create an OpenGL 4x4 matrix from an OpenCV translation & rotation vector.
HighResTimer _timer
High resolution timer.
static AvgFloat poseTimesMS
Averaged time for video feature pose estimation in ms.
float elapsedTimeInMilliSec()
void set(T value)
Sets the current value in the value array and builds the average.
void warnMsg(const char *tag, const char *msg, const int line, const char *file)
Platform independent warn message output.
◆ _arucoID
int CVTrackedAruco::_arucoID |
|
private |
◆ _calibIniPath
string CVTrackedAruco::_calibIniPath |
|
private |
◆ _params
◆ arucoIDs
vector<int> CVTrackedAruco::arucoIDs |
|
protected |
◆ objectViewMats
The documentation for this class was generated from the following files: