Skip to content

Fix aruco tutorials #3396

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 15 commits into from
Dec 23, 2022
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 10 additions & 2 deletions modules/aruco/samples/detect_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,8 +177,16 @@ int main(int argc, char *argv[]) {

// estimate board pose
int markersOfBoardDetected = 0;
if(ids.size() > 0)
markersOfBoardDetected = estimatePoseBoard(corners, ids, board, camMatrix, distCoeffs, rvec, tvec);
if(ids.size() > 0) {
// Get object and image points for the solvePnP function
cv::Mat objPoints, imgPoints;
board->matchImagePoints(corners, ids, objPoints, imgPoints);

// Find pose
cv::solvePnP(objPoints, imgPoints, camMatrix, distCoeffs, rvec, tvec);

markersOfBoardDetected = (int)objPoints.total() / 4;
}

double currentTime = ((double)getTickCount() - tick) / getTickFrequency();
totalTime += currentTime;
Expand Down
23 changes: 19 additions & 4 deletions modules/aruco/samples/detect_markers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,13 +156,28 @@ int main(int argc, char *argv[]) {

vector< int > ids;
vector< vector< Point2f > > corners, rejected;
vector< Vec3d > rvecs, tvecs;

// detect markers and estimate pose
detector.detectMarkers(image, corners, ids, rejected);
if(estimatePose && ids.size() > 0)
aruco::estimatePoseSingleMarkers(corners, markerLength, camMatrix, distCoeffs, rvecs,
tvecs);

int nMarkers = corners.size();
vector<Vec3d> rvecs(nMarkers), tvecs(nMarkers);

if(estimatePose && ids.size() > 0) {
// float markerLength = 0.05;

// Set coordinate system
cv::Mat objPoints(4, 1, CV_32FC3);
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);

// Calculate pose for each marker
for (int i = 0; i < nMarkers; i++) {
solvePnP(objPoints, corners.at(i), camMatrix, distCoeffs, rvecs.at(i), tvecs.at(i));
}
}

double currentTime = ((double)getTickCount() - tick) / getTickFrequency();
totalTime += currentTime;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,61 +27,57 @@ Thus, the pose can be calculated even in the presence of occlusions or partial v
- The obtained pose is usually more accurate since a higher amount of point correspondences (marker
corners) are employed.

The aruco module allows the use of Boards. The main class is the ```cv::aruco::Board``` class which defines the Board layout:

@code{.cpp}
class Board {
public:
std::vector<std::vector<cv::Point3f> > objPoints;
cv::Ptr<cv::aruco::Dictionary> dictionary;
std::vector<int> ids;
};
@endcode

A object of type ```Board``` has three parameters:
- The ```objPoints``` structure is the list of corner positions in the 3d Board reference system, i.e. its layout.
For each marker, its four corners are stored in the standard order, i.e. in clockwise order and starting
with the top left corner.
- The ```dictionary``` parameter indicates to which marker dictionary the Board markers belong to.
- Finally, the ```ids``` structure indicates the identifiers of each of the markers in ```objPoints``` respect to the specified ```dictionary```.


Board Detection
-----

A Board detection is similar to the standard marker detection. The only difference is in the pose estimation step.
In fact, to use marker boards, a standard marker detection should be done before estimating the Board pose.

The aruco module provides a specific function, ```estimatePoseBoard()```, to perform pose estimation for boards:
To perform pose estimation for boards, you should use ```cv::solvePnP``` function, as shown below:

@code{.cpp}
cv::Mat inputImage;
// camera parameters are read from somewhere
cv::Mat cameraMatrix, distCoeffs;
// You can read camera parameters from tutorial_camera_params.yml
readCameraParameters(filename, cameraMatrix, distCoeffs); // This function is located in detect_board.cpp
// assume we have a function to create the board object
cv::Ptr<cv::aruco::Board> board = cv::aruco::Board::create();
...
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f>> markerCorners;
cv::aruco::detectMarkers(inputImage, board.dictionary, markerCorners, markerIds);
// if at least one marker detected
if(markerIds.size() > 0) {
cv::Vec3d rvec, tvec;
int valid = cv::aruco::estimatePoseBoard(markerCorners, markerIds, board, cameraMatrix, distCoeffs, rvec, tvec);
}
cv::Mat inputImage;

// Camera parameters are read from somewhere
cv::Mat cameraMatrix, distCoeffs;

// You can read camera parameters from tutorial_camera_params.yml
readCameraParameters(filename, cameraMatrix, distCoeffs); // This function is implemented in aruco_samples_utility.hpp

// Assume we have a function to create the board object
cv::Ptr<cv::aruco::Board> board = cv::aruco::Board::create();

...

std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f>> markerCorners;

cv::aruco::DetectorParameters detectorParams = cv::aruco::DetectorParameters();
cv::aruco::ArucoDetector detector(board.dictionary, detectorParams);

detector.detectMarkers(inputImage, markerCorners, markerIds);

cv::Vec3d rvec, tvec;

// If at least one marker detected
if(markerIds.size() > 0) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if(!markerIds.empty())

// Get object and image points for the solvePnP function
cv::Mat objPoints, imgPoints;
board->matchImagePoints(markerCorners, markerIds, objPoints, imgPoints);

// Find pose
cv::solvePnP(objPoints, imgPoints, cameraMatrix, distCoeffs, rvec, tvec);
}

@endcode

The parameters of estimatePoseBoard are:
The parameters are:

