39#include <visp3/core/vpConfig.h>
41#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_APRILTAG)
43#include <catch_amalgamated.hpp>
46#include <visp3/core/vpImageTools.h>
47#include <visp3/core/vpImageConvert.h>
48#include <visp3/detection/vpDetectorAprilTag.h>
50#if (VISP_HAVE_OPENCV_VERSION >= 0x040700)
51#include <opencv2/objdetect/aruco_detector.hpp>
52#include <opencv2/calib3d.hpp>
56#ifdef ENABLE_VISP_NAMESPACE
61static bool g_debug_print =
false;
63bool opt_no_display =
false;
65TEST_CASE(
"ArUco detection test",
"[aruco_detection_test]")
67 std::map<vpDetectorAprilTag::vpAprilTagFamily, int> apriltagMap = {
91 const int nb_tests = 50;
92 SECTION(
"Constructor")
94 for (
const auto &kv : apriltagMap) {
97 for (
int id = 0;
id < kv.second;
id += kv.second/nb_tests) {
99 detector.getTagImage(tag_img,
id);
104 bool detect = detector.detect(tag_img_big);
105 CHECK(detect ==
true);
107 bool found_id =
false;
109 for (
size_t i = 0;
i < detector.getNbObjects();
i++) {
110 std::string message = detector.getMessage(i);
111 std::size_t tag_id_pos = message.find(
"id: ");
113 if (tag_id_pos != std::string::npos) {
114 int tag_id = atoi(message.substr(tag_id_pos + 4).c_str());
116 WARN(
"tag_dict=" << kv.first <<
" ; tag_id=" << tag_id <<
" ; tag_ref=" <<
id);
123 CHECK(found_id ==
true);
127 std::vector<int> tagsId = detector.getTagsId();
128 for (
auto tag_id : tagsId) {
130 WARN(
"tag_dict=" << kv.first <<
" ; tag_id=" << tag_id <<
" ; tag_ref=" <<
id);
137 CHECK(found_id ==
true);
143 SECTION(
"Copy constructor")
145 for (
const auto &kv : apriltagMap) {
148 for (
int id = 0;
id < kv.second;
id += kv.second/nb_tests) {
150 detector.getTagImage(tag_img,
id);
155 bool detect = detector.detect(tag_img_big);
156 CHECK(detect ==
true);
158 std::vector<int> tagsId = detector.getTagsId();
159 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
160 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
161 CHECK(tagsId.size() == tagsDecisionMargin.size());
162 CHECK(tagsId.size() == tagsHammingDistance.size());
163 CHECK(tagsId.size() == detector.getNbObjects());
166 bool found_id =
false;
167 for (
auto tag_id : tagsId) {
169 WARN(
"tag_dict=" << kv.first <<
" ; tag_id=" << tag_id <<
" ; tag_ref=" <<
id);
176 CHECK(found_id ==
true);
182 SECTION(
"Getter/Setter")
184 for (
const auto &kv : apriltagMap) {
186 int hamming_dist_ref = 0;
187 float decision_margin = 50.0f;
188 detector.setAprilTagHammingDistanceThreshold(hamming_dist_ref);
189 detector.setAprilTagDecisionMarginThreshold(decision_margin);
190 CHECK(detector.getAprilTagHammingDistanceThreshold() == hamming_dist_ref);
191 CHECK(detector.getAprilTagDecisionMarginThreshold() == decision_margin);
193 for (
int id = 0;
id < kv.second;
id += kv.second/nb_tests) {
195 detector.getTagImage(tag_img,
id);
200 bool detect = detector.detect(tag_img_big);
201 CHECK(detect ==
true);
203 std::vector<int> tagsId = detector.getTagsId();
204 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
205 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
206 CHECK(tagsId.size() == tagsDecisionMargin.size());
207 CHECK(tagsId.size() == tagsHammingDistance.size());
208 CHECK(tagsId.size() == detector.getNbObjects());
211 bool found_id =
false;
212 for (
auto tag_id : tagsId) {
214 WARN(
"tag_dict=" << kv.first <<
" ; tag_id=" << tag_id <<
" ; tag_ref=" <<
id);
221 CHECK(found_id ==
true);
228#if (VISP_HAVE_OPENCV_VERSION >= 0x040800)
229TEST_CASE(
"ArUco pose computation test",
"[aruco_detection_test]")
231 std::map<vpDetectorAprilTag::vpAprilTagFamily, aruco::PredefinedDictionaryType> apriltagMap = {
239 const float markerLength = 0.05f;
243 std::vector<vpHomogeneousMatrix> cMo_vec;
246 aruco::DetectorParameters detectorParams;
247 Matx33d camMatrix = Matx33d::eye();
248 camMatrix(0, 0) =
cam.get_px(); camMatrix(0, 2) =
cam.get_u0();
249 camMatrix(1, 1) =
cam.get_py(); camMatrix(1, 2) =
cam.get_v0();
250 Matx41d distCoeffs = Matx41d::zeros();
253 Mat objPoints(4, 1, CV_32FC3);
254 objPoints.ptr<Vec3f>(0)[0] = Vec3f(-markerLength/2.f, markerLength/2.f, 0);
255 objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength/2.f, markerLength/2.f, 0);
256 objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength/2.f, -markerLength/2.f, 0);
257 objPoints.ptr<Vec3f>(0)[3] = Vec3f(-markerLength/2.f, -markerLength/2.f, 0);
259 for (
const auto &kv : apriltagMap) {
264 aruco::ArucoDetector cv_detector(aruco::getPredefinedDictionary(kv.second), detectorParams);
265 std::vector<int> ids;
266 std::vector<std::vector<Point2f> > corners, rejected;
268 const int tag_id_ref = 3;
270 detector.getTagImage(tag_img, tag_id_ref);
276 bool detect = detector.detect(tag_img_big, markerLength, cam, cMo_vec);
277 CHECK(detect ==
true);
279 std::vector<int> tagsId = detector.getTagsId();
280 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
281 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
282 CHECK(tagsId.size() == tagsDecisionMargin.size());
283 CHECK(tagsId.size() == tagsHammingDistance.size());
284 CHECK(tagsId.size() == detector.getNbObjects());
285 CHECK(tagsId.size() == cMo_vec.size());
289 bool found_id =
false;
290 for (
size_t idx = 0;
idx < tagsId.size();
idx++) {
291 int tag_id = tagsId[
idx];
293 WARN(
"tag_dict=" << kv.first <<
" ; tag_id=" << tag_id <<
" ; tag_ref=" << tag_id_ref);
295 if (tag_id == tag_id_ref) {
302 CHECK(found_id ==
true);
305 cv_detector.detectMarkers(image, corners, ids, rejected);
308 size_t idx_tag_id_ref = 0;
309 bool found_tag_id_ref =
false;
310 for (
size_t i = 0;
i < ids.size();
i++) {
311 if (ids[i] == tag_id_ref) {
312 found_tag_id_ref =
true;
317 CHECK(found_tag_id_ref);
318 if (found_tag_id_ref) {
320 solvePnP(objPoints, corners.at(idx_tag_id_ref), camMatrix, distCoeffs, rvec, tvec);
323 WARN(
"rvec: " << rvec(0) <<
" " << rvec(1) <<
" " << rvec(2));
324 WARN(
"tvec: " << tvec(0) <<
" " << tvec(1) <<
" " << tvec(2));
326 WARN(
"cro: " << cro[0] <<
" " << cro[1] <<
" " << cro[2]);
327 WARN(
"cto: " << cMo[0][3] <<
" " << cMo[1][3] <<
" " << cMo[2][3]);
330 CHECK_THAT(tvec(0), Catch::Matchers::WithinAbs(cMo[0][3], 1e-2));
331 CHECK_THAT(tvec(1), Catch::Matchers::WithinAbs(cMo[1][3], 1e-2));
332 CHECK_THAT(tvec(2), Catch::Matchers::WithinAbs(cMo[2][3], 1e-2));
334 double rvec_magn = std::sqrt(rvec(0)*rvec(0) + rvec(1)*rvec(1) + rvec(2)*rvec(2));
335 double cro_magn = std::sqrt(cro[0]*cro[0] + cro[1]*cro[1] + cro[2]*cro[2]);
336 CHECK_THAT(rvec_magn, Catch::Matchers::WithinAbs(cro_magn, 1e-2));
344int main(
int argc,
const char *argv[])
346 Catch::Session session;
348 using namespace Catch::Clara;
349 auto cli = session.cli()
350 | Catch::Clara::Opt(g_debug_print)[
"--debug-print"](
"Force the printing of some debug information.")
351 | Catch::Clara::Opt(opt_no_display)[
"--no-display"](
"Disable display");
354 int returnCode = session.applyCommandLine(argc, argv);
355 if (returnCode != 0) {
359 int numFailed = session.run();
364int main() {
return EXIT_SUCCESS; }
Generic class defining intrinsic camera parameters.
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.