Test ArUco detection.
Test ArUco detection.
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_APRILTAG)
#include <catch_amalgamated.hpp>
#include <iostream>
#include <visp3/core/vpImageTools.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/detection/vpDetectorAprilTag.h>
#if (VISP_HAVE_OPENCV_VERSION >= 0x040700)
#include <opencv2/objdetect/aruco_detector.hpp>
#include <opencv2/calib3d.hpp>
using namespace cv;
#endif
#ifdef ENABLE_VISP_NAMESPACE
#endif
static bool g_debug_print = false;
bool opt_no_display = false;
TEST_CASE("ArUco detection test", "[aruco_detection_test]")
{
std::map<vpDetectorAprilTag::vpAprilTagFamily, int> apriltagMap = {
};
const int nb_tests = 50;
SECTION("Constructor")
{
for (const auto &kv : apriltagMap) {
for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
bool detect = detector.
detect(tag_img_big);
CHECK(detect == true);
if (detect) {
bool found_id = false;
std::size_t tag_id_pos = message.find("id: ");
if (tag_id_pos != std::string::npos) {
int tag_id = atoi(message.substr(tag_id_pos + 4).c_str());
if (g_debug_print) {
WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
}
if (tag_id == id) {
found_id = true;
}
}
}
CHECK(found_id == true);
found_id = false;
std::vector<int> tagsId = detector.
getTagsId();
for (auto tag_id : tagsId) {
if (g_debug_print) {
WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
}
if (tag_id == id) {
found_id = true;
break;
}
}
CHECK(found_id == true);
}
}
}
}
SECTION("Copy constructor")
{
for (const auto &kv : apriltagMap) {
for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
bool detect = detector.
detect(tag_img_big);
CHECK(detect == true);
if (detect) {
std::vector<int> tagsId = detector.
getTagsId();
CHECK(tagsId.size() == tagsDecisionMargin.size());
CHECK(tagsId.size() == tagsHammingDistance.size());
bool found_id = false;
for (auto tag_id : tagsId) {
if (g_debug_print) {
WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
}
if (tag_id == id) {
found_id = true;
break;
}
}
CHECK(found_id == true);
}
}
}
}
SECTION("Getter/Setter")
{
for (const auto &kv : apriltagMap) {
int hamming_dist_ref = 0;
float decision_margin = 50.0f;
for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
bool detect = detector.
detect(tag_img_big);
CHECK(detect == true);
if (detect) {
std::vector<int> tagsId = detector.
getTagsId();
CHECK(tagsId.size() == tagsDecisionMargin.size());
CHECK(tagsId.size() == tagsHammingDistance.size());
bool found_id = false;
for (auto tag_id : tagsId) {
if (g_debug_print) {
WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
}
if (tag_id == id) {
found_id = true;
break;
}
}
CHECK(found_id == true);
}
}
}
}
}
#if (VISP_HAVE_OPENCV_VERSION >= 0x040800)
TEST_CASE("ArUco pose computation test", "[aruco_detection_test]")
{
std::map<vpDetectorAprilTag::vpAprilTagFamily, aruco::PredefinedDictionaryType> apriltagMap = {
};
const float markerLength = 0.05f;
std::vector<vpHomogeneousMatrix> cMo_vec;
aruco::DetectorParameters detectorParams;
Matx33d camMatrix = Matx33d::eye();
camMatrix(0, 0) =
cam.get_px(); camMatrix(0, 2) =
cam.get_u0();
camMatrix(1, 1) =
cam.get_py(); camMatrix(1, 2) =
cam.get_v0();
Matx41d distCoeffs = Matx41d::zeros();
Mat image;
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);
for (const auto &kv : apriltagMap) {
aruco::ArucoDetector cv_detector(aruco::getPredefinedDictionary(kv.second), detectorParams);
std::vector<int> ids;
std::vector<std::vector<Point2f> > corners, rejected;
const int tag_id_ref = 3;
detector.getTagImage(tag_img, tag_id_ref);
bool detect = detector.detect(tag_img_big, markerLength, cam, cMo_vec);
CHECK(detect == true);
if (detect) {
std::vector<int> tagsId = detector.getTagsId();
std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
CHECK(tagsId.size() == tagsDecisionMargin.size());
CHECK(tagsId.size() == tagsHammingDistance.size());
CHECK(tagsId.size() == detector.getNbObjects());
CHECK(tagsId.size() == cMo_vec.size());
bool found_id = false;
for (
size_t idx = 0;
idx < tagsId.size();
idx++) {
int tag_id = tagsId[
idx];
if (g_debug_print) {
WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << tag_id_ref);
}
if (tag_id == tag_id_ref) {
found_id = true;
break;
}
}
CHECK(found_id == true);
if (found_id) {
cv_detector.detectMarkers(image, corners, ids, rejected);
CHECK(!ids.empty());
size_t idx_tag_id_ref = 0;
bool found_tag_id_ref = false;
for (
size_t i = 0;
i < ids.size();
i++) {
if (ids[i] == tag_id_ref) {
found_tag_id_ref = true;
}
}
CHECK(found_tag_id_ref);
if (found_tag_id_ref) {
Matx31d rvec, tvec;
solvePnP(objPoints, corners.at(idx_tag_id_ref), camMatrix, distCoeffs, rvec, tvec);
if (g_debug_print) {
WARN("rvec: " << rvec(0) << " " << rvec(1) << " " << rvec(2));
WARN("tvec: " << tvec(0) << " " << tvec(1) << " " << tvec(2));
WARN("cro: " << cro[0] << " " << cro[1] << " " << cro[2]);
WARN("cto: " << cMo[0][3] << " " << cMo[1][3] << " " << cMo[2][3]);
}
CHECK_THAT(tvec(0), Catch::Matchers::WithinAbs(cMo[0][3], 1e-2));
CHECK_THAT(tvec(1), Catch::Matchers::WithinAbs(cMo[1][3], 1e-2));
CHECK_THAT(tvec(2), Catch::Matchers::WithinAbs(cMo[2][3], 1e-2));
double rvec_magn = std::sqrt(rvec(0)*rvec(0) + rvec(1)*rvec(1) + rvec(2)*rvec(2));
double cro_magn = std::sqrt(cro[0]*cro[0] + cro[1]*cro[1] + cro[2]*cro[2]);
CHECK_THAT(rvec_magn, Catch::Matchers::WithinAbs(cro_magn, 1e-2));
}
}
}
}
}
#endif
int main(int argc, const char *argv[])
{
Catch::Session session;
using namespace Catch::Clara;
auto cli = session.cli()
| Catch::Clara::Opt(g_debug_print)["--debug-print"]("Force the printing of some debug information.")
| Catch::Clara::Opt(opt_no_display)["--no-display"]("Disable display");
session.cli(cli);
int returnCode = session.applyCommandLine(argc, argv);
if (returnCode != 0) {
return returnCode;
}
int numFailed = session.run();
return numFailed;
}
#else
int main() { return EXIT_SUCCESS; }
#endif
Generic class defining intrinsic camera parameters.
std::vector< float > getTagsDecisionMargin() const
void setAprilTagHammingDistanceThreshold(int hammingDistanceThreshold)
bool detect(const vpImage< unsigned char > &I) VP_OVERRIDE
std::vector< int > getTagsHammingDistance() const
void setAprilTagDecisionMarginThreshold(float decisionMarginThreshold)
std::vector< int > getTagsId() const
bool getTagImage(vpImage< unsigned char > &I, int id)
float getAprilTagDecisionMarginThreshold() const
int getAprilTagHammingDistanceThreshold() const
std::vector< std::string > & getMessage()
size_t getNbObjects() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Definition of the vpImage class member functions.
unsigned int getWidth() const
unsigned int getHeight() const
Implementation of a rotation vector as axis-angle minimal representation.