- ```markerCorners``` and ```markerIds```: structures of detected markers from ```detectMarkers()``` function.
- ```objPoints```, ```imgPoints```: object and image points, matched with ```matchImagePoints```, which, in turn, takes as input ```markerCorners``` and ```markerIds```: structures of detected markers from ```detectMarkers()``` function).
- ```board```: the ```Board``` object that defines the board layout and its ids
- ```cameraMatrix``` and ```distCoeffs```: camera calibration parameters necessary for pose estimation.
- ```rvec``` and ```tvec```: estimated pose of the Board. If not empty then treated as initial guess.
- The function returns the total number of markers employed for estimating the board pose. Note that not all the
markers provided in ```markerCorners``` and ```markerIds``` should be used, since only the markers whose ids are
listed in the ```Board::ids``` structure are considered.
- The function returns the total number of markers employed for estimating the board pose.

The ```drawFrameAxes()``` function can be used to check the obtained pose. For instance:

Expand Down Expand Up @@ -135,16 +131,15 @@ in any unit, having in mind that the estimated pose for this board will be measu
- Finally, the dictionary of the markers is provided.

So, this board will be composed by 5x7=35 markers. The ids of each of the markers are assigned, by default, in ascending
order starting on 0, so they will be 0, 1, 2, ..., 34. This can be easily customized by accessing to the ids vector
through ```board.ids```, like in the ```Board``` parent class.
order starting on 0, so they will be 0, 1, 2, ..., 34.

After creating a Grid Board, we probably want to print it and use it. A function to generate the image
of a ```GridBoard``` is provided in ```cv::aruco::GridBoard::generateImage()```. For example:

@code{.cpp}
cv::Ptr<cv::aruco::GridBoard> board = cv::aruco::GridBoard::create(5, 7, 0.04, 0.01, dictionary);
cv::Mat boardImage;
board->draw( cv::Size(600, 500), boardImage, 10, 1 );
board->generateImage( cv::Size(600, 500), boardImage, 10, 1 );
@endcode

- The first parameter is the size of the output image in pixels. In this case 600x500 pixels. If this is not proportional
Expand Down Expand Up @@ -173,30 +168,42 @@ Finally, a full example of board detection:

cv::Mat cameraMatrix, distCoeffs;
// You can read camera parameters from tutorial_camera_params.yml
readCameraParameters(filename, cameraMatrix, distCoeffs); // This function is located in detect_board.cpp
readCameraParameters(filename, cameraMatrix, distCoeffs); // This function is implemented in aruco_samples_utility.hpp

cv::Ptr<cv::aruco::Dictionary> dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);
// To use tutorial sample, you need read custome dictionaty from tutorial_dict.yml
readDictionary(filename, dictionary); // This function is located in detect_board.cpp
cv::aruco::Dictionary dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);

// To use tutorial sample, you need read custom dictionaty from tutorial_dict.yml
readDictionary(filename, dictionary); // This function is implemented in opencv/modules/objdetect/src/aruco/aruco_dictionary.cpp
cv::Ptr<cv::aruco::GridBoard> board = cv::aruco::GridBoard::create(5, 7, 0.04, 0.01, dictionary);

cv::aruco::DetectorParameters detectorParams = cv::aruco::DetectorParameters();
cv::aruco::ArucoDetector detector(dictionary, detectorParams);

while (inputVideo.grab()) {
cv::Mat image, imageCopy;
inputVideo.retrieve(image);
image.copyTo(imageCopy);

std::vector<int> ids;
std::vector<std::vector<cv::Point2f> > corners;
cv::aruco::detectMarkers(image, dictionary, corners, ids);

// if at least one marker detected
// Detect markers
detector.detectMarkers(image, corners, ids);

// If at least one marker detected
if (ids.size() > 0) {
cv::aruco::drawDetectedMarkers(imageCopy, corners, ids);

cv::Vec3d rvec, tvec;
int valid = estimatePoseBoard(corners, ids, board, cameraMatrix, distCoeffs, rvec, tvec);

// if at least one board marker detected
// Get object and image points for the solvePnP function
cv::Mat objPoints, imgPoints;
board->matchImagePoints(corners, ids, objPoints, imgPoints);

// Find pose
cv::solvePnP(objPoints, imgPoints, cameraMatrix, distCoeffs, rvec, tvec);

// If at least one board marker detected
if(valid > 0)
cv::drawFrameAxes(imageCopy, cameraMatrix, distCoeffs, rvec, tvec, 0.1);
}
Expand Down Expand Up @@ -269,13 +276,17 @@ internal bits are not analyzed at all and only the corner distances are evaluate
This is an example of using the ```refineDetectedMarkers()``` function:

@code{.cpp}
cv::Ptr<cv::aruco::Dictionary> dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);

cv::aruco::Dictionary dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);
cv::Ptr<cv::aruco::GridBoard> board = cv::aruco::GridBoard::create(5, 7, 0.04, 0.01, dictionary);
cv::aruco::DetectorParameters detectorParams = cv::aruco::DetectorParameters();
cv::aruco::ArucoDetector detector(dictionary, detectorParams);

std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f>> markerCorners, rejectedCandidates;
cv::aruco::detectMarkers(inputImage, dictionary, markerCorners, markerIds, cv::aruco::DetectorParameters(), rejectedCandidates);
detector.detectMarkers(inputImage, markerCorners, markerIds, rejectedCandidates);

cv::aruco::refineDetectedMarkersinputImage, board, markerCorners, markerIds, rejectedCandidates);
detector.refineDetectedMarkers(inputImage, board, markerCorners, markerIds, rejectedCandidates);
// After calling this function, if any new marker has been detected it will be removed from rejectedCandidates and included
// at the end of markerCorners and markerIds
@endcode
Expand Down
Loading