Visual Servoing Platform  version 3.5.1 under development (2023-05-30)
vpMbKltTracker.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Model based tracker using only KLT
33  *
34  * Authors:
35  * Romain Tallonneau
36  * Aurelien Yol
37  *
38  *****************************************************************************/
44 #ifndef vpMbKltTracker_h
45 #define vpMbKltTracker_h
46 
47 #include <visp3/core/vpConfig.h>
48 
49 #if defined(VISP_HAVE_MODULE_KLT) && (defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100))
50 
51 #include <visp3/core/vpExponentialMap.h>
52 #include <visp3/core/vpMeterPixelConversion.h>
53 #include <visp3/core/vpPixelMeterConversion.h>
54 #include <visp3/core/vpSubColVector.h>
55 #include <visp3/core/vpSubMatrix.h>
56 #include <visp3/klt/vpKltOpencv.h>
57 #include <visp3/mbt/vpMbTracker.h>
58 #include <visp3/mbt/vpMbtDistanceCircle.h>
59 #include <visp3/mbt/vpMbtDistanceKltCylinder.h>
60 #include <visp3/mbt/vpMbtDistanceKltPoints.h>
61 #include <visp3/vision/vpHomography.h>
62 
210 class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker
211 {
212 protected:
214 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
215  cv::Mat cur;
216 #else
217  IplImage *cur;
218 #endif
225  unsigned int maskBorder;
231  double percentGood;
238  std::list<vpMbtDistanceKltPoints *> kltPolygons;
240  std::list<vpMbtDistanceKltCylinder *> kltCylinders;
242  std::list<vpMbtDistanceCircle *> circles_disp;
244  unsigned int m_nbInfos;
246  unsigned int m_nbFaceUsed;
258  std::vector<std::vector<double> > m_featuresToBeDisplayedKlt;
259 
260 public:
261  vpMbKltTracker();
262  virtual ~vpMbKltTracker();
263 
266 
267  void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, double r, const std::string &name = "");
268  virtual void display(const vpImage<unsigned char> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
269  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false);
270  virtual void display(const vpImage<vpRGBa> &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
271  const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false);
272 
274  virtual std::list<vpMbtDistanceCircle *> &getFeaturesCircle() { return circles_disp; }
276  virtual std::list<vpMbtDistanceKltCylinder *> &getFeaturesKltCylinder() { return kltCylinders; }
278  virtual std::list<vpMbtDistanceKltPoints *> &getFeaturesKlt() { return kltPolygons; }
279 
285 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
286  inline std::vector<cv::Point2f> getKltPoints() const { return tracker.getFeatures(); }
287 #else
288  inline CvPoint2D32f *getKltPoints() { return tracker.getFeatures(); }
289 #endif
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 { return m_error_klt; }
325 
326  virtual inline vpColVector getRobustWeights() const { 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);
332 
333  virtual void loadConfigFile(const std::string &configFile, bool verbose = true);
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();
338 
339  void setCameraParameters(const vpCameraParameters &cam);
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)
371  {
373 #ifdef VISP_HAVE_OGRE
374  faces.getOgreContext()->setWindowName("MBT Klt");
375 #endif
376  }
377 
383  virtual void setScanLineVisibilityTest(const bool &v)
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);
392  virtual void setPose(const vpImage<vpRGBa> &I_color, const vpHomogeneousMatrix &cdMo);
393 
400  virtual void setProjectionErrorComputation(const bool &flag)
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();
411  virtual void track(const vpImage<unsigned char> &I);
412  virtual void track(const vpImage<vpRGBa> &I_color);
413 
418 
425  /* vp_deprecated */ inline unsigned int getMaskBorder() const { return maskBorder; }
432  /* vp_deprecated */ inline int getNbKltPoints() const { return tracker.getNbFeatures(); }
433 
441  /* vp_deprecated */ inline double getThresholdAcceptation() const { return threshold_outlier; }
447  /* vp_deprecated */ inline void setMaskBorder(const unsigned int &e)
448  {
449  maskBorder = e;
450  // if(useScanLine)
451  faces.getMbScanLineRenderer().setMaskBorder(maskBorder);
452  }
453 
460  /* vp_deprecated */ inline void setThresholdAcceptation(double th) { threshold_outlier = th; }
461 
463 
464 protected:
467  void computeVVS();
468  virtual void computeVVSInit();
470 
471  virtual std::vector<std::vector<double> > getFeaturesForDisplayKlt();
472 
473  virtual void init(const vpImage<unsigned char> &I);
474  virtual void initFaceFromCorners(vpMbtPolygon &polygon);
475  virtual void initFaceFromLines(vpMbtPolygon &polygon);
476  virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name = "");
477  virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name = "");
478 
479  void preTracking(const vpImage<unsigned char> &I);
480  bool postTracking(const vpImage<unsigned char> &I, vpColVector &w);
481  virtual void reinit(const vpImage<unsigned char> &I);
482  virtual void setPose(const vpImage<unsigned char> *const I, const vpImage<vpRGBa> *const I_color,
483  const vpHomogeneousMatrix &cdMo);
485 };
486 
487 #endif
488 #endif // VISP_HAVE_OPENCV
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:172
Class to define RGB colors available for display functionnalities.
Definition: vpColor.h:158
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:79
int getNbFeatures() const
Get the number of current features.
Definition: vpKltOpencv.h:120
std::vector< cv::Point2f > getFeatures() const
Get the list of current features.
Definition: vpKltOpencv.h:105
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:154
Model based tracker using only KLT.
std::list< vpMbtDistanceKltCylinder * > kltCylinders
vpColVector m_error_klt
(s - s*)
vpHomogeneousMatrix c0Mo
Initial pose.
virtual void setScanLineVisibilityTest(const bool &v)
void setMaskBorder(const unsigned int &e)
vpHomogeneousMatrix ctTc0
std::list< vpMbtDistanceKltPoints * > kltPolygons
double getKltThresholdAcceptation() const
virtual std::list< vpMbtDistanceKltPoints * > & getFeaturesKlt()
cv::Mat cur
Temporary OpenCV image for fast conversion.
unsigned int getKltMaskBorder() const
virtual std::list< vpMbtDistanceCircle * > & getFeaturesCircle()
std::list< vpMbtDistanceCircle * > circles_disp
Vector of the circles used here only to display the full model.
vpColVector m_weightedError_klt
Weighted error.
vpKltOpencv tracker
Points tracker.
virtual void setProjectionErrorComputation(const bool &flag)
virtual std::list< vpMbtDistanceKltCylinder * > & getFeaturesKltCylinder()
double threshold_outlier
std::vector< cv::Point2f > getKltPoints() const
unsigned int m_nbInfos
unsigned int getMaskBorder() const
vpKltOpencv getKltOpencv() const
void setKltThresholdAcceptation(double th)
void setThresholdAcceptation(double th)
vpRobust m_robust_klt
Robust.
int getKltNbPoints() const
virtual void setOgreVisibilityTest(const bool &v)
double getThresholdAcceptation() const
virtual vpColVector getError() 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.
vpMatrix m_L_klt
Interaction matrix.
void setKltMaskBorder(const unsigned int &e)
int getNbKltPoints() const
virtual vpColVector getRobustWeights() const
Main methods for a model-based tracker.
Definition: vpMbTracker.h:105
virtual void track(const vpImage< unsigned char > &I)=0
virtual void resetTracker()=0
virtual void init(const vpImage< unsigned char > &I)=0
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 initFaceFromLines(vpMbtPolygon &polygon)=0
virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace=0, const std::string &name="")=0
virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace=0, const std::string &name="")=0
virtual void setCameraParameters(const vpCameraParameters &cam)
Definition: vpMbTracker.h:488
virtual void setScanLineVisibilityTest(const bool &v)
Definition: vpMbTracker.h:605
virtual void setOgreVisibilityTest(const bool &v)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)=0
virtual void computeVVSInteractionMatrixAndResidu()=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
virtual void initFaceFromCorners(vpMbtPolygon &polygon)=0
virtual void loadConfigFile(const std::string &configFile, bool verbose=true)
Implementation of a polygon of the model used by the model-based tracker.
Definition: vpMbtPolygon.h:67
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:82
Contains an M-estimator and various influence function.
Definition: vpRobust.h:89