Visual Servoing Platform  version 3.6.1 under development (2024-04-26)
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 
205 class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker
206 {
207 protected:
209  cv::Mat cur;
216  unsigned int maskBorder;
222  double percentGood;
229  std::list<vpMbtDistanceKltPoints *> kltPolygons;
231  std::list<vpMbtDistanceKltCylinder *> kltCylinders;
233  std::list<vpMbtDistanceCircle *> circles_disp;
235  unsigned int m_nbInfos;
237  unsigned int m_nbFaceUsed;
249  std::vector<std::vector<double> > m_featuresToBeDisplayedKlt;
250 
251 public:
252  vpMbKltTracker();
253  virtual ~vpMbKltTracker();
254 
257 
258  void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, double r, const std::string &name = "");
259  virtual void display(const vpImage<unsigned char> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
260  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override;
261  virtual void display(const vpImage<vpRGBa> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
262  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override;
263 
265  virtual std::list<vpMbtDistanceCircle *> &getFeaturesCircle() { return circles_disp; }
267  virtual std::list<vpMbtDistanceKltCylinder *> &getFeaturesKltCylinder() { return kltCylinders; }
269  virtual std::list<vpMbtDistanceKltPoints *> &getFeaturesKlt() { return kltPolygons; }
270 
276  inline std::vector<cv::Point2f> getKltPoints() const { return tracker.getFeatures(); }
277 
278  std::vector<vpImagePoint> getKltImagePoints() const;
279 
280  std::map<int, vpImagePoint> getKltImagePointsWithId() const;
281 
287  inline vpKltOpencv getKltOpencv() const { return tracker; }
288 
294  inline unsigned int getKltMaskBorder() const { return maskBorder; }
295 
301  inline int getKltNbPoints() const { return tracker.getNbFeatures(); }
302 
309  inline double getKltThresholdAcceptation() const { return threshold_outlier; }
310 
311  virtual inline vpColVector getError() const vp_override { return m_error_klt; }
312 
313  virtual inline vpColVector getRobustWeights() const vp_override { return m_w_klt; }
314 
315  virtual std::vector<std::vector<double> > getModelForDisplay(unsigned int width, unsigned int height,
316  const vpHomogeneousMatrix &cMo,
317  const vpCameraParameters &cam,
318  bool displayFullModel = false) vp_override;
319 
320  virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override;
321 
322  virtual void reInitModel(const vpImage<unsigned char> &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo,
323  bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix());
324  void resetTracker() vp_override;
325 
326  void setCameraParameters(const vpCameraParameters &cam) vp_override;
327 
333  inline void setKltMaskBorder(const unsigned int &e)
334  {
335  maskBorder = e;
336  // if(useScanLine)
337  faces.getMbScanLineRenderer().setMaskBorder(maskBorder);
338  }
339 
340  virtual void setKltOpencv(const vpKltOpencv &t);
341 
347  inline void setKltThresholdAcceptation(double th) { threshold_outlier = th; }
348 
357  virtual void setOgreVisibilityTest(const bool &v) vp_override
358  {
360 #ifdef VISP_HAVE_OGRE
361  faces.getOgreContext()->setWindowName("MBT Klt");
362 #endif
363  }
364 
370  virtual void setScanLineVisibilityTest(const bool &v) vp_override
371  {
373 
374  for (std::list<vpMbtDistanceKltPoints *>::const_iterator it = kltPolygons.begin(); it != kltPolygons.end(); ++it)
375  (*it)->useScanLine = v;
376  }
377 
378  virtual void setPose(const vpImage<unsigned char> &I, const vpHomogeneousMatrix &cdMo) vp_override;
379  virtual void setPose(const vpImage<vpRGBa> &I_color, const vpHomogeneousMatrix &cdMo) vp_override;
380 
387  virtual void setProjectionErrorComputation(const bool &flag) vp_override
388  {
389  if (flag)
390  std::cerr << "This option is not yet implemented in vpMbKltTracker, "
391  "projection error computation set to false."
392  << std::endl;
393  }
394 
395  void setUseKltTracking(const std::string &name, const bool &useKltTracking);
396 
397  virtual void testTracking() vp_override;
398  virtual void track(const vpImage<unsigned char> &I) vp_override;
399  virtual void track(const vpImage<vpRGBa> &I_color) vp_override;
400 
405 
412  /* vp_deprecated */ inline unsigned int getMaskBorder() const { return maskBorder; }
413 
420  /* vp_deprecated */ inline int getNbKltPoints() const { return tracker.getNbFeatures(); }
421 
429  /* vp_deprecated */ inline double getThresholdAcceptation() const { return threshold_outlier; }
430 
436  /* vp_deprecated */ inline void setMaskBorder(const unsigned int &e)
437  {
438  maskBorder = e;
439  // if(useScanLine)
440  faces.getMbScanLineRenderer().setMaskBorder(maskBorder);
441  }
442 
449  /* vp_deprecated */ inline void setThresholdAcceptation(double th) { threshold_outlier = th; }
450 
452 
453 protected:
456  void computeVVS();
457  virtual void computeVVSInit() vp_override;
458  virtual void computeVVSInteractionMatrixAndResidu() vp_override;
459 
460  virtual std::vector<std::vector<double> > getFeaturesForDisplayKlt();
461 
462  virtual void init(const vpImage<unsigned char> &I) vp_override;
463  virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override;
464  virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override;
465  virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name = "") vp_override;
466  virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name = "") vp_override;
467 
468  void preTracking(const vpImage<unsigned char> &I);
469  bool postTracking(const vpImage<unsigned char> &I, vpColVector &w);
470  virtual void reinit(const vpImage<unsigned char> &I);
471  virtual void setPose(const vpImage<unsigned char> *I, const vpImage<vpRGBa> *I_color,
472  const vpHomogeneousMatrix &cdMo);
474 };
475 
476 #endif
477 #endif // VISP_HAVE_OPENCV
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
Class to define RGB colors available for display functionalities.
Definition: vpColor.h:152
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:73
int getNbFeatures() const
Get the number of current features.
Definition: vpKltOpencv.h:197
std::vector< cv::Point2f > getFeatures() const
Get the list of current features.
Definition: vpKltOpencv.h:182
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:146
Model based tracker using only KLT.
std::list< vpMbtDistanceKltCylinder * > kltCylinders
vpColVector m_error_klt
(s - s*)
vpHomogeneousMatrix c0Mo
Initial pose.
void setMaskBorder(const unsigned int &e)
vpHomogeneousMatrix ctTc0
std::list< vpMbtDistanceKltPoints * > kltPolygons
double getKltThresholdAcceptation() const
virtual vpColVector getRobustWeights() const vp_override
virtual std::list< vpMbtDistanceKltPoints * > & getFeaturesKlt()
cv::Mat cur
Temporary OpenCV image for fast conversion.
unsigned int getKltMaskBorder() const
virtual void setProjectionErrorComputation(const bool &flag) vp_override
std::list< vpMbtDistanceCircle * > circles_disp
Vector of the circles used here only to display the full model.
vpColVector m_weightedError_klt
Weighted error.
virtual void setOgreVisibilityTest(const bool &v) vp_override
vpKltOpencv tracker
Points tracker.
virtual std::list< vpMbtDistanceKltCylinder * > & getFeaturesKltCylinder()
double threshold_outlier
std::vector< cv::Point2f > getKltPoints() const
unsigned int m_nbInfos
vpKltOpencv getKltOpencv() const
void setKltThresholdAcceptation(double th)
void setThresholdAcceptation(double th)
vpRobust m_robust_klt
Robust.
int getKltNbPoints() const
double getThresholdAcceptation() const
unsigned int maskBorder
Erosion of the mask.
unsigned int m_nbFaceUsed
vpColVector m_w_klt
Robust weights.
std::vector< std::vector< double > > m_featuresToBeDisplayedKlt
Display features.
virtual void setScanLineVisibilityTest(const bool &v) vp_override
vpMatrix m_L_klt
Interaction matrix.
virtual vpColVector getError() const vp_override
int getNbKltPoints() const
Main methods for a model-based tracker.
Definition: vpMbTracker.h:105
virtual std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)=0
virtual void setScanLineVisibilityTest(const bool &v)
Definition: vpMbTracker.h:608
virtual void setOgreVisibilityTest(const bool &v)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)=0
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:58
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:77
Definition: vpRGBa.h:61
Contains an M-estimator and various influence function.
Definition: vpRobust.h:83