1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564
|
/**
\page tutorial-tracking-mb-generic Tutorial: Markerless generic model-based tracking using a color camera
\tableofcontents
\section mb_generic_intro Introduction
ViSP allows simultaneously the tracking of a markerless object using the knowledge of its CAD model while providing its 3D
localization (i.e., the object pose expressed in the camera frame) when a calibrated camera is used \cite Comport06b, \cite Trinh18a.
Considered objects should be modeled by lines, circles or cylinders. The CAD model of the object could be defined in vrml format
(except for circles), or in cao format (a home-made format).
This tutorial focuses on vpMbGenericTracker class that was introduced in ViSP 3.1.0. This class brings a generic way to consider
different kind of visual features used as measures by the model-based tracker and allows also to consider either a single camera
or multiple cameras observing the object to track. This class replaces advantageously the usage of the following classes
vpMbEdgeTracker, vpMbKltTracker or the one mixing edges and keypoints vpMbEdgeKltTracker that will continue to exist in ViSP but
that we don't recommend to use, since switching from one class to an other may be laborious. If for one reason or another you
still want to use these classes, we invite you to follow \ref tutorial-tracking-mb-deprecated.
In this tutorial, we will show how to use vpMbGenericTracker class in order to track an object from images acquires by a monocular
color camera using either moving edges, either keypoints, or either a combination of them using an hybrid scheme. To illustrate
this tutorial we will consider that the object to track is a tea box.
Note that all the material (source code, input video, CAD model or XML settings files) described in this tutorial is part of ViSP
source code and could be downloaded using the following command:
\code
$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/tracking/model-based/generic
\endcode
\subsection mb_generic_intro_features_overview Features overview
Considering the use case of a monocular color camera, the tracker implemented in vpMbGenericTracker class allows to consider a
combination of the following visual features:
- moving edges: image points tracked along the visible edges defined in the CAD model (line, face, cylinder and circle primitives)
\cite Comport06b. This feature is appropriate to track texture-less objects (with visible edges)
- keypoints: they are tracked on the visible object faces using KLT tracker (face and cylinder primitives) \cite Pressigout:2007.
This feature is suitable for textured objects
The moving-edges and KLT features require a RGB camera but note that these features operate on grayscale image.
Note also that combining the visual features (moving edges + keypoints) can be a good way to improve the tracking robustness.
\subsection mb_generic_intro_3rd_parties Considered third-parties
Depending on your use case the following optional third-parties may be used by the tracker. Make sure ViSP was build with the
appropriate 3rd parties:
- \c OpenCV: Essential if you want to use the keypoints as visual features that are detected and tracked thanks to the KLT tracker.
This 3rd party may be also useful to consider input videos (mpeg, png, jpeg...).
- \c Ogre \c 3D: This 3rd party is optional and could be difficult to install on OSX and Windows. To begin with the tracker we don't
recommend to install it. \c Ogre \c 3D allows to enable \ref mb_generic_settings_visibility_ogre.
- \c Coin \c 3D: This 3rd party is also optional and difficult to install. That's why we don't recommend to install \c Coin \c 3D
to begin with the tracker. \c Coin \c 3D allows only to consider \ref mb_generic_advanced_wrml instead of the home-made
\ref mb_generic_advanced_cao.
\subsection mb_generic_input Input images data
For classical features working on grayscale image, you have to use the following data type:
\code
vpImage<unsigned char> I;
\endcode
You can convert to a grayscale image if the image acquired is in RGBa data type:
\code
vpImage<vpRGBa> I_color;
// Color image acquisition
vpImage<unsigned char> I;
vpImageConvert::convert(I_color, I);
\endcode
Since ViSP 3.2.1, it is also possible to consider color images as input with the following data type:
\code
vpImage<vpRGBa> I;
\endcode
\note If you consider color images as intput, the time requested by the tracker to process one image will increase since there is a
conversion from the color to a gray level image used in the tracker low level layers.
\section mb_generic_started Getting started
To start with the generic markerless model-based tracker we recommend to understand the tutorial-mb-generic-tracker.cpp source code
that is given and explained below.
\subsection mb_generic_started_input Example input/output data
The tutorial-mb-generic-tracker.cpp example uses the following data as input:
- a video file; `teabox.mpg` is the default video.
- a cad model that describes the object to track. In our case the file `teabox.cao` is the default one. See \ref mb_generic_model
section to learn how the teabox is modeled and section \ref mb_generic_advanced_cao to learn how to model an other object.
- a file with extension `*.init` that contains the 3D coordinates of some points used to compute an initial pose which serves to
initialize the tracker. The user has than to click in the image on the corresponding 2D points. The default file is named
`teabox.init`. The content of this file is detailed in \ref mb_generic_init_user section.
- an optional image with extension `*.ppm` that may help the user to remember the location of the corresponding 3D points specified
in `*.init` file. To know more about this file see \ref mb_generic_init_user section.
As an output the tracker provides the pose \f$^c {\bf M}_o \f$ corresponding to a 4 by 4 matrix that corresponds to the geometric
transformation between the frame attached to the object (in our case the tea box) and the frame attached to the camera. The pose
is return as a vpHomogeneousMatrix container.
\subsection mb_generic_started_src Example source code
The following example that comes from tutorial-mb-generic-tracker.cpp allows to track a tea box modeled in cao format using either moving
edges of keypoints as visual features.
\include tutorial-mb-generic-tracker.cpp
\note An extension of the previous getting started example is proposed in tutorial-mb-generic-tracker-full.cpp where advanced functionality
such as reading tracker settings from an XML file or visibility computation are implemented.
\subsection mb_generic_started_exe Running the example
Once build, to see the options that are available in the previous source code, just run:
\code
$ ./tutorial-mb-generic-tracker --help
Usage: ./tutorial-mb-generic-tracker [--video <video name>] [--model <model name>] [--tracker <0=egde|1=keypoint|2=hybrid>] [--help]
\endcode
By default, `model/teabox/teabox.mpg` video and `model/teabox/teabox.cao` model are used as input. Using \c "--tracker" option, you can
specify which tracker has to be used:
- Using \c "--tracker 0" to track only moving-edges:
\code
$ ./tutorial-mb-generic-tracker --tracker 0
\endcode
will produce results similar to:
\htmlonly
<br>
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/b__u_yGEbmc" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly
- Using \c "--tracker 1" to track only keypoints:
\code
$ ./tutorial-mb-generic-tracker --tracker 1
\endcode
will produce results similar to:
\htmlonly
<br>
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/eZmUw9r6Idw" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly
- Using \c "--tracker 2" to track moving-edges and keypoints in an hybrid scheme:
\code
$ ./tutorial-mb-generic-tracker --tracker 2
\endcode
will produce results similar to:
\htmlonly
<br>
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/a-RX9NPF2k0" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly
With this example it is also possible to work on an other data set using \c "--video" and \c "--model" command line options. For example, if you run:
\code
$ ./tutorial-mb-generic-tracker --video <path1>/myvideo%04.png --model <path2>/myobject.cao.
\endcode
it means that the following images will be used as input:
\code
<path1>/myvideo0001.png
<path1>/myvideo0002.png
...
<path1>/myvideo0009.png
<path1>/myvideo0010.png
...
\endcode
and that in \c \<path2\> you have the following data:
- \c myobject.init: The coordinates of at least four 3D points used for the initialization.
- \c myobject.cao: The CAD model of the object to track.
- \c myobject.ppm: An optional image that shows where the user has to click the points defined in \c myobject.init. Supported image format
are png, ppm, png, jpeg.
- \c myobject.xml: An optional files that contains the tracker parameters that are specific to the image sequence and that contains also
the camera intrinsic parameters obtained by calibration (see \ref tutorial-calibration-intrinsic). This file is handled in
tutorial-mb-generic-tracker-full.cpp but not in tutorial-mb-generic-tracker.cpp. That's why since the video \c teabox.mpg was acquired
by an other camera than yours, you have to set the camera intrinsic parameters in tutorial-mb-generic-tracker.cpp source code modifying
the line:
\snippet tutorial-mb-generic-tracker.cpp Set camera parameters
and build again before using \c "--model ..." command line option.
\subsection mb_generic_started_src_explained Source code explained
Hereafter is the description of the some lines introduced in the previous example.
First we include the header of the generic tracker.
\snippet tutorial-mb-generic-tracker.cpp Include
The tracker uses image \c I and the intrinsic camera parameters \c cam as input.
\snippet tutorial-mb-generic-tracker.cpp Image
As output, it estimates \c cMo, the pose of the object in the camera frame.
\snippet tutorial-mb-generic-tracker.cpp cMo
Once input image \c teabox.pgm is loaded in \c I, a window is created and initialized with image \c I. Then we create an instance of the
tracker depending on \c "--tracker" command line option.
\snippet tutorial-mb-generic-tracker.cpp Constructor
Then the corresponding tracker settings are initialized. More details are given in \ref mb_generic_settings section.
\snippet tutorial-mb-generic-tracker.cpp Set parameters
Now we are ready to load the cad model of the object. ViSP supports cad model in cao format or in vrml format. The cao format is a particular
format only supported by ViSP. It doesn't require an additional 3rd party rather then vrml format that require Coin 3rd party. We load the
cad model in cao format from \c teabox.cao file which complete description is provided in \ref mb_generic_teabox_cao with:
\snippet tutorial-mb-generic-tracker.cpp Load cao
It is also possible to modify the code to load the cad model in vrml format from \c teabox.wrl file described in \ref mb_generic_teabox_vrml.
To this end modify the previous line with:
\code
tracker->loadModel(objectname + ".wrl");
\endcode
Once the model of the object to track is loaded, with the next line the display in the image window of additional drawings in overlay such
as the moving edges positions, is then enabled by:
\snippet tutorial-mb-generic-tracker.cpp Set display
Now we have to initialize the tracker. With the next line we choose to use a user interaction (see \ref mb_generic_init_user).
\snippet tutorial-mb-generic-tracker.cpp Init
Next, in the infinite while loop, after displaying the next image, we track the object on a new image \c I.
\snippet tutorial-mb-generic-tracker.cpp Track
The result of the tracking is a pose \c cMo that can be obtained by:
\snippet tutorial-mb-generic-tracker.cpp Get pose
Next lines are used first to retrieve the camera parameters used by the tracker, then to display the visible part of the cad model using
red lines with 2 as thickness, and finally to display the object frame at the estimated position \c cMo. Each axis of the frame are 0.025
meters long. Using vpColor::none indicates that x-axis is displayed in red, y-axis in green, while z-axis in blue. The thickness of the axis is 3.
\snippet tutorial-mb-generic-tracker.cpp Display
The last lines are here to free the memory allocated for the display and tracker:
\snippet tutorial-mb-generic-tracker.cpp Cleanup
\section mb_generic_model Tracker CAD model
ViSP model-based tracker supports two different ways to describe CAD models, either in `cao` or in `vrml` format.
- `cao` format is specific to ViSP. It allows to describe the CAD model of an object using a text file with extension `.cao`.
- `vrml` format is supported only if Coin 3rd party is installed. This format allows to describe the CAD model of an object using a
text file with extension `.wrl`.
To load a CAD model there is the vpMbGenericTracker::loadModel() function that could be used to load either `cao` model:
\code
vpMbGenericTracker tracker;
tracker.loadModel("teabox.cao");
\endcode
or a `vrml` model:
\code
tracker.loadModel("teabox.wrl");
\endcode
\subsection mb_generic_teabox_cao teabox.cao example
The content of the file `teabox.cao` used in the getting started \ref mb_generic_started_src but also in tutorial-mb-edge-tracker.cpp and
in tutorial-mb-hybrid-tracker.cpp examples is given here:
\includelineno tutorial/tracking/model-based/generic/model/teabox/teabox.cao
This file describes the model of the tea box corresponding to the next image:
\image html img-teabox-cao.jpg Index of the vertices used to model the tea box in cao format.
We make the choice to describe the faces of the box from the 3D points that correspond to the vertices. We provide now a line by line
description of the file. Notice that the characters after the '#' are considered as comments.
- line 1: Header of the \c .cao file
- line 3: The model is defined by 8 3D points. Here the 8 points correspond to the 8 vertices of the tea box presented in the previous
figure. Thus, next 8 lines define the 3D points coordinates.
- line 4: 3D point with coordinate (0,0,0) corresponding to vertex 0 of the tea box. This point is also the origin of the frame in which
all the 3D points are defined.
- line 5: 3D point with coordinate (0,0,-0.08) corresponding to vertex 1.
- line 6 to 11: The other 3D points corresponding to vertices 2 to 7 respectively.
- line 13: Number of 3D lines defined from two 3D points. It is possible to introduce 3D lines and then use these lines to define faces
from these 3D lines. This is particularly useful to define faces from non-closed polygons. For instance, it can be used to specify the
tracking of only 3 edges of a rectangle. Notice also that a 3D line that doesn't belong to a face is always visible and consequently
always tracked.
- line 15: Number of faces defined from 3D lines. In our teabox example we decide to define all the faces from 3D points, that is why
this value is set to 0.
- line 17: The number of faces defined by a set of 3D points. Here our teabox has 6 faces. Thus, next 6 lines describe each face from the
3D points defined previously line 4 to 11. Notice here that all the faces defined from 3D points corresponds to closed polygons.
- line 18: First face defined by 4 3D points, respectively vertices 0,1,2,3. The orientation of the face is counter clockwise by going
from vertex 0 to vertex 1, then 2 and 3. This fixes the orientation of the normal of the face going outside the object.
- line 19: Second face also defined by 4 points, respectively vertices 1,6,5,2 to have a counter clockwise orientation.
- line 20 to 23: The four other faces of the box.
- line 25: Number of 3D cylinders describing the model. Since we model a simple box, the number of cylinders is 0.
- line 27: Number of 3D circles describing the model. For the same reason, the number of circles is 0.
\subsection mb_generic_teabox_cao_triangle teabox-triangle.cao example
The content of the file teabox-triangle.cao used in the tutorial-mb-klt-tracker.cpp example is given here:
\includelineno tutorial/tracking/model-based/old/keypoint/teabox-triangle.cao
This file describes the model of the tea box corresponding to the next image:
\image html img-teabox-cao-triangle.jpg Index of the vertices used to model the tea box in cao format with triangles.
Until line 15, the content of this file is similar to the one described in
\ref mb_generic_teabox_cao. Line 17 we specify that the model contains 12 faces. Each face is then described as a triangle.
\note Since some lines of the model (for example the one between points 0 and 2, or 7 and 3...) don't correspond to teabox edges, this CAD
model is not suited for moving-edges and hybrid trackers.
\subsection mb_generic_teabox_vrml teabox.wrl example
The content of the \c teabox.wrl file used in tutorial-mb-generic-tracker-full.cpp and tutorial-mb-edge-tracker.cpp when \c teabox.cao is
missing is given hereafter. This content is to make into relation with \c teabox.cao described in \ref mb_generic_teabox_cao. As for the cao
format, \c teabox.wrl describes first the vertices of the box, then the edges that corresponds to the faces.
\includelineno tracking/model-based/generic/model/teabox/teabox.wrl
This file describes the model of the tea box corresponding to the next image:
\image html img-teabox-cao.jpg Index of the vertices used to model the tea box in vrml format.
We provide now a line by line description of the file where the faces of the box are defined from the vertices:
- line 1 to 10: Header of the \c .wrl file.
- line 13 to 20: 3D coordinates of the 8 tea box vertices.
- line 34 to 29: Each line describe a face. In this example, a face is defined by 4 vertices. For example, the first face join vertices
0,1,2,3. The orientation of the face is counter clockwise by going from vertex 0 to vertex 1, then 2 and 3. This fixes the orientation
of the normal of the face going outside the object.
\section mb_generic_init Tracker initialization
There are two ways to initialize the tracker, either by user interaction, either using an initial pose provided by a specific algorithm.
\subsection mb_generic_init_user Initialization by user click
The tracker could be initialized by the user that has to click on at least 4 points on the object seen in the image. To this end,
vpMbGenericTracker::initClick() function has to be used.
\snippet tutorial-mb-generic-tracker.cpp Init
The previous line of code, loads a file named \c "<objectname>.init" and waits for user click. When an image named \c "<objectname>.ppm"
exists besides \c "<objectname>.init" and when the last parameter of the function is set to `true`, the image is displayed to help the user
to know where to click. Supported image formats are `.ppm`, `.pgm`, `.png`, `.jpeg` and `.jpg`.
Let us consider the teabox example.
The user has to click in the image on four vertices with their 3D coordinates defined in the \c "teabox.init" file. The following image
\c "teabox.ppm" shows where the user has to click.
\image html img-teabox-click.jpg Image \c "teabox.ppm" used to help the user to initialize the tracker.
Matched 2D and 3D coordinates are then used to compute an initial pose used to initialize the tracker. Note also that the third optional
argument "true" is used here to enable the display of an image that may help the user for the initialization. The name of this image is
the same as the \c "*.init" file except the extension that should be \c ".ppm". In our case it will be \c "teabox.ppm".
The content of \c teabox.init file that defines 3D coordinates of some points of the model used during user initialization is provided
hereafter. Note that all the characters after character '#' are considered as comments.
\includelineno tutorial/tracking/model-based/generic/model/teabox/teabox.init
We give now the signification of each line of this file:
- line 1: Number of 3D points that are defined in this file. At least 4 points are required. Four is the minimal number of points requested
to compute a pose.
- line 2: Each point is defined by its 3D coordinates. Here we define the first point with coordinates (0,0,0). In the previous figure it
corresponds to vertex 0 of the tea box. This point is also the origin of the frame in which all the points are defined.
- line 3: 3D coordinates of vertex 3.
- line 4: 3D coordinates of vertex 2.
- line 5: 3D coordinates of vertex 5.
Here the user has to click on vertex 0, 3, 2 and 5 in the window that displays image \c I. From the 3D coordinates defined in \c teabox.init
and the corresponding 2D coordinates of the vertices obtained by user interaction a pose is computed that is then used to initialize the tracker.
<b>How to choose good points for manual initialization</b>
To select which 3D points to put in the `.init` file that are used to initialize manually the tracker, you should ensure that:
- The projection of the points (usually we use four 3D points but could be more in the `.init` file) in the image must be visible
- The spatial distribution of the projection of 3D points in the image should be as wide as possible in the image (ie they should
not be distributed over a very small part in the image), they should be not aligned and not located in the same plane when the object
is non planar
- Usually, we copy/paste coordinates of 3D points from `.cao` file.
\subsection mb_generic_init_pose Initialization by external pose
The other way to initialize the tracker is to use an initial pose provided by an external algorithm. To this end,
vpMbGenericTracker::initFromPose() function has to be used.
\snippet tutorial-mb-generic-tracker-apriltag-webcam.cpp Init
Initial pose named `cMo` is here a vpHomogeneousMatrix object.
There are several ways to get an initial pose:
- by using a fiducal marker such an AprilTag that could be detected online and which pose can serve as initialization; see
\ref tutorial-tracking-mb-generic-apriltag-live
- when the object is textured, by learning the keypoint descriptors located on visible faces; see \ref tutorial-detection-object
- by using advanced deep learning algorithms...
\section mb_generic_settings Tracker settings
\subsection mb_generic_settings_xml Settings from an XML file
Instead of setting the tracker parameters from source code, it is possible to specify the settings from an XML file. As done in
tutorial-mb-generic-tracker-full.cpp example, to read the parameters from an XML file, simply modify the code like:
\snippet tutorial-mb-generic-tracker-full.cpp Load xml
The content of the XML file teabox.xml that is considered by default is the following:
\code
<?xml version="1.0"?>
<conf>
<ecm>
<mask>
<size>5</size>
<nb_mask>180</nb_mask>
</mask>
<range>
<tracking>8</tracking>
</range>
<contrast>
<edge_threshold_type>1</edge_threshold_type>
<edge_threshold>20</edge_threshold>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
</contrast>
<sample>
<step>4</step>
</sample>
</ecm>
<klt>
<mask_border>5</mask_border>
<max_features>300</max_features>
<window_size>5</window_size>
<quality>0.015</quality>
<min_distance>8</min_distance>
<harris>0.01</harris>
<size_block>3</size_block>
<pyramid_lvl>3</pyramid_lvl>
</klt>
<camera>
<u0>325.66776</u0>
<v0>243.69727</v0>
<px>839.21470</px>
<py>839.44555</py>
</camera>
<face>
<angle_appear>70</angle_appear>
<angle_disappear>80</angle_disappear>
<near_clipping>0.1</near_clipping>
<far_clipping>100</far_clipping>
<fov_clipping>1</fov_clipping>
</face>
</conf>
\endcode
Depending on the visual features that are used all the XML tags are not useful:
- \c \<ecm\> tag corresponds to the moving-edges settings
- \c \<klt\> tag corresponds to the keypoint visual features and especially the KLT tracker settings used to detect and track the keypoints
- \c \<camera\> tag is used to define the camera intrinsic parameters
- \c \<face\> tag is used by the visibility algorithm used to determine if a face of the object is visible or not.
\subsection mb_generic_settings_ecm Moving-edges settings
Moving-edges settings affect the way the visible edges of an object are tracked.
These settings could be tuned either from XML using \<ecm\> tag as:
\code
<conf>
...
<ecm>
<mask>
<size>5</size>
<nb_mask>180</nb_mask>
</mask>
<range>
<tracking>8</tracking>
</range>
<contrast>
<edge_threshold_type>1</edge_threshold_type>
<edge_threshold>20</edge_threshold>
<mu1>0.5</mu1>
<mu2>0.5</mu2>
</contrast>
<sample>
<step>4</step>
</sample>
</ecm>
...
</conf>
\endcode
of from source code using vpMbGenericTracker::setMovingEdge() method:
\snippet tutorial-mb-generic-tracker-full.cpp Set moving-edges parameters
Either from xml or from the previous source code you can set:
- mask size: using vpMe::setMaskSize() or `<mask>/<size>` xml tag, you will define the size of the convolution mask used to detect an edge.
Possible values are 3, 5 or 7. We recommend to use 5.
- mask number: using vpMe::setMaskNumber() or `<mask>/<nb_mask>` xml tag, you will set the number of mask applied to determine the object contour.
The number of mask determines the precision of the normal of the edge for every sample. If precision is 2 deg, then there are 360/2 = 180 masks.
Recommended value is 180.
- range tracking: using vpMe::setRange() or `<range>/<tracking>` xml tag, you will define the range on both sides of the reference pixel along the
normal of the contour used to track a moving-edge. If the displacement of the tracked object in two successive images is large, you have to increase this parameter.
- moving-edges likelihood threshold type: this setting is new since ViSP 3.6.0. Using vpMe::setLikelihoodThresholdType() or `<contrast>/<edge_threshold_type>` xml tag,
you will define the type of likelihood threshold used to determined if the moving edge is valid or not. Two values are possible: vpMe::OLD_THRESHOLD corresponding to `0`,
or vpMe::NORMALIZED_THRESHOLD corresponding to a value of `1` in the xml file. To keep compatibility with previous ViSP releases, the default type is set to vpMe::OLD_THRESHOLD
in vpMe constructor, but we recommend to use the normalized threshold.
- moving-edges threshold: using vpMe::setThreshold() or `<contrast>/<edge_threshold>` xml tag, you will define the likelihood threshold used to determined if the moving edge is valid or not.
- When the moving-edges likelihood threshold type is set to vpMe::NORMALIZED_THRESHOLD, admissible values are in range [0 ; 255] and correspond to the
luminance contrast between both sides of the moving-edge. When the contrast is small in the image, you should use a small value, like 5 or 10.
When the contrast is large, corresponding for example to a transition from black to white or vice-versa, you can increase this value to 60 or 100.
- When the moving-edges likelihood threshold type is set to vpMe::OLD_THRESHOLD, the value depends on the mask size and the contrast. To ease setting this parameter,
we recommend to use rather a normalized version.
- To convert an old threshold to a normalized one, you can use the following trick:
- When your convolution mask size is 3: divide the value by 300
- When your convolution mask size is 5: divide the value by 2000
- When your convolution mask size is 7: divide the value by 21000.
.
Remmember that the value should be always in [0 ; 255].
- mu1: using vpMe::setMu1() or `<contrast>/<mu1>` xml tag, you will define the minimum image contrast allowed to detect a contour. We recommend to keep this value to 0.5.
- mu2: using vpMe::setMu2() or `<contrast>/<mu2>` xml tag, you will define the maximum image contrast allowed to detect a contour. We recommend to keep this value to 0.5.
- sample step: using vpMe::setSampleStep() or `<sample>/<step>` xml tag, you will define the minimum distance in pixel between two discretized moving-edges.
To increase the number of moving-edges you have to reduce this parameter.
\note Most important parameters are \e range_tracking and \e sample_step.
\subsection mb_generic_settings_klt Keypoints settings
Keypoint settings affect tracking of keypoints on visible faces using KLT.
These settings could be tuned either from XML using \<klt\> tag as:
\code
<conf>
...
<klt>
<mask_border>5</mask_border>
<max_features>300</max_features>
<window_size>5</window_size>
<quality>0.015</quality>
<min_distance>8</min_distance>
<harris>0.01</harris>
<size_block>3</size_block>
<pyramid_lvl>3</pyramid_lvl>
</klt>
...
</conf>
\endcode
of from source code using vpMbKltTracker::setKltOpencv() and vpMbKltTracker::setMaskBorder() methods:
\snippet tutorial-mb-generic-tracker-full.cpp Set klt parameters
With the previous parameters you can set:
- mask border: using vpMbKltTracker::setMaskBorder() or `<klt>/<mask_border>` xml tag, you can specify the size of the mask corresponding
to a zone inside the face along the contour in which the keypoints will not be detected. A mask size of zero means that keypoints
can be detected on the contour.
- max features: using vpKltOpencv::setMaxFeatures() or `<klt>/<max_features>` xml tag, you can set the maximum number of keypoint features to track in the image.
- window size: using vpKltOpencv::setWindowSize() or `<klt>/<window_size>` xml tag, you can set the window size used to refine the corner locations.
- quality: using vpKltOpencv::setQuality() or `<klt>/<quality>` xml tag, you can set the parameter characterizing the minimal accepted quality
of image corners. Corners with quality measure less than this parameter are rejected. This means that if you want to have more keypoints
on a face, you have to reduce this parameter.
- min_distance: using vpKltOpencv::setMinDistance() or `<klt>/<min_distance>` xml tag, you can set the minimal Euclidean distance between
detected corners during keypoint detection stage used to initialize keypoint location.
- harris: using vpKltOpencv::setHarrisFreeParameter() or `<klt>/<harris>` xml tag, you can set the free parameter of the Harris detector.
- block size: using vpKltOpencv::setBlockSize() or `<klt>/<size_block>` xml tag, you can set the size of the averaging block used to track
the keypoint features.
- pyramid level: using vpKltOpencv::setPyramidLevels() or `<klt>/<pyramid_lvl>` xml tag, you can set the maximal pyramid level.
If the level is zero, then no pyramid is computed for the optical flow.
\note Most important parameters are \e min_distance and \e quality.
\subsection mb_generic_settings_cam Camera settings
Camera settings correspond to the intrinsic camera parameters without distortion. If images are acquired by a camera that has a large
field of view that introduce distortion, images need to be undistorded before processed by the tracker. The camera parameters are then
the one obtained on undistorded images.
Camera settings could be set from XML using \<camera\> tag as:
\code
<conf>
...
<camera>
<u0>325.66776</u0>
<v0>243.69727</v0>
<px>839.21470</px>
<py>839.44555</py>
</camera>
...
</conf>
\endcode
of from source code using vpMbTracker::setCameraParameters() method:
\snippet tutorial-mb-generic-tracker-full.cpp Set camera parameters
As described in vpCameraParameters class, these parameters correspond to \f$(p_x, p_y)\f$ the ratio between the focal length and the
size of a pixel, and \f$(u_0, v_0)\f$ the coordinates of the principal point in pixel.
\note The \ref tutorial-calibration-intrinsic explains how to obtain these parameters from a camera calibration stage.
\subsection mb_generic_settings_visibility Visibility settings
An important setting concerns the visibility test that is used to determine if a face is visible or not. Note that moving-edges and
keypoints are only tracked on visible faces. Three different visibility tests are implemented; with or without Ogre ray tracing and
with or without scanline rendering. The default test is the one without Ogre and scanline. The functions
vpMbTracker::setOgreVisibilityTest() and vpMbTracker::setScanLineVisibilityTest() allow to select which test to use.
\subsubsection mb_generic_settings_visibility_default Default visibility based on normals
Let us now highlight how the default visibility test works. As illustrated in the following figure, the angle \f$ \alpha \f$ between
the normal of the face and the line going from the camera to the center of gravity of the face is used to determine if the face is visible.
\image html img-tracker-mb-visibility.jpg Principle of the visibility test used to determine if a face is visible.
When no advanced visibility test is enable (we recall that this is the default behavior), the algorithm that computes the normal of
the face is very simple. It makes the assumption that faces are convex and oriented counter clockwise. If we consider two parameters;
the angle to determine if a face is appearing \f$ \alpha_{appear} \f$, and the angle to determine if the face is disappearing
\f$ \alpha_{disappear} \f$, a face will be considered as visible if \f$ \alpha \leq \alpha_{disappear} \f$. We consider also
that a new face is appearing if \f$ \alpha \leq \alpha_{appear} \f$. These two parameters can be set either in the XML file:
\code
<conf>
...
<face>
<angle_appear>70</angle_appear>
<angle_disappear>80</angle_disappear>
</face>
\endcode
or in the code:
\snippet tutorial-mb-generic-tracker-full.cpp Set angles
Here the face is considered as appearing if \f$ \alpha \leq 70\f$ degrees, and disappearing if \f$ \alpha > 80\f$ degrees.
\note When these two angle parameters are not set, their default values set to 89 degrees are used.
\subsubsection mb_generic_settings_visibility_ogre Advanced visibility via Ogre3D
The Ogre3D visibility test approach is based on ray tracing. When this test is enabled, the algorithm used to determine the visibility
of a face performs (<b>in addition to the previous test based on normals, i.e on the visible faces resulting from the previous test</b>)
another test which sets the faces that are <b>partially occluded as non-visible</b>. It can be enabled via:
\code
tracker->setOgreVisibilityTest(true);
\endcode
\image html img-tracker-mb-visibility-ogre.png "Ogre visibility test on both polygons."
When using the <b>classical version of the ogre visibility test</b> (which is the default behavior when activating this test),
<b>only one ray</b> is used per polygon to test its visibility. As shown on the figure above, this only ray is sent from the camera
to the center of gravity of the considered polygon. If the ray intersects another polygon before the considered one, it is set as
non-visible. Intersections are computed <b>between the ray and the axis-aligned bounding-box (AABB)</b> of each polygon. In the
figure above, the ray associated to the first polygon intersects first the AABB of the second polygon so it is considered as occluded.
As a result, only the second polygon will be used during the tracking phase. This means that when using the edges, only the blue lines
will be taken into account, and when using the keypoints, they will be detected only inside the second polygon (blue area).
Additionally, it is also possible to use a statistical approach during the ray tracing phase in order to improve the visibility results.
\code
tracker->setNbRayCastingAttemptsForVisibility(4);
tracker->setGoodNbRayCastingAttemptsRatio(0.70);
\endcode
\image html img-tracker-mb-visibility-ogre-advanced.png "Ogre visibility test on the first polygon, using a statistical approach."
Contrary to the classical version of this test, the <b>statistical approach uses multiple rays per polygons</b> (4 in the example above).
Each ray is sent randomly toward the considered polygon. If a specified ratio of rays do not have intersected another polygon before the
considered one, the polygon is set as visible. In the example above, three ray on four return the first polygon as visible. As the ratio
of good matches is more than 70% (which corresponds to the chosen ratio in this example) the first polygon is considered as visible, as
well as the second one. As a result, all visible blue lines will be taken into account during the tracking phase of the edges and the
keypoints that are detected inside the green area will be also used. Unfortunately, this approach is a <b>polygon based approach</b>
so the dashed blue lines, that are not visible, will also be used during the tracking phase. Plus, keypoints that are detected inside
the overlapping area won't be well associated and can disturb the algorithm.
\note Since ViSP 3.0.0 we have introduced vpMbTracker::setOgreShowConfigDialog() method that allows to open the Ogre configuration panel
which can be used to select the renderer. To enable this feature, use:
\code
tracker->setOgreShowConfigDialog(true);
\endcode
\subsubsection mb_generic_settings_visibility_scanline Advanced visibility via Scanline Rendering
Contrary to the visibility test using Ogre3D, this method <b>does not require any additional third-party library</b>. As for the advanced
visibility using Ogre3D, <b>this test is applied in addition to the test based on normals (i.e on the faces set as visible during this test)
and also in addition to the test with Ogre3D if it has been activated</b>. This test is based on the scanline rendering algorithm and can
be enabled via:
\code
tracker->setScanLineVisibilityTest(true);
\endcode
\image html img-tracker-mb-visibility-scanline.png "Scanline visibility test on both polygons."
Even if this approach requires a bit <b>more computing power</b>, it is a <b>pixel perfect visibility test</b>. According to the camera
point of view, polygons will be <b>decomposed in order to consider only their visible parts</b>. As a result, if we consider the example
above, dashed red lines won't be considered during the tracking phase and detected keypoints will be correctly matched with the closest
(in term of depth from the camera position) polygon.
\subsection mb_generic_settings_clipping Clipping settings
Additionally to the visibility test described above, it is also possible to use clipping. Firstly, the algorithm removes the faces that
are not visible, according to the visibility test used, then it will also remove the faces or parts of the faces that are out of the
clipping planes. As illustrated in the following figure, different clipping planes can be enabled.
\image html img-fov.png Camera field of view and clipping planes.
Let us consider two plane categories: the ones belonging to the field of view or FOV (Left, Right, Up and Down), and the Near and
Far clipping planes. The FOV planes can be enabled by:
\snippet tutorial-mb-generic-tracker-full.cpp Set clipping fov
which is equivalent to:
\code
tracker->setClipping(vpMbtPolygon::LEFT_CLIPPING
| vpMbtPolygon::RIGHT_CLIPPING
| vpMbtPolygon::UP_CLIPPING
| vpMbtPolygon::DOWN_CLIPPING);
\endcode
Of course, if the user just wants to activate Right and Up clipping, he will use:
\code
tracker->setClipping(vpMbtPolygon::RIGHT_CLIPPING | vpMbtPolygon::UP_CLIPPING);
\endcode
For the Near and Far clipping it is quite different. Indeed, those planes require clipping distances. Here there are two choices,
either the user uses default values and activate them with:
\code
tracker->setClipping(vpMbtPolygon::NEAR_CLIPPING | vpMbtPolygon::FAR_CLIPPING);
\endcode
or the user can specify the distances in meters, which will automatically activate the clipping for those planes:
\snippet tutorial-mb-generic-tracker-full.cpp Set clipping distance
It is also possible to enable them in the XML file. This is done with the following lines:
\code
<conf>
...
<face>
...
<near_clipping>0.1</near_clipping>
<far_clipping>100.0</far_clipping>
<fov_clipping>0</fov_clipping>
</face>
\endcode
Here for simplicity, the user just has the possibility to either activate all the FOV clipping planes or none of them
(fov_clipping requires a boolean).
\note When clipping parameters are not set in the XML file, nor in the code, clipping is not used. Usually clipping is not helpful
when the object to track is simple.
\section mb_generic_advanced Advanced
\subsection mb_generic_advanced_failure_detection How to detect tracking failures
The first way to detect a tracking failure is to catch potential internal exceptions returned by the tracker:
\code
vpMbGenericTracker tracker;
...
while (! end)
{
bool tracking_failed = false;
...
try {
tracker.track(I);
} catch (const vpException &e) {
std::cout << "Tracker exception: " << e.getStringMessage() << std::endl;
tracking_failed = true;
}
...
}
\endcode
If you are using edges as features, you can exploit the internal tracker state using vpMbTracker::getProjectionError() to get
a scalar criteria between 0 and 90 degrees corresponding to the cad model projection error. This criteria corresponds to the
mean angle between the gradient direction of the moving-edges features that are tracked and the normal of the projected cad model.
Thresholding this scalar allows to detect a tracking failure. Usually we consider that a projection angle higher to 25 degrees
corresponds to a tracking failure. This threshold needs to be adapted to your setup and illumination conditions.
\code
...
while (! end)
{
...
if (! tracking_failed) {
double proj_error = 0;
if (tracker.getTrackerType() & vpMbGenericTracker::EDGE_TRACKER) {
proj_error = tracker.getProjectionError();
}
if (proj_error > 25) {
std::cout << "Tracker needs to restart (projection error detected: " << proj_error << ")" << std::endl;
tracking_failed = true;
}
}
...
}
\endcode
When edges are not tracked, meaning that your tracker uses rather klt keypoints or depth features, there is
vpMbGenericTracker::computeCurrentProjectionError() function that may be useful.
\code
...
while (! end)
{
...
if (! tracking_failed) {
double proj_error = 0;
if (tracker.getTrackerType() & vpMbGenericTracker::EDGE_TRACKER) {
proj_error = tracker.getProjectionError();
}
else {
tracker.getPose(cMo);
tracker.getCameraParameters(cam);
proj_error = tracker.computeCurrentProjectionError(I, cMo, cam);
}
if (proj_error > 25) {
std::cout << "Tracker needs to restart (projection error detected: " << proj_error << ")" << std::endl;
tracking_failed = true;
}
}
...
}
\endcode
\note The function vpMbTracker::getProjectionError() is able to compute the projection error only from moving edges that are located on
visible faces, while vpMbGenericTracker::computeCurrentProjectionError() is not able to distinguish between visible & non visible faces.
Thus, results may be more precise with vpMbTracker::getProjectionError(). The tracker allows to display gradient and model orientation
when computing the projection error. To this end use the following:
\code
vpMbGenericTracker tracker;
tracker.setProjectionErrorDisplay(true);
...
while (! end)
{
...
}
\endcode
Tracking failure detection is used in tutorial-mb-generic-tracker-live.cpp and tutorial-mb-generic-tracker-rgbd-realsense.cpp examples.
The model-based tracker can also update a covariance matrix corresponding to the estimated pose. But from our experience, analysing
the diagonal of the 6 by 6 covariance matrix doesn't allow to detect a tracking failure. If you want to have a trial, we recall the way
to get the covariance matrix:
\code
vpMbGenericTracker tracker;
tracker.setCovarianceComputation(true);
...
while (! end)
{
bool tracking_failed = false;
...
try {
tracker.track(I);
} catch (const vpException &e) {
std::cout << "Tracker exception: " << e.getStringMessage() << std::endl;
tracking_failed = true;
}
...
vpMatrix covariance = tracker.getCovarianceMatrix();
}
\endcode
\subsection mb_generic_advanced_model How to manipulate the model
The following code shows how to access to the CAD model
- to check if a face is visible,
- to get the name of the face (only with models in \c .cao format for the moment)
- to check if the level of detail is enable/disable (only with models in \c .cao format for the moment)
- to access to the coordinates of the 3D points used to model a face
- from the pose \e cMo estimated by the tracker to compute the coordinates of the 3D points in the image
\code
vpMbHiddenFaces<vpMbtPolygon> &faces = tracker.getFaces();
std::cout << "Number of faces: " << faces.size() << std::endl;
for (unsigned int i=0; i < faces.size(); i++) {
std::vector<vpMbtPolygon*> &poly = faces.getPolygon();
std::cout << "face " << i << " with index: " << poly[i]->getIndex()
<< (poly[i]->getName().empty() ? "" : (" with name: " + poly[i]->getName()))
<< " is " << (poly[i]->isVisible() ? "visible" : "not visible")
<< " and has " << poly[i]->getNbPoint() << " points"
<< " and LOD is " << (poly[i]->useLod ? "enabled" : "disabled") << std::endl;
for (unsigned int j=0; j<poly[i]->getNbPoint(); j++) {
vpPoint P = poly[i]->getPoint(j);
P.project(cMo);
std::cout << " P obj " << j << ": " << P.get_oX() << " " << P.get_oY() << " " << P.get_oZ() << std::endl;
std::cout << " P cam" << j << ": " << P.get_X() << " " << P.get_Y() << " " << P.get_Z() << std::endl;
vpImagePoint iP;
vpMeterPixelConversion::convertPoint(cam, P.get_x(), P.get_y(), iP);
std::cout << " iP " << j << ": " << iP.get_u() << " " << iP.get_v() << std::endl;
}
}
\endcode
\subsection mb_generic_advanced_lod Level of detail (LOD)
The level of detail (LOD) consists in introducing additional constraints to the visibility check to determine if the features of a
face have to be tracked or not. Two parameters are used:
- the line length (in pixel)
- the area of the face (in pixel²), that could be closed or not (you can define an open face by adding all the segments without the
last one which closes the face)
The tracker allows to enable/disable the level of detail concept using vpMbTracker::setLod() function.
This example permits to set LOD settings to all elements :
\code
tracker.setLod(true);
tracker.setMinLineLengthThresh(40.0);
tracker.setMinPolygonAreaThresh(500.0);
\endcode
This example permits to set LOD settings to specific elements denominated by his name.
\code
tracker.setLod(false);
tracker.setLod(true, "Left line");
tracker.setLod(true, "Front face");
tracker.setMinLineLengthThresh(35.0, "Left line");
tracker.setMinPolygonAreaThresh(120.0, "Front face");
\endcode
Furthermore, to set a name to a face see \ref mb_generic_advanced_cao_nam.
\subsection mb_generic_advanced_cao CAD model in cao format
\note You may be interested to look at \ref tutorial-tracking-mb-CAO-editor that will present some useful tools to handle more conveniently
the custom .cao model file:
- one Blender plugin to export a classical CAD model (Collada, Wavefront, Stl, ...) in the ViSP .cao format
- one Blender plugin to import the ViSP .cao format into Blender
- a Qt-based application to edit and view a .cao model file to check if the modeling is correct for instance
\subsubsection mb_generic_advanced_cao_lin How to model faces from lines
The first thing to do is to declare the differents points. Then you define each segment of the face with the index of the start point and with
the index of the end point. Finally, you define the face with the index of the segments which constitute the face.
\note The way you declare the face segments (clockwise or counter clockwise) will determine the direction of the normal of the face and so will
influe on the visibility of the face.
\code
V1
# Left wing model
6 # Number of points
# 3D points
-4 -3.8 0.7
-6 -8.8 0.2
-12 -21.7 -1.2
-9 -21.7 -1.2
0.8 -8.8 0.2
4.6 -3.8 0.7
# 3D lines
6 # Number of lines
0 1 # line 0
1 2
2 3
3 4
4 5
5 0 # line 5
# Faces from 3D lines
1 # Number of faces defined by lines
6 0 1 2 3 4 5 # face 0: [number of lines] [index of the lines]...
# Faces from 3D points
0
# 3D cylinders
0
# 3D circles
0
\endcode
\subsubsection mb_generic_advanced_cao_cyl How to model cylinders
The first thing to do is to declare the two points defining the cylinder axis of revolution. Then you declare the cylinder with the index of
the points that define the cylinder axis of revolution and with the cylinder radius.
\note For the level of detail, in a case of a cylinder, this is taking into account by using the length of the axis of revolution to determine
the visibility.
\image html img-cylinder.png Example of a cylinder.
\code
V1
# Cylinder model
2 # Number of points
# 3D points
16.9 0 0.5 # point 0
-20 0 0.5 # point 1
# 3D lines
0
# Faces from 3D lines
0
# Faces from 3D points
0
# 3D cylinders
1 # Number of cylinders
0 1 2.4 # cylinder 0: [1st point on revolution axis] [2nd point on revolution axis] [radius]
# 3D circles
0
\endcode
\subsubsection mb_generic_advanced_cao_cir How to model circles
The first thing to do is to declare three points: one point for the center of the circle and two points on the circle plane (i.e. not necessary
located on the perimeter of the circle but on the plane of the circle). Then you declare your circle with the radius and with index of the three points.
\note The way you declare the two points on the circle plane (clockwise or counter clockwise) will determine the direction of the normal of the
circle and so will influe on the visibility of the circle. For the level of detail, in a case of a circle, this is taking into account by using
the area of the bounding box of the circle to determine the visibility.
\image html img-circle.png Example of a circle.
\code
V1
# Circle model
3 # Number of points
# 3D points
-3.4 14.6 1.1 # point 0
-3.4 15.4 1.1
-3.4 14.6 1.8 # point 2
# 3D lines
0
# Faces from 3D lines
0
# Faces from 3D points
0
# 3D cylinders
0
# 3D circles
1 # Number of circles
0.8 0 2 1 # circle 0: [radius] [circle center] [1st point on circle plane] [2nd point on circle plane]
\endcode
\subsubsection mb_generic_advanced_origin How to change cao model origin
By default, the `cMo` pose estimated by the tracker corresponds to the homogeneous transformation between the camera frame and the CAD model
object frame.
The tracker can consider an optional transformation matrix (currently only for `.cao`) to transform 3D points of the CAD model expressed in the
original object frame to a desired object frame. Let us call this matrix `oMod`. When this matrix is introduced, the tracker estimates the
homogeneous transformation between the camera and the modified CAD model object frame.
The tracker has the ability to modify the location of the CAD model origin frame, introducing an extra homogeneous transformation. was designed
to easily modify the location of the CAD model origin introducing an offset transformation matrix:
To load a CAD model there is the vpMbGenericTracker::loadModel() function that could be used to load either `cao` model:
\code
vpMbGenericTracker tracker;
vpHomogeneousMatrix oMd;
...
tracker.loadModel("teabox.cao", false, oMod);
\endcode
\subsubsection mb_generic_advanced_cao_hie How to create a hierarchical model
It could be useful to define a complex model instead of using one big model file with all the declaration with different sub-models, each one
representing a specific part of the complex model in a specific model file. To create a hierarchical model, the first step is to define all
the elementary parts and then regroup them.
\image html img-plane-hierarchical-diagram.jpg Example of a possible hierarchical modeling of a plane.
For example, if we want to have a model of a plane, we could represent as elementary parts the left and right wings, the tailplane (which is
constituted of some other parts) and a cylinder for the plane fuselage.
The following lines represent the top model of the plane.
\code
V1
# header
# load the different parts of the plane
load("wings.cao") # load the left and right wings
load("tailplane.cao")
# 3D points
2 # Number of points
16.9 0 0.5
-20 0 0.5
# 3D lines
0
# Faces from 3D lines
0
# Faces from 3D points
0
# 3D cylinders
1 # Number of cylinders
0 1 2.4 # define the plane fuselage as a cylinder
# 3D circles
0
\endcode
\note The path to include another model can be expressed as an absolute or a relative path (relative to the file which includes the model).
\subsubsection mb_generic_advanced_cao_nam How to set a name to a face
To exploit the name of a face in the code, see sections about \ref mb_generic_advanced_lod and \ref mb_generic_advanced_exclude.
It could be useful to give a name for a face in a model in order to easily modify his LOD parameters for example, or to decide if you want
to use this face or not during the tracking phase. This is done directly in the `.cao` model file. For example, the next example shows how
to set `plane_fuselage` as name for the cylinder used to model the plane fuselage and `right reactor` as name for the corresponding plane
reactor modeled as a circle:
\code
V1
# header
# load the different parts of the plane
load("wings.cao")
load("tailplane.cao")
# 3D points
5 # Number of points
16.9 0 0.5
-20 0 0.5
-3.4 14.6 1.1
-3.4 15.4 1.1
-3.4 14.6 1.8
# 3D lines
0
# Faces from 3D lines
0
# Faces from 3D points
0
# 3D cylinders
1 # Number of cylinders
0 1 2.4 name=plane_fuselage
# 3D circles
1 # Number of circles
0.8 2 4 3 name="right reactor"
\endcode
\note If the name contains space characters, it must be surrounded by quotes.
You can give a name to all the elements excepts for points.
\subsubsection mb_generic_advanced_transformation How to load cao model with transformation
In ViSP 3.2.1 we introduce the capability to load a `.cao` model with 3D translation and rotation. For the translation, values are expressed
in meters. For the rotation, the representation is the \f$\theta_u\f$ axis-angle implemented in vpThetaUVector class. Values can be
expressed in degrees or radians.
Let us model a square made with 4 lego 2x4 bricks as shown in the next immage.
\image html img-tracker-mb-model-lego-square.jpg
Instead of modeling all the 4 brick, we can just model one brick and use translation and rotation to model the others.
The `.cao` model of the 2x4 brick located in `./lego_parts/brick-2x4.cao` is the following:
\code
V1
#################################################################
# CAD model in cao format of a LEGO Element ID: 4211385 2x4 brick
# 2x4 brick size is 0.032m/0.016m/0.0096m
#################################################################
# 3D points
8 # Number of points (here 8 brick corners)
0.000 0.000 0.0000 # Point 0: front face bottom/left
0.032 0.000 0.0000 # Point 1: front face bottom/right
0.032 0.000 0.0096 # Point 2: front face top/right
0.000 0.000 0.0096 # Point 3: front face top/left
0.000 0.016 0.0000 # Point 4: rear face bottom/left
0.032 0.016 0.0000 # Point 5: rear face bottom/right
0.032 0.016 0.0096 # Point 6: rear face top/right
0.000 0.016 0.0096 # Point 7: rear face top/left
# 3D lines
0 # No 3D lines
# 3D faces from lines
0 # No 3D faces from lines
# 3D faces from points
6 # 6 faces to describe the brick
4 0 1 2 3 # Face 0: front face
4 3 2 6 7 # Face 1: top face
4 7 6 5 4 # Face 2: rear face
4 0 4 5 1 # Face 3: bottom face
4 0 3 7 4 # Face 4: left face
4 1 5 6 2 # Face 5: right face
# 3D cylinders
0
# 3D circle
0 # No 3D circle
\endcode
Now to model a square made with 4 bricks, we can reuse the same 2x4 brick model introducing translation and rotation.
The corresponding model `./lego-square.cao` is the following:
\code
V1
################################################
# Construct a square made with 4 2x4 lego bricks
# 2x4 brick size is 0.032m/0.016m/0.0096m
################################################
# lego 1: the white in the previous image
load("lego_parts/brick-2x4.cao")
# lego 2: the yellow one
load("lego_parts/brick-2x4.cao", t=[0.048; 0.0; 0.0], tu=[0; 0; 90 deg]) # 0.048=0.032+0.016
# lego 3: the gray one
load("lego_parts/brick-2x4.cao", t=[0.016; 0.032; 0.0])
# lego 4: the blue one
load("lego_parts/brick-2x4.cao", t=[0.016; 0.016; 0.0], tu=[0; 0; 1.57 rad])
###############################################
# 3D points
0 # No 3D points
# 3D lines
0 # No 3D lines
# 3D faces from lines
0 # No 3D faces from lines
# 3D faces from points
0 # No 3D faces from points
# 3D cylinders
0 # No 3D cylinders
# 3D circle
0 # No 3D circle
\endcode
The corresponding `./lego-square.init` file could contain the following coordinates of the points
\code
4
0.000 0.000 0.0096 # Point 1 corresponding to lego 1 front face top/left
0.032 0.000 0.0096 # Point 2 corresponding to lego 2 front face top/left
0.032 0.000 0.0000 # Point 3 corresponding to lego 2 front face bottom/left
0.032 0.016 0.0000 # Point 4 corresponding to lego 2 front face bottom/right
\endcode
\image html img-tracker-mb-model-lego-square-init.jpg
Now to see how to track this object you can jump to \ref mb_generic_use_case_lego_square section.
\subsubsection mb_generic_advanced_cao_lod How to tune the level of detail
As explained in section \ref mb_generic_advanced_lod the parameters of the lod can be set in the source code. They can also be set directly
in the configuration file or in the CAD model in cao format.
The following lines show the content of the configuration file :
\code
<?xml version="1.0"?>
<conf>
<lod>
<use_lod>1</use_lod>
<min_line_length_threshold>40</min_line_length_threshold>
<min_polygon_area_threshold>150</min_polygon_area_threshold>
</lod>
</conf>
\endcode
In CAD model file, you can specify the LOD settings to the desired elements :
\code
V1
# header
# load the different parts of the plane
load("wings.cao")
load("tailplane.cao")
# 3D points
5 # number of points
16.9 0 0.5
-20 0 0.5
-3.4 14.6 1.1
-3.4 15.4 1.1
-3.4 14.6 1.8
# 3D lines
0
# Faces from 3D lines
0
# Faces from 3D points
0
# 3D cylinders
1 # Number of cylinders
0 1 2.4 name=plane_fuselage useLod=true minLineLengthThreshold=100.0
# 3D circles
1 # Number of circles
0.8 2 4 3 name="right reactor" useLod=true minPolygonAreaThreshold=40.0
\endcode
\note The order you call the methods to load the configuration file and to load the CAD model in the code will modify the result of the
LOD parameters. Basically, the LOD settings expressed in configuration file will have effect on all the elements in the CAD model while
the LOD settings expressed in CAD model will be specific to an element. The natural order would be to load first the configuration file
and after the CAD model.
\subsection mb_generic_advanced_wrml CAD model in wrml format
\subsubsection mb_generic_advanced_wrml_nam How to set a name to a face
To exploit the name of a face in the code, see sections about \ref mb_generic_advanced_lod and \ref mb_generic_advanced_exclude.
When using a wrml file, names are associated with shapes. In the example below (the model of a teabox), as only one shape is defined,
all its faces will have the same name: "teabox_name".
\note If you want to set different names for different faces, you have to define them in different shapes.
\code
#VRML V2.0 utf8
DEF fst_0 Group {
children [
# Object "teabox"
DEF teabox_name Shape {
geometry DEF cube IndexedFaceSet {
coord Coordinate {
point [
0 0 0 ,
0 0 -0.08,
0.165 0 -0.08,
0.165 0 0 ,
0.165 0.068 0 ,
0.165 0.068 -0.08,
0 0.068 -0.08,
0 0.068 0 ]
}
coordIndex [
0,1,2,3,-1,
1,6,5,2,-1,
4,5,6,7,-1,
0,3,4,7,-1,
5,4,3,2,-1,
0,7,6,1,-1]}
}
]
}
\endcode
\subsection mb_generic_advanced_exclude How not to consider specific polygons
When using model-based trackers, it is possible to not consider edge, keypoint or depth features tracking for specific faces. To do so,
<b>the faces you want to consider must have a name</b> following \ref mb_generic_advanced_cao_nam.
If you want to enable (default behavior) or disable the edge tracking on specific face it can be done via:
\code
vpMbGenericTracker tracker;
tracker.setUseEdgeTracking("name of the face", boolean);
\endcode
If the boolean is set to `false`, the tracking of the edges of the faces that have the given name will be disable. If it is set to `true`
(default behavior), it will be enable.
As for the edge tracking, the same functionality is also available when using keypoints via:
\code
vpMbGenericTracker tracker;
tracker.setUseKltTracking("name of the face", boolean);
\endcode
For the depth feature, this functionality is also available via:
\code
vpMbGenericTracker tracker;
tracker.setUseDepthDenseTracking("name of the face", boolean);
\endcode
or
\code
vpMbGenericTracker tracker;
tracker.setUseDepthNormalTracking("name of the face", boolean);
\endcode
\subsection mb_generic_advanced_display How to save tracking results without vpDisplay
The classical way to save tracking results is to use vpDisplay::getImage() as in tutorial-export-image.cpp to exploit the display window
in order to get the image and all the drawings in overlay in a RGBa image and then to save the resulting image.
But on embedded systems, it is not always possible to open a display window with vpDisplayX, vpDisplayOpenCV or vpDisplayGDI to view
real-time tracking results. That's why we propose to use vpMbGenericTracker::getModelForDisplay() and
vpMbGenericTracker::getFeaturesForDisplay() in conjunction with vpImageDraw to draw tracking results directly in an image
that could be saved during tracking.
The following code from testGenericTracker.cpp shows how to draw the CAD model in an image named `resultsColor` or `resultsDepth`:
\snippet testGenericTracker.cpp Draw CAD model
There is also the possibility to draw the tracked features in the same images:
\snippet testGenericTracker.cpp Draw features
And then to save the images in a file:
\snippet testGenericTracker.cpp Save drawings
\subsection mb_generic_advanced_dof How to set which degree of freedom to consider
By default the model-based tracker estimates the 6 degrees of freedom (dof) of the pose [tx, ty, tz, rx, ry, rz].
In the particular case where the model is a circle or a cylinder, the tracker does not consider the degree of freedom that
it cannot estimate around the axis of symmetry or revolution of the object. Thus if the model consists of a circle of radius R defined
in the plane \f$Y_o = cst\f$, the estimated degrees of freedom in the object frame correspond to [tx, ty, tz, rx, 0, rz] .
Given your use case it could be useful to reduce the number of dof to consider.
For example, if your object is always parallel to the image plane, estimating only the translation can make the tracker more reliable.
In this case, you can use the following code to avoid estimating the rotation.
\code
vpMbGenericTracker tracker;
tracker.loadModel(...);
...
vpColVector dof_to_estimate({1, 1, 1, 0, 0, 0});
tracker.setEstimatedDoF(dof_to_estimate);
tracker.init(...);
\endcode
\section mb_generic_use_case Use case
Hereafter we provide the information to test the tracker with different objects.
\subsection mb_generic_use_case_teabox Test tracker on teabox model
Enter model-based tracker tutorial build folder:
\code
$ cd $VISP_WS/visp-build/tutorial/tracking/model-based/generic
\endcode
There is `tutorial-mb-generic-tracker-full` binary that corresponds to the build of tutorial-mb-generic-tracker-full.cpp example.
This example is an extension of tutorial-mb-generic-tracker.cpp that was explained in \ref mb_generic_started section.
to see the options that are available run:
\code
$ ./tutorial-mb-generic-tracker-full --help
\endcode
By default all the parameters are set to work with the teabox example. Just run the binary without option:
\code
$ ./tutorial-mb-generic-tracker-full
\endcode
You may also obtain the same results using:
\code
$ ./tutorial-mb-generic-tracker-full --video model/teabox/teabox.mpg --model model/teabox/teabox.cao
\endcode
\subsection mb_generic_use_case_cubesat Test tracker on CubeSAT satellite model
In http://visp-doc.inria.fr/download/mbt-model/cubesat.zip you will find the model data set (.obj, .cao, .init, .xml, .ppm) and a
video to test the \c CubeSAT object tracking. After unzip in a folder (let say \c /your-path-to-model) you may run the tracker
with something similar to:
\code
$ cd $VISP_WS
$ wget http://visp-doc.inria.fr/download/mbt-model/cubesat.zip
$ unzip ~/Downloads/mmicro.zip
$ cd $VISP_WS/visp-build/tutorial/tracking/model-based/generic
$ ./tutorial-mb-generic-tracker-full --video $VISP_WS/cubesat/video/00%2d.png --model $VISP_WS/cubesat/cubesat1b.cao
\endcode
You should be able to obtain these kind of results:
\htmlonly
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/i1zRGhZGpLk" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly
\subsection mb_generic_use_case_mmicro Test tracker on mmicro model
In http://visp-doc.inria.fr/download/mbt-model/mmicro.zip you will find the model data set (.cao, .wrl, .init, .xml, .ppm) and a video
to track the \c mmicro object. After unzip in a folder (let say `$VISP_WS`) you may run the tracker with something similar to:
\code
$ cd $VISP_WS
$ wget http://visp-doc.inria.fr/download/mbt-model/mmicro.zip
$ unzip ~/Downloads/mmicro.zip
$ cd $VISP_WS/visp-build/tutorial/tracking/model-based/generic
$ ./tutorial-mb-generic-tracker-full --video $VISP_WS/mmicro/video/mmicro00%2d.png --model $VISP_WS/mmicro/mmicro.cao
\endcode
You should be able to obtain these kind of results:
\htmlonly
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/UK10KMMJFCI" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly
\subsection mb_generic_use_case_lego_square Test tracker on lego model with a live camera
All the previous examples (teabox, CubeSAT, mmicro) were working with videos. We provide tutorial-mb-generic-tracker-live.cpp that allows
to use a camera in order to test the tracker live.
This example tries to use the first grabber that is available in the following list:
- vpV4l2Grabber
- vp1394TwoGrabber
- vp1394CMUGrabber
- vpFlyCaptureGrabber
- vpRealSense2
- cv::VideoCapture
By default, if you are on an Ubuntu like system that has `libv4l-dev` package installed, you should be able to grab images from a webcam
without modifying the code.
To select an other grabber that corresponds to your camera you have to uncomment some lines at the beginning of
tutorial-mb-generic-tracker-live.cpp tutorial:
\snippet tutorial-mb-generic-tracker-live.cpp Undef grabber
For example to force the usage of vpRealSense2 class that allows to grab images from an Intel Realsense device like D435 or SR300,
you should modify the code like:
\code
$ cd $VISP_WS/visp/tutorial/tracking/model-based/generic
$ gedit tutorial-mb-generic-tracker-live.cpp
#undef VISP_HAVE_V4L2
#undef VISP_HAVE_DC1394
#undef VISP_HAVE_CMU1394
#undef VISP_HAVE_FLYCAPTURE
//#undef VISP_HAVE_REALSENSE2
\endcode
Once modified, enter the build folder and build the tutorial:
\code
$ cd $VISP_WS/visp-build/tutorial/tracking/model-based/generic
$ make tutorial-mb-generic-tracker-live
\endcode
Let us now consider the object made with 4 lego 2x4 bricks described in \ref mb_generic_advanced_transformation.
Once build, to get the usage, run:
\code
$ ./tutorial-mb-generic-tracker-live --help
\endcode
To test the tracker on the lego-square object, run:
\code
$ ./tutorial-mb-generic-tracker-live --model model/lego-square/lego-square.cao
\endcode
You should be able to obtain these kind of results:
\htmlonly
<p align="center"><iframe width="560" height="315" src="https://www.youtube.com/embed/nFP_9sl09t8" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe></p>
\endhtmlonly
Now if the tracker is working, you can learn the object running:
\code
$ ./tutorial-mb-generic-tracker-live --model model/lego-square/lego-square.cao --learn
\endcode
Once initialized by 4 user clicks, use the left click to learn on one or two images and then the right click to quit. In the terminal you
should see printings like:
\code
...
Data learned
Data learned
Save learning from 2 images in file: learning/data-learned.bin
\endcode
You can now use this learning to automize tracker initialization with:
\code
$ ./tutorial-mb-generic-tracker-live --model model/lego-square/lego-square.cao --auto_init
\endcode
\section mb_generic_known_issues Known issues
\subsection mb_generic_known_issues_example_with_ogre Model-based trackers examples are not working with Ogre visibility check
If you run mbtEdgeTracking.cpp, mbtKltTracking.cpp or mbtEdgeKltTracking.cpp examples enabling Ogre visibility check (using "-o" option),
you may encounter the following issue:
\code
C:\> mbtEdgeTracking.exe -c -o
...
OGRE EXCEPTION(6:FileNotFoundException): Cannot locate resource VTFInstancing.cg in resource group General
...
*** Initializing OIS ***
\endcode
and then a wonderful runtime issue as in the next image:
\image html img-win8.1-msvc-mbtracker-ogre-issue.jpg
It means maybe that Ogre version is not compatible with DirectX 11. This can be checked adding "-w" option to the command line:
\code
C:\> mbtEdgeTracking.exe -c -o -w
\endcode
Now the binary should open the Ogre configuration window where you have to select "OpenGL Rendering Subsystem" instead of
"Direct3D11 Rendering Subsystem". Press then OK to continue and start the tracking of the cube.
\image html img-win8.1-msvc-mbtracker-ogre-opengl.jpg
\subsection mb_generic_known_issues_tutorial_with_ogre Model-based trackers tutorials are not working with Ogre visibility check
This issue is similar to \ref mb_generic_known_issues_example_with_ogre. It may occur with tutorial-mb-edge-tracker.cpp,
tutorial-mb-klt-tracker.cpp and tutorial-mb-hybrid-tracker.cpp. To make working the tutorials:
- modify the code like:
\code
tracker.setOgreVisibilityTest(true);
tracker.setOgreShowConfigDialog(true);
\endcode
- build the modified tutorial
- run the binary. Now the binary should open the Ogre configuration window where you have to select an Ogre renderer that is working on
your computer.
\image html img-win8.1-msvc-mbtracker-ogre-opengl.jpg
- Press then OK to continue and start the tracking of the object.
\section mb_generic_next Next tutorial
If you have a webcam, you are now ready to experiment the generic model-based tracker on a cube that has an AprilTag on one face
following \ref tutorial-tracking-mb-generic-apriltag-live.
There is also \ref tutorial-detection-object to learn how to initialize the tracker without user click, by learning the object to track
using keypoints when the object is textured. There is also \ref tutorial-tracking-mb-generic-stereo if you want to know how to extend the
tracker to use a stereo camera or \ref tutorial-tracking-mb-generic-rgbd if you want to extend the tracking by using depth as visual
features. There is also this other \ref tutorial-tracking-tt.
*/
|