![]() |
Visual Servoing Platform version 3.7.0
|
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 [8]. 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.
To follow this tutorial depending on your interest you should be sure that ViSP was build with the following third-parties:
OpenCV: Useful if you want to investigate the KLT keypoint tracker implemented in vpMbKltTracker or its hybrid version vpMbEdgeKltTracker. We recommend to install OpenCV. This 3rd party may be also useful to consider input videos (mpeg, png, jpeg...).Ogre 3D: This 3rd party is optional and could be difficult to instal on OSX and Windows. To begin with the tracker we don't recommend to install it. Ogre 3D allows to enable Advanced visibility via Ogre3D.Coin 3D: This 3rd party is also optional and difficult to install. That's why we don't recommend to install Coin 3D to begin with the tracker. Coin 3D allows only to consider CAD model in wrml format instead of the home-made CAD model in cao format.Next sections highlight how to use the differents versions of the markerless model-based trackers that are implemented in ViSP.
Note that all the material (source code and videos) described in this tutorial is part of ViSP source code (in tutorial/tracking/model-based/old/generic folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/tracking/model-based/old/generic.
In ViSP, depending on the visual features that are used three trackers are available:
The following example that comes from tutorial-mb-tracker.cpp allows to track a tea box modeled in cao format using one of the markerless model-based tracker implemented in ViSP.
The previous example uses the following data as input:
"teabox.cao" is the default one. See Teabox CAD model section to learn how the teabox is modelled and section CAD model in cao format to learn how to model an other object.Once build, to see the options that are available in the previous source code, just run:
By default, teabox.mpg video and teabox.cao model are used as input. Using "--tracker" option, you can specify which tracker has to be used:
With this example it is also possible to work on an other data set using "--video" and "--model" command line options. For example, if you run:
it means that the following images will be used as input:
and that in <path2> you have the following data:
myobject.init: The coordinates of at least four 3D points used for the initialization.myobject.cao: The CAD model of the object to track.myobject.ppm: An optional image that shows where the user has to click the points defined in myobject.init.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 Tutorial: Camera intrinsic calibration). This file is handled in tutorial-mb-tracker-full.cpp but not in tutorial-mb-tracker.cpp. That's why since the video teabox.mpg was acquired by an other camera than yours, you have to set the camera intrinsic parameters in tutorial-mb-tracker.cpp source code modifying the line: "--model" command line option.Hereafter is the description of the some lines introduced in the previous example.
First we include the header of the hybrid tracker that includes internally vpMbEdgeTracker and vpMbKltTracker classes.
The tracker uses image I and the intrinsic camera parameters cam as input.
As output, it estimates cMo, the pose of the object in the camera frame.
Once input image teabox.pgm is loaded in I, a window is created and initialized with image I. Then we create an instance of the tracker depending on "--tracker" command line option.
Then the corresponding tracker settings are initialized. More details are given in Tracker settings section.
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 teabox.cao file which complete description is provided in teabox.cao example with:
It is also possible to modify the code to load the cad model in vrml format from teabox.wrl file described in teabox.wrl example. To this end modify the previous line with:
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:
Now we have to initialize the tracker. With the next line we choose to use a user interaction.
The user has to click in the image on four vertices with their 3D coordinates defined in the "teabox.init" file. The following image shows where the user has to click.
"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 "*.init" file except the extension that sould be ".ppm". In our case it will be "teabox.ppm".
The content of teabox.init file that defines 3D coordinates of some points of the model used during user intialization is provided hereafter. Note that all the characters after character '#' are considered as comments.
We give now the signification of each line of this file:
Here the user has to click on vertex 0, 3, 2 and 5 in the window that displays image I. From the 3D coordinates defined in 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.
Next, in the infinite while loop, after displaying the next image, we track the object on a new image I.
The result of the tracking is a pose cMo that can be obtained by:
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 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.
The last lines are here to free the memory allocated for the display and tracker:
ViSP supports two different ways to describe CAD models, either in cao or in vrml format.
.cao..wrl.The content of the file teabox.cao used in the getting started Example source code but also in tutorial-mb-edge-tracker.cpp and in tutorial-mb-hybrid-tracker.cpp examples is given here:
This file describes the model of the tea box corresponding to the next image:
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.
.cao fileThe content of the file teabox-triangle.cao used in the tutorial-mb-klt-tracker.cpp example is given here:
This file describes the model of the tea box corresponding to the next image:
Until line 15, the content of this file is similar to the one described in teabox.cao example. Line 17 we specify that the model contains 12 faces. Each face is then described as a triangle.
The content of the teabox.wrl file used in tutorial-mb-tracker-full.cpp and tutorial-mb-edge-tracker.cpp when teabox.cao is missing is given hereafter. This content is to make into relation with teabox.cao described in teabox.cao example. As for the cao format, teabox.wrl describes first the vertices of the box, then the edges that corresponds to the faces.
This file describes the model of the tea box corresponding to the next image:
We provide now a line by line description of the file where the faces of the box are defined from the vertices:
.wrl 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-tracker-full.cpp example, to read the parameters from an XML file, simply modify the code like:
The content of the XML file teabox.xml that is considered by default is the following:
Depending on the tracker all the XML tags are not useful:
<ecm> tag corresponds to the moving-edges settings. This tag is used by vpMbEdgeTracker and vpMbEdgeKltTracker.<klt> tag corresponds to the keypoint settings. This tag is used by vpMbKltTracker and vpMbEdgeKltTracker.<camera> and <face> tags are used by all the trackers.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:
of from source code using vpMbEdgeTracker::setMovingEdge() method:
Either from xml or from the previous source code you can set:
Keypoint settings affect tracking of keypoints on visible faces using KLT. These settings could be tuned either from XML using <klt> tag as:
of from source code using vpMbKltTracker::setKltOpencv() and vpMbKltTracker::setMaskBorder() methods:
With the previous parameters you can set:
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:
of from source code using vpMbTracker::setCameraParameters() method:
As described in vpCameraParameters class, these parameters correspond to
the ratio between the focal length and the size of a pixel, and
the coordinates of the principal point in pixel.
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.
Let us now highlight how the default visibility test works. As illustrated in the following figure, the angle
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.
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
, and the angle to determine if the face is disappearing
, a face will be considered as visible if
. We consider also that a new face is appearing if
. These two parameters can be set either in the XML file:
or in the code:
Here the face is considered as appearing if
degrees, and disappearing if
degrees.
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 (in addition to the previous test based on normals, i.e on the visible faces resulting from the previous test) another test which sets the faces that are partially occluded as non-visible. It can be enabled via:
When using the classical version of the ogre visibility test (which is the default behavior when activating this test), only one ray 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 between the ray and the axis-aligned bounding-box (AABB) 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).
Additionnaly, it is also possible to use a statistical approach during the ray tracing phase in order to improve the visibility results.
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 mbdep_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 mbdep_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 visibles, 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-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-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 oject to track is simple. @section mbdep_advanced Advanced @subsection mbdep_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 mbdep_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 mbdep_advanced_cao_nam. @subsection mbdep_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 mbdep_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 mbdep_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 mbdep_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 mbdep_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 modelling 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 mbdep_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 mbdep_advanced_lod and \ref mbdep_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 model file : @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 mbdep_advanced_cao_lod How to tune the level of detail As explained in section \ref mbdep_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 mbdep_advanced_wrml CAD model in wrml format @subsubsection mbdep_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 mbdep_advanced_lod and \ref mbdep_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 mbdep_advanced_exclude How not to consider specific polygons When using model-based trackers, it is possible not to consider edge tracking or keypoint tracking for specific faces. To do so, <b>the faces you want to consider must have a name</b>. If you want to enable (default behavior) or disable the edge tracking on specific face it can be done via: @code vpMbEdgeTracker::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 functionnality is also available when using keypoints via: @code vpMbKltTracker::setUseKltTracking("name of the face", boolean); \endcode @section mbdep_use_case Use case Hereafter we provide the information to test the tracker on more complex objects. Data-set could be found browsing http://visp-doc.inria.fr/download/mbt-model/ @subsection mbdep_use_case_cubesat 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 $ ./tutorial-mb-tracker-full --video /your-path-to-model/cubesat/video/00%2d.png --model /your-path-to-model/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" allowfullscreen></iframe></p> \endhtmlonly @subsection mbdep_use_case_mmicro 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 \c /your-path-to-model) you may run the tracker with something similar to: @code $ ./tutorial-mb-tracker-full --video /your-path-to-model/mmicro/video/mmicro00%2d.png --model /your-path-to-model/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" allowfullscreen></iframe></p> \endhtmlonly @section mbdep_known_issues Known issues @subsection mbdep_known_issues_example_with_ogre Model-based trackers examples are not working with Ogre visibility ckeck 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.
This issue is similar to Model-based trackers examples are not working with Ogre visibility ckeck. 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:
You are now ready to see the next Tutorial: Markerless generic model-based tracking using a color camera if you want to use the new version of this tracker or Tutorial: Template tracking.