Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
tutorial-apriltag-detector-live-T265-realsense.cpp
1
2#include <visp3/core/vpConfig.h>
3#ifdef VISP_HAVE_MODULE_SENSOR
4#include <visp3/sensor/vpRealSense2.h>
5#endif
7#include <visp3/detection/vpDetectorAprilTag.h>
9#include <visp3/core/vpImageConvert.h>
10#include <visp3/core/vpImageTools.h>
11#include <visp3/core/vpMeterPixelConversion.h>
12#include <visp3/core/vpPixelMeterConversion.h>
13#include <visp3/gui/vpDisplayFactory.h>
14#include <visp3/vision/vpPose.h>
15
16void usage(const char **argv, int error);
17
18void usage(const char **argv, int error)
19{
20 std::cout << "Synopsis" << std::endl
21 << " " << argv[0]
22 << " [--tag-size <size>]"
23 << " [--tag-family <family>]"
24 << " [--tag-decision-margin-threshold <threshold>]"
25 << " [--tag-hamming-distance-threshold <threshold>]"
26 << " [--tag-quad-decimate <factor>]"
27 << " [--tag-n-threads <number>]"
28 << " [--tag-z-aligned]"
29 << " [--tag-pose-method <method>]"
30#if defined(VISP_HAVE_DISPLAY)
31 << " [--display-tag]"
32 << " [--display-off]"
33 << " [--color <id>]"
34 << " [--opt_thickness <opt_thickness>"
35#endif
36 << " [--verbose, -v]"
37 << " [--help, -h]" << std::endl
38 << std::endl;
39 std::cout << "Description" << std::endl
40 << " Compute the pose of an Apriltag in images acquired with a realsense T265 camera." << std::endl
41 << std::endl
42 << " --tag-size <size>" << std::endl
43 << " Apriltag size in [m]." << std::endl
44 << " Default: 0.03" << std::endl
45 << std::endl
46 << " --tag-family <family>" << std::endl
47 << " Apriltag family. Supported values are:" << std::endl
48 << " 0: TAG_36h11" << std::endl
49 << " 1: TAG_36h10 (DEPRECATED)" << std::endl
50 << " 2: TAG_36ARTOOLKIT (DEPRECATED)" << std::endl
51 << " 3: TAG_25h9" << std::endl
52 << " 4: TAG_25h7 (DEPRECATED)" << std::endl
53 << " 5: TAG_16h5" << std::endl
54 << " 6: TAG_CIRCLE21h7" << std::endl
55 << " 7: TAG_CIRCLE49h12" << std::endl
56 << " 8: TAG_CUSTOM48h12" << std::endl
57 << " 9: TAG_STANDARD41h12" << std::endl
58 << " 10: TAG_STANDARD52h13" << std::endl
59 << " 11: TAG_ARUCO_4x4_50" << std::endl
60 << " 12: TAG_ARUCO_4x4_100" << std::endl
61 << " 13: TAG_ARUCO_4x4_250" << std::endl
62 << " 14: TAG_ARUCO_4x4_1000" << std::endl
63 << " 15: TAG_ARUCO_5x5_50" << std::endl
64 << " 16: TAG_ARUCO_5x5_100" << std::endl
65 << " 17: TAG_ARUCO_5x5_250" << std::endl
66 << " 18: TAG_ARUCO_5x5_1000" << std::endl
67 << " 19: TAG_ARUCO_6x6_50" << std::endl
68 << " 20: TAG_ARUCO_6x6_100" << std::endl
69 << " 21: TAG_ARUCO_6x6_250" << std::endl
70 << " 22: TAG_ARUCO_6x6_1000" << std::endl
71 << " 23: TAG_ARUCO_7x7_50" << std::endl
72 << " 24: TAG_ARUCO_7x7_100" << std::endl
73 << " 25: TAG_ARUCO_7x7_250" << std::endl
74 << " 26: TAG_ARUCO_7x7_1000" << std::endl
75 << " 27: TAG_ARUCO_MIP_36h12" << std::endl
76 << " Default: 0 (36h11)" << std::endl
77 << std::endl
78 << " --tag-decision-margin-threshold <threshold>" << std::endl
79 << " Threshold used to discard low-confident detections. A typical value is " << std::endl
80 << " around 100. The higher this value, the more false positives will be filtered" << std::endl
81 << " out. When this value is set to -1, false positives are not filtered out." << std::endl
82 << " Default: 50" << std::endl
83 << std::endl
84 << " --tag-hamming-distance-threshold <threshold>" << std::endl
85 << " Threshold used to discard low-confident detections with corrected bits." << std::endl
86 << " A typical value is between 0 and 3. The lower this value, the more false" << std::endl
87 << " positives will be filtered out." << std::endl
88 << " Default: 0" << std::endl
89 << std::endl
90 << " --tag-quad-decimate <factor>" << std::endl
91 << " Decimation factor used to detect a tag. " << std::endl
92 << " Default: 1" << std::endl
93 << std::endl
94 << " --tag-n-threads <number>" << std::endl
95 << " Number of threads used to detect a tag." << std::endl
96 << " Default: 1" << std::endl
97 << std::endl
98 << " --tag-z-aligned" << std::endl
99 << " When enabled, tag z-axis and camera z-axis are aligned." << std::endl
100 << " Default: false" << std::endl
101 << std::endl
102 << " --tag-pose-method <method>" << std::endl
103 << " Algorithm used to compute the tag pose from its 4 corners." << std::endl
104 << " Possible values are:" << std::endl
105 << " 0: HOMOGRAPHY" << std::endl
106 << " 1: HOMOGRAPHY_VIRTUAL_VS" << std::endl
107 << " 2: DEMENTHON_VIRTUAL_VS" << std::endl
108 << " 3: LAGRANGE_VIRTUAL_VS" << std::endl
109 << " 4: BEST_RESIDUAL_VIRTUAL_VS" << std::endl
110 << " 5: HOMOGRAPHY_ORTHOGONAL_ITERATION" << std::endl
111 << " Default: 1 (HOMOGRAPHY_VIRTUAL_VS)" << std::endl
112 << std::endl
113#if defined(VISP_HAVE_DISPLAY)
114 << " --display-tag" << std::endl
115 << " Flag used to enable displaying the edges of a tag." << std::endl
116 << " Default: disabled" << std::endl
117 << std::endl
118 << " --display-off" << std::endl
119 << " Flag used to turn display off." << std::endl
120 << " Default: enabled" << std::endl
121 << std::endl
122 << " --color <id>" << std::endl
123 << " Color id used to display the frame over each tag." << std::endl
124 << " Possible values are:" << std::endl
125 << " -1: R-G-B colors for X, Y, Z axis respectively" << std::endl
126 << " 0: all axis in black" << std::endl
127 << " 1: all axis in white" << std::endl
128 << " ..." << std::endl
129 << " Default: -1" << std::endl
130 << std::endl
131 << " --thickness <thickness>" << std::endl
132 << " Thickness of the drawings in overlay." << std::endl
133 << " Default: 2" << std::endl
134 << std::endl
135#endif
136 << " --verbose, -v" << std::endl
137 << " Enable extra verbosity." << std::endl
138 << std::endl
139 << " --help, -h" << std::endl
140 << " Print this helper message." << std::endl
141 << std::endl;
142
143 if (error) {
144 std::cout << "Error" << std::endl
145 << " "
146 << "Unsupported parameter " << argv[error] << std::endl;
147 }
148}
149
150int main(int argc, const char **argv)
151{
153 // Realsense T265 is only supported if realsense API > 2.31.0
154#if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
156
157#ifdef ENABLE_VISP_NAMESPACE
158 using namespace VISP_NAMESPACE_NAME;
159#endif
160
163 double opt_tag_size = 0.053;
164 float opt_tag_quad_decimate = 1.0;
165 float opt_tag_decision_margin_threshold = 50;
166 int opt_tag_hamming_distance_threshold = 2;
167 int opt_tag_nThreads = 1;
168 bool opt_display_tag = false;
169 int opt_color_id = -1;
170 unsigned int opt_thickness = 2;
171 bool opt_tag_z_align_frame = false;
172
173#if !(defined(VISP_HAVE_DISPLAY))
174 bool opt_display_off = true;
175 std::cout << "Warning: There is no 3rd party (X11, GDI or openCV) to display images..." << std::endl;
176#else
177 bool opt_display_off = false;
178#endif
179
180 for (int i = 1; i < argc; i++) {
181 if (std::string(argv[i]) == "--tag-size" && i + 1 < argc) {
182 opt_tag_size = atof(argv[++i]);
183 }
184 else if (std::string(argv[i]) == "--tag-family" && i + 1 < argc) {
185 opt_tag_family = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[++i]);
186 }
187 else if (std::string(argv[i]) == "--tag-quad-decimate" && i + 1 < argc) {
188 opt_tag_quad_decimate = static_cast<float>(atof(argv[++i]));
189 }
190 else if (std::string(argv[i]) == "--tag-n-threads" && i + 1 < argc) {
191 opt_tag_nThreads = atoi(argv[++i]);
192 }
193 else if (std::string(argv[i]) == "--tag-z-aligned") {
194 opt_tag_z_align_frame = true;
195 }
196 else if (std::string(argv[i]) == "--tag-pose-method" && i + 1 < argc) {
197 opt_tag_pose_estimation_method = (vpDetectorAprilTag::vpPoseEstimationMethod)atoi(argv[++i]);
198 }
199 else if (std::string(argv[i]) == "--tag-decision-margin-threshold" && i + 1 < argc) {
200 opt_tag_decision_margin_threshold = static_cast<float>(atof(argv[++i]));
201 }
202 else if (std::string(argv[i]) == "--tag-hamming-distance-threshold" && i + 1 < argc) {
203 opt_tag_hamming_distance_threshold = atoi(argv[++i]);
204 }
205#if defined(VISP_HAVE_DISPLAY)
206 else if (std::string(argv[i]) == "--display-tag") {
207 opt_display_tag = true;
208 }
209 else if (std::string(argv[i]) == "--display-off") {
210 opt_display_off = true;
211 }
212 else if (std::string(argv[i]) == "--color" && i + 1 < argc) {
213 opt_color_id = atoi(argv[++i]);
214 }
215 else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) {
216 opt_thickness = static_cast<unsigned int>(atoi(argv[++i]));
217 }
218#endif
219 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
220 usage(argv, 0);
221 return EXIT_SUCCESS;
222 }
223 else {
224 usage(argv, i);
225 return EXIT_FAILURE;
226 }
227 }
228
229#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
230 std::shared_ptr<vpDisplay> display_left, display_undistort;
231#else
232 vpDisplay *display_left = nullptr;
233 vpDisplay *display_undistort = nullptr;
234#endif
235
236 try {
238 std::cout << "Use Realsense 2 grabber" << std::endl;
239 vpRealSense2 g;
240 rs2::config config;
241 unsigned int width = 848, height = 800;
242 config.disable_stream(RS2_STREAM_FISHEYE, 1);
243 config.disable_stream(RS2_STREAM_FISHEYE, 2);
244 config.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8);
245 config.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8);
246
247 vpImage<unsigned char> I_left(height, width);
248 vpImage<unsigned char> I_undist(height, width);
249
250 g.open(config);
251 g.acquire(&I_left, nullptr, nullptr);
252
253 std::cout << "Read camera parameters from Realsense device" << std::endl;
254 vpCameraParameters cam_left, cam_undistort;
256 cam_undistort.initPersProjWithoutDistortion(cam_left.get_px(), cam_left.get_py(), cam_left.get_u0(),
257 cam_left.get_v0());
259
260 std::cout << cam_left << std::endl;
261 std::cout << "Tag detector settings" << std::endl;
262 std::cout << " Tag size [m] : " << opt_tag_size << std::endl;
263 std::cout << " Tag family : " << opt_tag_family << std::endl;
264 std::cout << " Quad decimate : " << opt_tag_quad_decimate << std::endl;
265 std::cout << " Decision margin threshold : " << opt_tag_decision_margin_threshold << std::endl;
266 std::cout << " Hamming distance threshold: " << opt_tag_hamming_distance_threshold << std::endl;
267 std::cout << " Num threads : " << opt_tag_nThreads << std::endl;
268 std::cout << " Z aligned : " << opt_tag_z_align_frame << std::endl;
269 std::cout << " Pose estimation : " << opt_tag_pose_estimation_method << std::endl;
270
271 if (!opt_display_off) {
272#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
273 display_left = vpDisplayFactory::createDisplay(I_left, 100, 30, "Left image");
274 display_undistort = vpDisplayFactory::createDisplay(I_undist, I_left.getWidth(), 30, "Undistorted image");
275#else
276 display_left = vpDisplayFactory::allocateDisplay(I_left, 100, 30, "Left image");
277 display_undistort = vpDisplayFactory::allocateDisplay(I_undist, I_left.getWidth(), 30, "Undistorted image");
278#endif
279 }
280
282 vpArray2D<int> mapU, mapV;
283 vpArray2D<float> mapDu, mapDv;
284 vpImageTools::initUndistortMap(cam_left, I_left.getWidth(), I_left.getHeight(), mapU, mapV, mapDu, mapDv);
286
288 vpDetectorAprilTag detector(opt_tag_family);
290
292 detector.setAprilTagQuadDecimate(opt_tag_quad_decimate);
293 detector.setAprilTagPoseEstimationMethod(opt_tag_pose_estimation_method);
294 detector.setAprilTagNbThreads(opt_tag_nThreads);
295 detector.setDisplayTag(opt_display_tag, opt_color_id < 0 ? vpColor::none : vpColor::getColor(opt_color_id), opt_thickness);
296 detector.setZAlignedWithCameraAxis(opt_tag_z_align_frame);
297 detector.setAprilTagDecisionMarginThreshold(opt_tag_decision_margin_threshold);
298 detector.setAprilTagHammingDistanceThreshold(opt_tag_hamming_distance_threshold);
300
301 std::vector<double> time_vec;
302
303 std::vector<std::vector<vpImagePoint> > tag_corners;
304
305 for (;;) {
306 double t = vpTime::measureTimeMs();
307
309 g.acquire(&I_left, nullptr, nullptr);
310
312 vpImageTools::undistort(I_left, mapU, mapV, mapDu, mapDv, I_undist);
314
316 vpDisplay::display(I_left);
317 vpDisplay::display(I_undist);
319
321 std::vector<vpHomogeneousMatrix> cMo_vec, cMo_vec1;
322 detector.detect(I_undist, opt_tag_size, cam_undistort, cMo_vec);
324
325 // Display tag corners, bounding box and pose
326 for (size_t i = 0; i < cMo_vec.size(); i++) {
327 tag_corners = detector.getTagsCorners();
328 for (size_t j = 0; j < 4; j++) {
329 vpDisplay::displayCross(I_undist, tag_corners[i][j], 20, vpColor::green, 2);
330 }
331
332 vpDisplay::displayRectangle(I_undist, detector.getBBox(i), vpColor::yellow, false, 3);
333 vpDisplay::displayFrame(I_undist, cMo_vec[i], cam_undistort, opt_tag_size / 2, vpColor::red, 3);
334 }
335
337 time_vec.push_back(t);
338
339 std::stringstream ss;
340 ss << "Detection time: " << t << " ms for " << detector.getNbObjects() << " tags";
341 vpDisplay::displayText(I_left, 50, 20, ss.str(), vpColor::red);
342 vpDisplay::displayText(I_undist, 50, 20, ss.str(), vpColor::red);
343
344 if (vpDisplay::getClick(I_left, false) || vpDisplay::getClick(I_undist, false))
345 break;
346
347 vpDisplay::flush(I_left);
348 vpDisplay::flush(I_undist);
349 }
350
351 std::cout << "Benchmark loop processing time" << std::endl;
352 std::cout << "Mean / Median / Std: " << vpMath::getMean(time_vec) << " ms"
353 << " ; " << vpMath::getMedian(time_vec) << " ms"
354 << " ; " << vpMath::getStdev(time_vec) << " ms" << std::endl;
355 }
356 catch (const vpException &e) {
357 std::cerr << "Catch an exception: " << e.getMessage() << std::endl;
358 }
359
360#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
361 if (!opt_display_off) {
362 if (display_left != nullptr) {
363 delete display_left;
364 }
365
366 if (display_undistort != nullptr) {
367 delete display_undistort;
368 }
369 }
370#endif
371
372 return EXIT_SUCCESS;
373#else
374 (void)argc;
375 (void)argv;
376#ifndef VISP_HAVE_APRILTAG
377 std::cout << "Enable Apriltag support, configure and build ViSP to run this tutorial" << std::endl;
378#elif defined(VISP_HAVE_REALSENSE2) && !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
379 std::cout << "Realsense T265 device needs librealsense API > 2.31.0. ViSP is linked with librealsense API "
380 << RS2_API_VERSION_STR << ". You need to upgrade librealsense to use this example." << std::endl;
381#else
382 std::cout << "Install librealsense 3rd party, configure and build ViSP again to use this example." << std::endl;
383#endif
384#endif
385 return EXIT_SUCCESS;
386}
Implementation of a generic 2D array used as base class for matrices and vectors.
Definition vpArray2D.h:146
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ ProjWithKannalaBrandtDistortion
Projection with Kannala-Brandt distortion model.
static vpColor getColor(const unsigned int &i)
Definition vpColor.h:300
static const vpColor red
Definition vpColor.h:198
static const vpColor none
Definition vpColor.h:210
static const vpColor yellow
Definition vpColor.h:206
static const vpColor green
Definition vpColor.h:201
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
static void flush(const vpImage< unsigned char > &I)
static void displayRectangle(const vpImage< unsigned char > &I, const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, bool fill=false, unsigned int thickness=1)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition vpException.h:60
static void initUndistortMap(const vpCameraParameters &cam, unsigned int width, unsigned int height, vpArray2D< int > &mapU, vpArray2D< int > &mapV, vpArray2D< float > &mapDu, vpArray2D< float > &mapDv)
static void undistort(const vpImage< Type > &I, const vpCameraParameters &cam, vpImage< Type > &newI, unsigned int nThreads=2)
Definition of the vpImage class member functions.
Definition vpImage.h:131
static double getMedian(const std::vector< double > &v)
Definition vpMath.cpp:343
static double getStdev(const std::vector< double > &v, bool useBesselCorrection=false)
Definition vpMath.cpp:374
static double getMean(const std::vector< double > &v)
Definition vpMath.cpp:323
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()