Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
vpMbKltTracker.h
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Model based tracker using only KLT
32  */
33 
39 #ifndef _vpMbKltTracker_h_
40 #define _vpMbKltTracker_h_
41 
42 #include <visp3/core/vpConfig.h>
43 
44 #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
45 
46 #include <visp3/core/vpExponentialMap.h>
47 #include <visp3/core/vpMeterPixelConversion.h>
48 #include <visp3/core/vpPixelMeterConversion.h>
49 #include <visp3/core/vpSubColVector.h>
50 #include <visp3/core/vpSubMatrix.h>
51 #include <visp3/klt/vpKltOpencv.h>
52 #include <visp3/mbt/vpMbTracker.h>
53 #include <visp3/mbt/vpMbtDistanceCircle.h>
54 #include <visp3/mbt/vpMbtDistanceKltCylinder.h>
55 #include <visp3/mbt/vpMbtDistanceKltPoints.h>
56 #include <visp3/vision/vpHomography.h>
57 
58 BEGIN_VISP_NAMESPACE
218 class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker
219 {
220 protected:
222  cv::Mat cur;
224  vpHomogeneousMatrix c0Mo;
227  bool firstInitialisation;
229  unsigned int maskBorder;
232  double threshold_outlier;
235  double percentGood;
238  vpHomogeneousMatrix ctTc0;
240  vpKltOpencv tracker;
242  std::list<vpMbtDistanceKltPoints *> kltPolygons;
244  std::list<vpMbtDistanceKltCylinder *> kltCylinders;
246  std::list<vpMbtDistanceCircle *> circles_disp;
248  unsigned int m_nbInfos;
250  unsigned int m_nbFaceUsed;
252  vpMatrix m_L_klt;
254  vpColVector m_error_klt;
256  vpColVector m_w_klt;
258  vpColVector m_weightedError_klt;
260  vpRobust m_robust_klt;
262  std::vector<std::vector<double> > m_featuresToBeDisplayedKlt;
263 
264 public:
265  vpMbKltTracker();
266  virtual ~vpMbKltTracker();
267 
270 
271  void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, double r, const std::string &name = "");
272  virtual void display(const vpImage<unsigned char> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
273  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) VP_OVERRIDE;
274  virtual void display(const vpImage<vpRGBa> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
275  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) VP_OVERRIDE;
276 
278  virtual std::list<vpMbtDistanceCircle *> &getFeaturesCircle() { return circles_disp; }
280  virtual std::list<vpMbtDistanceKltCylinder *> &getFeaturesKltCylinder() { return kltCylinders; }
282  virtual std::list<vpMbtDistanceKltPoints *> &getFeaturesKlt() { return kltPolygons; }
283 
289  inline std::vector<cv::Point2f> getKltPoints() const { return tracker.getFeatures(); }
290 
291  std::vector<vpImagePoint> getKltImagePoints() const;
292 
293  std::map<int, vpImagePoint> getKltImagePointsWithId() const;
294 
300  inline vpKltOpencv getKltOpencv() const { return tracker; }
301 
307  inline unsigned int getKltMaskBorder() const { return maskBorder; }
308 
314  inline int getKltNbPoints() const { return tracker.getNbFeatures(); }
315 
322  inline double getKltThresholdAcceptation() const { return threshold_outlier; }
323 
324  virtual inline vpColVector getError() const VP_OVERRIDE { return m_error_klt; }
325 
326  virtual inline vpColVector getRobustWeights() const VP_OVERRIDE { return m_w_klt; }
327 
328  virtual std::vector<std::vector<double> > getModelForDisplay(unsigned int width, unsigned int height,
329  const vpHomogeneousMatrix &cMo,
330  const vpCameraParameters &cam,
331  bool displayFullModel = false) VP_OVERRIDE;
332 
333  virtual void loadConfigFile(const std::string &configFile, bool verbose = true) VP_OVERRIDE;
334 
335  virtual void reInitModel(const vpImage<unsigned char> &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo,
336  bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix());
337  void resetTracker() VP_OVERRIDE;
338 
339  void setCameraParameters(const vpCameraParameters &cam) VP_OVERRIDE;
340 
346  inline void setKltMaskBorder(const unsigned int &e)
347  {
348  maskBorder = e;
349  // if(useScanLine)
350  faces.getMbScanLineRenderer().setMaskBorder(maskBorder);
351  }
352 
353  virtual void setKltOpencv(const vpKltOpencv &t);
354 
360  inline void setKltThresholdAcceptation(double th) { threshold_outlier = th; }
361 
370  virtual void setOgreVisibilityTest(const bool &v) VP_OVERRIDE
371  {
373 #ifdef VISP_HAVE_OGRE
374  faces.getOgreContext()->setWindowName("MBT Klt");
375 #endif
376  }
377 
383  virtual void setScanLineVisibilityTest(const bool &v) VP_OVERRIDE
384  {
386 
387  for (std::list<vpMbtDistanceKltPoints *>::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it)
388  (*it)->useScanLine = v;
389  }
390 
391  virtual void setPose(const vpImage<unsigned char> &I, const vpHomogeneousMatrix &cdMo) VP_OVERRIDE;
392  virtual void setPose(const vpImage<vpRGBa> &I_color, const vpHomogeneousMatrix &cdMo) VP_OVERRIDE;
393 
400  virtual void setProjectionErrorComputation(const bool &flag) VP_OVERRIDE
401  {
402  if (flag)
403  std::cerr << "This option is not yet implemented in vpMbKltTracker, "
404  "projection error computation set to false."
405  << std::endl;
406  }
407 
408  void setUseKltTracking(const std::string &name, const bool &useKltTracking);
409 
410  virtual void testTracking() VP_OVERRIDE;
411  virtual void track(const vpImage<unsigned char> &I) VP_OVERRIDE;
412  virtual void track(const vpImage<vpRGBa> &I_color) VP_OVERRIDE;
413 
418 
425  /* VP_DEPRECATED */ inline unsigned int getMaskBorder() const { return maskBorder; }
426 
433  /* VP_DEPRECATED */ inline int getNbKltPoints() const { return tracker.getNbFeatures(); }
434 
442  /* VP_DEPRECATED */ inline double getThresholdAcceptation() const { return threshold_outlier; }
443 
449  /* VP_DEPRECATED */ inline void setMaskBorder(const unsigned int &e)
450  {
451  maskBorder = e;
452  // if(useScanLine)
453  faces.getMbScanLineRenderer().setMaskBorder(maskBorder);
454  }
455 
462  /* VP_DEPRECATED */ inline void setThresholdAcceptation(double th) { threshold_outlier = th; }
463 
465 
466 protected:
469  void computeVVS();
470  virtual void computeVVSInit() VP_OVERRIDE;
471  virtual void computeVVSInteractionMatrixAndResidu() VP_OVERRIDE;
472 
473  virtual std::vector<std::vector<double> > getFeaturesForDisplayKlt();
474 
475  virtual void init(const vpImage<unsigned char> &I) VP_OVERRIDE;
476  virtual void initFaceFromCorners(vpMbtPolygon &polygon) VP_OVERRIDE;
477  virtual void initFaceFromLines(vpMbtPolygon &polygon) VP_OVERRIDE;
478  virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name = "") VP_OVERRIDE;
479  virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name = "") VP_OVERRIDE;
480 
481  void preTracking(const vpImage<unsigned char> &I);
482  bool postTracking(const vpImage<unsigned char> &I, vpColVector &w);
483  virtual void reinit(const vpImage<unsigned char> &I);
484  virtual void setPose(const vpImage<unsigned char> *I, const vpImage<vpRGBa> *I_color,
485  const vpHomogeneousMatrix &cdMo);
487 };
488 END_VISP_NAMESPACE
489 #endif
490 #endif // VISP_HAVE_OPENCV
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
Class to define RGB colors available for display functionalities.
Definition: vpColor.h:157
Implementation of an homogeneous matrix and operations on such kind of matrices.
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Definition: vpKltOpencv.h:74
int getNbFeatures() const
Get the number of current features.
Definition: vpKltOpencv.h:198
std::vector< cv::Point2f > getFeatures() const
Get the list of current features.
Definition: vpKltOpencv.h:183
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Main methods for a model-based tracker.
Definition: vpMbTracker.h:107
virtual std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)=0
virtual vpColVector getError() const =0
virtual void setScanLineVisibilityTest(const bool &v)
Definition: vpMbTracker.h:610
virtual void setOgreVisibilityTest(const bool &v)
virtual vpColVector getRobustWeights() const =0
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)=0
virtual void setProjectionErrorComputation(const bool &flag)
Definition: vpMbTracker.h:587
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false)=0
virtual void computeVVSInit()=0
virtual void testTracking()=0
Manage a circle used in the model-based tracker.
Implementation of a polygon of the model used by the model-based tracker.
Definition: vpMbtPolygon.h:60
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
Definition: vpRGBa.h:65
Contains an M-estimator and various influence function.
Definition: vpRobust.h:84