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], [45]. 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 Tutorial: Markerless model-based tracking (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:
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) [8]. 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) [39]. 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.
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:
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...).
Ogre3D: 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. Ogre3D allows to enable Advanced visibility via Ogre3D.
Coin3D: This 3rd party is also optional and difficult to install. That's why we don't recommend to install Coin3D to begin with the tracker. Coin3D allows only to consider CAD model in wrml format instead of the home-made CAD model in cao format.
Input images data
For classical features working on grayscale image, you have to use the following data type:
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.
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.
a cad model that describes the object to track. In our case the file teabox.cao is the default one. See Tracker CAD model section to learn how the teabox is modeled and section CAD model in cao format 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 Initialization by user click 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 Initialization by user click section.
As an output the tracker provides the pose 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.
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.
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.
Running the example
Once build, to see the options that are available in the previous source code, just run:
By default, model/teabox/teabox.mpg video and model/teabox/teabox.cao model are used as input. Using "--tracker" option, you can specify which tracker has to be used:
Using "--tracker 0" to track only moving-edges:
$ ./tutorial-mb-generic-tracker --tracker 0
will produce results similar to:
Using "--tracker 1" to track only keypoints:
$ ./tutorial-mb-generic-tracker --tracker 1
will produce results similar to:
Using "--tracker 2" to track moving-edges and keypoints in an hybrid scheme:
$ ./tutorial-mb-generic-tracker --tracker 2
will produce results similar to:
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:
<path1>/myvideo0001.png
<path1>/myvideo0002.png
...
<path1>/myvideo0009.png
<path1>/myvideo0010.png
...
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. Supported image format are png, ppm, png, jpeg.
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.
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:
tracker->loadModel(objectname + ".wrl");
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:
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:
delete display;
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.
18 4 0 1 2 3 # Face 0: [number of points] [index of the 3D points]...
19 4 1 6 5 2
20 4 4 5 6 7
21 4 0 3 4 7
22 4 5 4 3 2
23 4 0 7 6 1 # Face 5
24 # 3D cylinders
25 0 # Number of cylinders
26 # 3D circles
27 0 # Number of circles
This file describes the model of the tea box corresponding to the next image:
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 .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.
18 3 0 1 2 # Face 0: [number of points] [index of the 3D points]...
19 3 0 2 3
20 3 0 3 7
21 3 3 4 7
22 3 4 5 6
23 3 4 6 7
24 3 1 6 5
25 3 1 5 2
26 3 5 3 2
27 3 5 4 3
28 3 7 6 1
29 3 7 1 0 # Face 11
30 # 3D cylinders
31 0 # Number of cylinders
32 # 3D circles
33 0 # Number of circles
This file describes the model of the tea box corresponding to the next image:
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 teabox.cao example. 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.
teabox.wrl example
The content of the teabox.wrl file used in tutorial-mb-generic-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.
1 #VRML V2.0 utf8
2
3 DEF fst_0 Group {
4 children [
5
6 # Object "teabox"
7 Shape {
8
9 geometry DEF cube IndexedFaceSet {
10
11 coord Coordinate {
12 point [
13 0 0 0 ,
14 0 0 -0.08,
15 0.165 0 -0.08,
16 0.165 0 0 ,
17 0.165 0.068 0 ,
18 0.165 0.068 -0.08,
19 0 0.068 -0.08,
20 0 0.068 0 ]
21 }
22
23 coordIndex [
24 0,1,2,3,-1,
25 1,6,5,2,-1,
26 4,5,6,7,-1,
27 0,3,4,7,-1,
28 5,4,3,2,-1,
29 0,7,6,1,-1]}
30 }
31
32 ]
33 }
This file describes the model of the tea box corresponding to the next image:
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 .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.
Tracker initialization
There are two ways to initialize the tracker, either by user interaction, either using an initial pose provided by a specific algorithm.
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.
The previous line of code, loads a file named "<objectname>.init" and waits for user click. When an image named "<objectname>.ppm" exists besides "<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 "teabox.init" file. The following image "teabox.ppm" shows where the user has to click.
Image "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 should 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 initialization is provided hereafter. Note that all the characters after character '#' are considered as comments.
1 4 # Number of points
2 0 0 0 # Point 0
3 0.165 0 0 # Point 3
4 0.165 0 -0.08 # Point 2
5 0.165 0.068 -0.08 # Point 5
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 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.
How to choose good points for manual initialization
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.
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.
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:
Either from xml or from the previous source code you can set:
mask_size: defines the size of the convolution mask used to detect an edge.
nb_mask: 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 2deg, then there are 360/2 = 180 masks.
range_tracking: 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.
edge_threshold: likelihood threshold used to determined if the moving edge is valid or not.
mu1: minimum image contrast allowed to detect a contour.
mu2: maximum image contrast allowed to detect a contour.
sample_step: 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 range_tracking and sample_step.
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:
mask_border: erosion number of the mask used on each face.
max_features: maximum number of keypoint features to track in the image.
window_size: window size used to refine the corner locations.
quality: 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: minimal Euclidean distance between detected corners during keypoint detection stage used to initialize keypoint location.
harris: free parameter of the Harris detector.
size_block: size of the averaging block used to track the keypoint features.
pyramid_lvl: maximal pyramid level. If the level is zero, then no pyramid is computed for the optical flow.
Note
Most important parameters are min_distance and quality.
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:
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.
Default visibility based on normals
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.
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 , 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:
Here the face is considered as appearing if degrees, and disappearing if degrees.
Note
When these two angle parameters are not set, their default values set to 89 degrees are used.
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 (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).
Additionally, it is also possible to use a statistical approach during the ray tracing phase in order to improve the visibility results.
Ogre visibility test on the first polygon, using a statistical approach.
Contrary to the classical version of this test, the statistical approach uses multiple rays per polygons (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 polygon based approach 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:
Contrary to the visibility test using Ogre3D, this method does not require any additional third-party library. As for the advanced visibility using Ogre3D, 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. This test is based on the scanline rendering algorithm and can be enabled via:
Even if this approach requires a bit more computing power, it is a pixel perfect visibility test. According to the camera point of view, polygons will be decomposed in order to consider only their visible parts. 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.
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.
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:
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:
It is also possible to enable them in the XML file. This is done with the following lines:
<conf>
...
<face>
...
<near_clipping>0.1</near_clipping>
<far_clipping>100.0</far_clipping>
<fov_clipping>0</fov_clipping>
</face>
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.
Advanced
How to detect tracking failures
The first way to detect a tracking failure is to catch potential internal exceptions returned by the tracker:
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.
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:
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:
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 :
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
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.
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
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.
Example of a cylinder.
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
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.
Example of a circle.
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]
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:
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.
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.
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
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).
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:
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"
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.
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 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.
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:
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
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:
As explained in section Level of detail (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 :
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.
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.
#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]}
}
]
}
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, the faces you want to consider must have a name following How to set a name to a face.
If you want to enable (default behavior) or disable the edge tracking on specific face it can be done via:
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:
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.
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 , 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.
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 CubeSAT object tracking. After unzip in a folder (let say /your-path-to-model) you may run the tracker with something similar to:
You should be able to obtain these kind of results:
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 mmicro object. After unzip in a folder (let say $VISP_WS) you may run the tracker with something similar to:
You should be able to obtain these kind of results:
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:
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:
// #undef VISP_HAVE_V4L2
// #undef VISP_HAVE_DC1394
// #undef VISP_HAVE_CMU1394
// #undef VISP_HAVE_FLYCAPTURE
// #undef VISP_HAVE_REALSENSE2
// #undef VISP_HAVE_OPENCV
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:
$ 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
Once modified, enter the build folder and build the tutorial:
$ cd $VISP_WS/visp-build/tutorial/tracking/model-based/generic
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:
...
Data learned
Data learned
Save learning from 2 images in file: learning/data-learned.bin
You can now use this learning to automize tracker initialization with:
OGRE EXCEPTION(6:FileNotFoundException): Cannot locate resource VTFInstancing.cg in resource group General
...
Initializing OIS ***
and then a wonderful runtime issue as in the next image:
It means maybe that Ogre version is not compatible with DirectX 11. This can be checked adding "-w" option to the command line:
C:\> mbtEdgeTracking.exe -c -o -w
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.
Model-based trackers tutorials are not working with Ogre visibility check