Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
mbtKltTracking.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Example of MBT KLT Tracking.
33  *
34 *****************************************************************************/
35 
42 #include <iostream>
43 #include <visp3/core/vpConfig.h>
44 
45 #if defined(VISP_HAVE_MODULE_MBT) && defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && \
46  defined(VISP_HAVE_DISPLAY) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
47 
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpHomogeneousMatrix.h>
50 #include <visp3/core/vpIoTools.h>
51 #include <visp3/core/vpMath.h>
52 #include <visp3/gui/vpDisplayD3D.h>
53 #include <visp3/gui/vpDisplayGDI.h>
54 #include <visp3/gui/vpDisplayGTK.h>
55 #include <visp3/gui/vpDisplayOpenCV.h>
56 #include <visp3/gui/vpDisplayX.h>
57 #include <visp3/io/vpImageIo.h>
58 #include <visp3/io/vpParseArgv.h>
59 #include <visp3/io/vpVideoReader.h>
60 #include <visp3/mbt/vpMbKltTracker.h>
61 
62 #define GETOPTARGS "x:m:i:n:de:chtfolwv"
63 
64 #ifdef ENABLE_VISP_NAMESPACE
65 using namespace VISP_NAMESPACE_NAME;
66 #endif
67 
68 void usage(const char *name, const char *badparam)
69 {
70 #if VISP_HAVE_DATASET_VERSION >= 0x030600
71  std::string ext("png");
72 #else
73  std::string ext("pgm");
74 #endif
75  fprintf(stdout, "\n\
76 Example of tracking based on the 3D model.\n\
77 \n\
78 SYNOPSIS\n\
79  %s [-i <test image path>] [-x <config file>]\n\
80  [-m <model name>] [-n <initialisation file base name>] [-e <last frame index>]\n\
81  [-t] [-c] [-d] [-h] [-f] [-o] [-w] [-l] [-v]\n",
82  name);
83 
84  fprintf(stdout, "\n\
85 OPTIONS: \n\
86  -i <input image path> \n\
87  Set image input path.\n\
88  From this path read images \n\
89  \"mbt/cube/image%%04d.%s\". These \n\
90  images come from visp-images-x.y.z.tar.gz available \n\
91  on the ViSP website.\n\
92  Setting the VISP_INPUT_IMAGE_PATH environment\n\
93  variable produces the same behaviour than using\n\
94  this option.\n\
95 \n\
96  -x <config file> \n\
97  Set the config file (the xml file) to use.\n\
98  The config file is used to specify the parameters of the tracker.\n\
99 \n\
100  -m <model name> \n\
101  Specify the name of the file of the model\n\
102  The model can either be a vrml model (.wrl) or a .cao file.\n\
103 \n\
104  -e <last frame index> \n\
105  Specify the index of the last frame. Once reached, the tracking is stopped\n\
106 \n\
107  -f \n\
108  Do not use the vrml model, use the .cao one. These two models are \n\
109  equivalent and comes from ViSP-images-x.y.z.tar.gz available on the ViSP\n\
110  website. However, the .cao model allows to use the 3d model based tracker \n\
111  without Coin.\n\
112 \n\
113  -n <initialisation file base name> \n\
114  Base name of the initialisation file. The file will be 'base_name'.init .\n\
115  This base name is also used for the Optional picture specifying where to \n\
116  click (a .ppm picture).\n\
117 \n\
118  -t \n\
119  Turn off the display of the the klt points. \n\
120 \n\
121  -d \n\
122  Turn off the display.\n\
123 \n\
124  -c\n\
125  Disable the mouse click. Useful to automate the \n\
126  execution of this program without human intervention.\n\
127 \n\
128  -o\n\
129  Use Ogre3D for visibility tests\n\
130 \n\
131  -w\n\
132  When Ogre3D is enable [-o] show Ogre3D configuration dialog thatallows to set the renderer.\n\
133 \n\
134  -l\n\
135  Use the scanline for visibility tests.\n\
136 \n\
137  -v\n\
138  Compute covariance matrix.\n\
139 \n\
140  -h \n\
141  Print the help.\n\n",
142  ext.c_str());
143 
144  if (badparam)
145  fprintf(stdout, "\nERROR: Bad parameter [%s]\n", badparam);
146 }
147 
148 bool getOptions(int argc, const char **argv, std::string &ipath, std::string &configFile, std::string &modelFile,
149  std::string &initFile, long &lastFrame, bool &displayKltPoints, bool &click_allowed, bool &display,
150  bool &cao3DModel, bool &useOgre, bool &showOgreConfigDialog, bool &useScanline, bool &computeCovariance)
151 {
152  const char *optarg_;
153  int c;
154  while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
155 
156  switch (c) {
157  case 'e':
158  lastFrame = atol(optarg_);
159  break;
160  case 'i':
161  ipath = optarg_;
162  break;
163  case 'x':
164  configFile = optarg_;
165  break;
166  case 'm':
167  modelFile = optarg_;
168  break;
169  case 'n':
170  initFile = optarg_;
171  break;
172  case 't':
173  displayKltPoints = false;
174  break;
175  case 'f':
176  cao3DModel = true;
177  break;
178  case 'c':
179  click_allowed = false;
180  break;
181  case 'd':
182  display = false;
183  break;
184  case 'o':
185  useOgre = true;
186  break;
187  case 'l':
188  useScanline = true;
189  break;
190  case 'w':
191  showOgreConfigDialog = true;
192  break;
193  case 'v':
194  computeCovariance = true;
195  break;
196  case 'h':
197  usage(argv[0], nullptr);
198  return false;
199  break;
200 
201  default:
202  usage(argv[0], optarg_);
203  return false;
204  break;
205  }
206  }
207 
208  if ((c == 1) || (c == -1)) {
209  // standalone param or error
210  usage(argv[0], nullptr);
211  std::cerr << "ERROR: " << std::endl;
212  std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
213  return false;
214  }
215 
216  return true;
217 }
218 
219 int main(int argc, const char **argv)
220 {
221  try {
222  std::string env_ipath;
223  std::string opt_ipath;
224  std::string ipath;
225  std::string opt_configFile;
226  std::string configFile;
227  std::string opt_modelFile;
228  std::string modelFile;
229  std::string opt_initFile;
230  std::string initFile;
231  long opt_lastFrame = -1;
232  bool displayKltPoints = true;
233  bool opt_click_allowed = true;
234  bool opt_display = true;
235  bool cao3DModel = false;
236  bool useOgre = false;
237  bool showOgreConfigDialog = false;
238  bool useScanline = false;
239  bool computeCovariance = false;
240  bool quit = false;
241 
242 #if VISP_HAVE_DATASET_VERSION >= 0x030600
243  std::string ext("png");
244 #else
245  std::string ext("pgm");
246 #endif
247 
248  // Get the visp-images-data package path or VISP_INPUT_IMAGE_PATH
249  // environment variable value
250  env_ipath = vpIoTools::getViSPImagesDataPath();
251 
252  // Set the default input path
253  if (!env_ipath.empty())
254  ipath = env_ipath;
255 
256  // Read the command line options
257  if (!getOptions(argc, argv, opt_ipath, opt_configFile, opt_modelFile, opt_initFile, opt_lastFrame, displayKltPoints,
258  opt_click_allowed, opt_display, cao3DModel, useOgre, showOgreConfigDialog, useScanline,
259  computeCovariance)) {
260  return EXIT_FAILURE;
261  }
262 
263  // Test if an input path is set
264  if (opt_ipath.empty() && env_ipath.empty()) {
265  usage(argv[0], nullptr);
266  std::cerr << std::endl << "ERROR:" << std::endl;
267  std::cerr << " Use -i <visp image path> option or set VISP_INPUT_IMAGE_PATH " << std::endl
268  << " environment variable to specify the location of the " << std::endl
269  << " image path where test images are located." << std::endl
270  << std::endl;
271 
272  return EXIT_FAILURE;
273  }
274 
275  // Get the option values
276  if (!opt_ipath.empty())
277  ipath = vpIoTools::createFilePath(opt_ipath, "mbt/cube/image%04d." + ext);
278  else
279  ipath = vpIoTools::createFilePath(env_ipath, "mbt/cube/image%04d." + ext);
280 
281  if (!opt_configFile.empty())
282  configFile = opt_configFile;
283  else if (!opt_ipath.empty())
284  configFile = vpIoTools::createFilePath(opt_ipath, "mbt/cube.xml");
285  else
286  configFile = vpIoTools::createFilePath(env_ipath, "mbt/cube.xml");
287 
288  if (!opt_modelFile.empty()) {
289  modelFile = opt_modelFile;
290  }
291  else {
292  std::string modelFileCao = "mbt/cube.cao";
293  std::string modelFileWrl = "mbt/cube.wrl";
294 
295  if (!opt_ipath.empty()) {
296  if (cao3DModel) {
297  modelFile = vpIoTools::createFilePath(opt_ipath, modelFileCao);
298  }
299  else {
300 #ifdef VISP_HAVE_COIN3D
301  modelFile = vpIoTools::createFilePath(opt_ipath, modelFileWrl);
302 #else
303  std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl;
304  modelFile = vpIoTools::createFilePath(opt_ipath, modelFileCao);
305 #endif
306  }
307  }
308  else {
309  if (cao3DModel) {
310  modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao);
311  }
312  else {
313 #ifdef VISP_HAVE_COIN3D
314  modelFile = vpIoTools::createFilePath(env_ipath, modelFileWrl);
315 #else
316  std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl;
317  modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao);
318 #endif
319  }
320  }
321  }
322 
323  if (!opt_initFile.empty())
324  initFile = opt_initFile;
325  else if (!opt_ipath.empty())
326  initFile = vpIoTools::createFilePath(opt_ipath, "mbt/cube");
327  else
328  initFile = vpIoTools::createFilePath(env_ipath, "mbt/cube");
329 
331  vpVideoReader reader;
332 
333  reader.setFileName(ipath);
334  try {
335  reader.open(I);
336  }
337  catch (...) {
338  std::cout << "Cannot open sequence: " << ipath << std::endl;
339  return EXIT_FAILURE;
340  }
341 
342  if (opt_lastFrame > 1 && opt_lastFrame < reader.getLastFrameIndex())
343  reader.setLastFrameIndex(opt_lastFrame);
344 
345  reader.acquire(I);
346 
347 // initialise a display
348 #if defined(VISP_HAVE_X11)
349  vpDisplayX display;
350 #elif defined(VISP_HAVE_GDI)
351  vpDisplayGDI display;
352 #elif defined(HAVE_OPENCV_HIGHGUI)
353  vpDisplayOpenCV display;
354 #elif defined(VISP_HAVE_D3D9)
355  vpDisplayD3D display;
356 #elif defined(VISP_HAVE_GTK)
357  vpDisplayGTK display;
358 #else
359  opt_display = false;
360 #endif
361  if (opt_display) {
362 #if defined(VISP_HAVE_DISPLAY)
363  display.init(I, 100, 100, "Test tracking");
364 #endif
366  vpDisplay::flush(I);
367  }
368 
369  vpMbKltTracker tracker;
371 
372  // Load tracker config file (camera parameters and moving edge settings)
373  vpCameraParameters cam;
374 
375 #if defined(VISP_HAVE_PUGIXML)
376  // From the xml file
377  tracker.loadConfigFile(configFile);
378 #else
379  // Corresponding parameters manually set to have an example code
380  // By setting the parameters:
381  cam.initPersProjWithoutDistortion(547, 542, 338, 234);
382 
383  vpKltOpencv klt;
384  klt.setMaxFeatures(10000);
385  klt.setWindowSize(5);
386  klt.setQuality(0.01);
387  klt.setMinDistance(5);
388  klt.setHarrisFreeParameter(0.01);
389  klt.setBlockSize(3);
390  klt.setPyramidLevels(3);
391 
392  tracker.setCameraParameters(cam);
393  tracker.setKltOpencv(klt);
394  tracker.setKltMaskBorder(5);
395  tracker.setAngleAppear(vpMath::rad(65));
396  tracker.setAngleDisappear(vpMath::rad(75));
397 
398  // Specify the clipping to use
399  tracker.setNearClippingDistance(0.01);
400  tracker.setFarClippingDistance(0.90);
401  tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING);
402 // tracker.setClipping(tracker.getClipping() | vpMbtPolygon::LEFT_CLIPPING |
403 // vpMbtPolygon::RIGHT_CLIPPING | vpMbtPolygon::UP_CLIPPING |
404 // vpMbtPolygon::DOWN_CLIPPING); // Equivalent to FOV_CLIPPING
405 #endif
406 
407  // Display the klt points
408  tracker.setDisplayFeatures(displayKltPoints);
409 
410  // Tells if the tracker has to use Ogre3D for visibility tests
411  tracker.setOgreVisibilityTest(useOgre);
412  if (useOgre)
413  tracker.setOgreShowConfigDialog(showOgreConfigDialog);
414 
415  // Tells if the tracker has to use the scanline visibility tests
416  tracker.setScanLineVisibilityTest(useScanline);
417 
418  // Tells if the tracker has to compute the covariance matrix
419  tracker.setCovarianceComputation(computeCovariance);
420 
421  // Retrieve the camera parameters from the tracker
422  tracker.getCameraParameters(cam);
423 
424  // Loop to position the cube
425  if (opt_display && opt_click_allowed) {
426  while (!vpDisplay::getClick(I, false)) {
428  vpDisplay::displayText(I, 15, 10, "click after positioning the object", vpColor::red);
429  vpDisplay::flush(I);
430  }
431  }
432 
433  // Load the 3D model (either a vrml file or a .cao file)
434  tracker.loadModel(modelFile);
435 
436  // Initialise the tracker by clicking on the image
437  // This function looks for
438  // - a ./cube/cube.init file that defines the 3d coordinates (in meter,
439  // in the object basis) of the points used for the initialisation
440  // - a ./cube/cube.ppm file to display where the user have to click
441  // (Optional, set by the third parameter)
442  if (opt_display && opt_click_allowed) {
443  tracker.initClick(I, initFile, true);
444  tracker.getPose(cMo);
445  // display the 3D model at the given pose
446  tracker.display(I, cMo, cam, vpColor::red);
447  }
448  else {
449  vpHomogeneousMatrix cMoi(0.02044769891, 0.1101505452, 0.5078963719, 2.063603907, 1.110231561, -0.4392789872);
450  tracker.initFromPose(I, cMoi);
451  }
452 
453  // track the model
454  tracker.track(I);
455  tracker.getPose(cMo);
456 
457  if (opt_display)
458  vpDisplay::flush(I);
459 
460  while (!reader.end()) {
461  // acquire a new image
462  reader.acquire(I);
463  // display the image
464  if (opt_display)
466 
467  // Test to reset the tracker
468  if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 10) {
469  vpTRACE("Test reset tracker");
470  if (opt_display)
472  tracker.resetTracker();
473 
474 #if defined(VISP_HAVE_PUGIXML)
475  tracker.loadConfigFile(configFile);
476 #else
477  // Corresponding parameters manually set to have an example code
478  // By setting the parameters:
479  cam.initPersProjWithoutDistortion(547, 542, 338, 234);
480 
481  vpKltOpencv klt;
482  klt.setMaxFeatures(10000);
483  klt.setWindowSize(5);
484  klt.setQuality(0.01);
485  klt.setMinDistance(5);
486  klt.setHarrisFreeParameter(0.01);
487  klt.setBlockSize(3);
488  klt.setPyramidLevels(3);
489 
490  tracker.setCameraParameters(cam);
491  tracker.setKltOpencv(klt);
492  tracker.setKltMaskBorder(5);
493  tracker.setAngleAppear(vpMath::rad(65));
494  tracker.setAngleDisappear(vpMath::rad(75));
495 
496  // Specify the clipping to use
497  tracker.setNearClippingDistance(0.01);
498  tracker.setFarClippingDistance(0.90);
499  tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING);
500 // tracker.setClipping(tracker.getClipping() | vpMbtPolygon::LEFT_CLIPPING |
501 // vpMbtPolygon::RIGHT_CLIPPING | vpMbtPolygon::UP_CLIPPING |
502 // vpMbtPolygon::DOWN_CLIPPING); // Equivalent to FOV_CLIPPING
503 #endif
504  tracker.loadModel(modelFile);
505  tracker.setCameraParameters(cam);
506  tracker.setOgreVisibilityTest(useOgre);
507  tracker.setScanLineVisibilityTest(useScanline);
508  tracker.setCovarianceComputation(computeCovariance);
509  tracker.initFromPose(I, cMo);
510  }
511 
512  // Test to set an initial pose
513  if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) {
514  cMo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946);
515  vpTRACE("Test set pose");
516  tracker.setPose(I, cMo);
517  // if (opt_display) {
518  // // display the 3D model
519  // tracker.display(I, cMo, cam, vpColor::darkRed);
520  // // display the frame
521  // vpDisplay::displayFrame (I, cMo, cam, 0.05);
526  // }
527  }
528 
529  // track the object: stop tracking from frame 40 to 50
530  if (reader.getFrameIndex() - reader.getFirstFrameIndex() < 40 ||
531  reader.getFrameIndex() - reader.getFirstFrameIndex() >= 50) {
532  tracker.track(I);
533  tracker.getPose(cMo);
534  if (opt_display) {
535  // display the 3D model
536  tracker.display(I, cMo, cam, vpColor::darkRed);
537  // display the frame
538  vpDisplay::displayFrame(I, cMo, cam, 0.05);
539  }
540  }
541 
542  if (opt_click_allowed) {
543  vpDisplay::displayText(I, 10, 10, "Click to quit", vpColor::red);
544  if (vpDisplay::getClick(I, false)) {
545  quit = true;
546  break;
547  }
548  }
549 
550  if (computeCovariance) {
551  std::cout << "Covariance matrix: \n" << tracker.getCovarianceMatrix() << std::endl << std::endl;
552  }
553 
554  if (opt_display)
555  vpDisplay::flush(I);
556  }
557 
558  std::cout << "Reached last frame: " << reader.getFrameIndex() << std::endl;
559 
560  if (opt_click_allowed && !quit) {
562  }
563 
564  reader.close();
565 
566  return EXIT_SUCCESS;
567  }
568  catch (const vpException &e) {
569  std::cout << "Catch an exception: " << e << std::endl;
570  return EXIT_FAILURE;
571  }
572 }
573 
574 #else
575 
576 int main()
577 {
578  std::cout << "visp_mbt, visp_gui modules and OpenCV are required to run "
579  "this example."
580  << std::endl;
581  return EXIT_SUCCESS;
582 }
583 
584 #endif
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
static const vpColor red
Definition: vpColor.h:217
static const vpColor darkRed
Definition: vpColor.h:218
Display for windows using Direct3D 3rd party. Thus to enable this class Direct3D should be installed....
Definition: vpDisplayD3D.h:106
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:133
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static std::string getViSPImagesDataPath()
Definition: vpIoTools.cpp:1053
static std::string createFilePath(const std::string &parent, const std::string &child)
Definition: vpIoTools.cpp:1427
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Definition: vpKltOpencv.h:74
void setBlockSize(int blockSize)
Definition: vpKltOpencv.h:267
void setQuality(double qualityLevel)
Definition: vpKltOpencv.h:356
void setHarrisFreeParameter(double harris_k)
Definition: vpKltOpencv.h:275
void setMaxFeatures(int maxCount)
Definition: vpKltOpencv.h:315
void setMinDistance(double minDistance)
Definition: vpKltOpencv.h:324
void setWindowSize(int winSize)
Definition: vpKltOpencv.h:377
void setPyramidLevels(int pyrMaxLevel)
Definition: vpKltOpencv.h:343
static double rad(double deg)
Definition: vpMath.h:129
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:70
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
void acquire(vpImage< vpRGBa > &I)
void setLastFrameIndex(const long last_frame)
long getLastFrameIndex()
void open(vpImage< vpRGBa > &I)
void setFileName(const std::string &filename)
long getFirstFrameIndex()
long getFrameIndex() const