Visual Servoing Platform  version 3.6.1 under development (2025-03-11)
vpRBKltTracker.h
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 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 
35 #ifndef VP_RB_KLT_TRACKER_H
36 #define VP_RB_KLT_TRACKER_H
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #if (defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO))
41 #define VP_HAVE_RB_KLT_TRACKER
42 #endif
43 
44 #if defined(VP_HAVE_RB_KLT_TRACKER)
45 #include <visp3/rbt/vpRBFeatureTracker.h>
46 #include <visp3/core/vpPoint.h>
47 #include <visp3/core/vpTrackingException.h>
48 #include <visp3/core/vpRobust.h>
49 #include <visp3/klt/vpKltOpencv.h>
50 
51 #include <opencv2/core/mat.hpp>
52 
53 
54 BEGIN_VISP_NAMESPACE
55 
61 class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker
62 {
63 public:
65 
66  virtual ~vpRBKltTracker() = default;
67 
68  bool requiresRGB() const VP_OVERRIDE { return false; }
69 
70  bool requiresDepth() const VP_OVERRIDE { return false; }
71 
72  bool requiresSilhouetteCandidates() const VP_OVERRIDE { return false; }
73 
74  void onTrackingIterStart() VP_OVERRIDE { }
75 
76  void onTrackingIterEnd() VP_OVERRIDE { }
77 
78  void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
79 
80  void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
81 
82  void initVVS(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
83 
84  void computeVVSIter(const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration) VP_OVERRIDE;
85 
86  void display(const vpCameraParameters &cam, const vpImage<unsigned char> &I, const vpImage<vpRGBa> &IRGB, const vpImage<unsigned char> &depth) const VP_OVERRIDE;
87 
97  unsigned int getMinimumNumberOfPoints() const { return m_numPointsReinit; }
98  void setMinimumNumberOfPoints(unsigned int points) { m_numPointsReinit = points; }
99 
105  double getMinimumDistanceNewPoints() const { return m_newPointsDistanceThreshold; }
106  void setMinimumDistanceNewPoints(double distance) { m_newPointsDistanceThreshold = distance; }
107 
112  unsigned int getFilteringBorderSize() const { return m_border; }
113  void setFilteringBorderSize(unsigned int border) { m_border = border; }
114 
122  double getFilteringMaxReprojectionError() const { return m_maxErrorOutliersPixels; }
123  void setFilteringMaxReprojectionError(double maxError) { m_maxErrorOutliersPixels = maxError; }
124 
129  bool shouldUseMask() const { return m_useMask; }
130  void setShouldUseMask(bool useMask) { m_useMask = useMask; }
131 
137  float getMinimumMaskConfidence() const { return m_minMaskConfidence; }
138  void setMinimumMaskConfidence(float confidence)
139  {
140  if (confidence > 1.f || confidence < 0.f) {
141  throw vpException(vpException::badValue, "Mask confidence should be between 0 and 1");
142  }
143  m_minMaskConfidence = confidence;
144  }
145 
149  const vpKltOpencv &getKltTracker() const { return m_klt; }
155  vpKltOpencv &getKltTracker() { return m_klt; }
156 
157 #if defined(VISP_HAVE_NLOHMANN_JSON)
158  virtual void loadJsonConfiguration(const nlohmann::json &j) VP_OVERRIDE
159  {
161 
162  m_klt = j;
163 
164  setMinimumNumberOfPoints(j.value("minimumNumPoints", m_numPointsReinit));
165  setMinimumDistanceNewPoints(j.value("newPointsMinPixelDistance", m_newPointsDistanceThreshold));
166  setFilteringMaxReprojectionError(j.value("maxReprojectionErrorPixels", m_maxErrorOutliersPixels));
167  setShouldUseMask(j.value("useMask", m_useMask));
168  setMinimumMaskConfidence(j.value("minMaskConfidence", m_minMaskConfidence));
169  }
170 #endif
171 
177  {
178  public:
183 
185  {
186  const vpHomogeneousMatrix cinitTc = cTo0 * oMc;
187  return cinitTc.getThetaUVector().getTheta();
188  }
189 
190  inline double normalDotProd(const vpHomogeneousMatrix &cMo)
191  {
192  vpColVector cameraNormal = cMo.getRotationMatrix() * normal;
193  oX.changeFrame(cMo);
194  vpColVector dir({ -oX.get_X(), -oX.get_Y(), -oX.get_Z() });
195  dir.normalize();
196  return dir * cameraNormal;
197  }
198 
199  inline void update(const vpHomogeneousMatrix &cMo)
200  {
201  oX.changeFrame(cMo);
202  oX.projection();
203  }
204 
205  inline void error(vpColVector &e, unsigned i) const
206  {
207  e[i * 2] = oX.get_x() - currentPos.get_u();
208  e[i * 2 + 1] = oX.get_y() - currentPos.get_v();
209  }
210 
211  inline double distance(const vpTrackedKltPoint &other) const
212  {
213  const double d = sqrt(std::pow(oX.get_oX() - other.oX.get_oX(), 2) +
214  std::pow(oX.get_oY() - other.oX.get_oY(), 2) +
215  std::pow(oX.get_oZ() - other.oX.get_oZ(), 2));
216  return d;
217  }
218 
219  inline void interaction(vpMatrix &L, unsigned i) const
220  {
221  double x = oX.get_x(), y = oX.get_y();
222  double xy = x * y;
223  double Zinv = 1.0 / oX.get_Z();
224  L[i * 2][0] = -Zinv;
225  L[i * 2][1] = 0.0;
226  L[i * 2][2] = x * Zinv;
227  L[i * 2][3] = xy;
228  L[i * 2][4] = -(1.0 + x * x);
229  L[i * 2][5] = y;
230 
231  L[i * 2 + 1][0] = 0.0;
232  L[i * 2 + 1][1] = -Zinv;
233  L[i * 2 + 1][2] = y * Zinv;
234  L[i * 2 + 1][3] = 1.0 + y * y;
235  L[i * 2 + 1][4] = -xy;
236  L[i * 2 + 1][5] = -x;
237  }
238  };
239 
240 private:
241 
242  void tryAddNewPoint(const vpRBFeatureTrackerInput &frame, std::map<long, vpTrackedKltPoint> &points,
243  long id, const float u, const float v, const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &oMc);
244 
245  vpRobust m_robust;
246 
247  cv::Mat m_I, m_Iprev;
248  vpKltOpencv m_klt;
249 
250  unsigned int m_numPointsReinit;
251  double m_newPointsDistanceThreshold;
252  unsigned int m_border;
253 
254  double m_maxErrorOutliersPixels;
255 
256  std::map<long, vpTrackedKltPoint> m_points;
257 
258  bool m_useMask;
259  float m_minMaskConfidence;
260 
261 };
262 
263 END_VISP_NAMESPACE
264 
265 #endif
266 #endif
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpColVector & normalize()
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ badValue
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:73
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpRotationMatrix getRotationMatrix() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
double get_u() const
Definition: vpImagePoint.h:136
double get_v() const
Definition: vpImagePoint.h:147
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Definition: vpKltOpencv.h:79
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
double get_oX() const
Get the point oX coordinate in the object frame.
Definition: vpPoint.cpp:415
void projection(const vpColVector &_cP, vpColVector &_p) const VP_OVERRIDE
Definition: vpPoint.cpp:249
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.cpp:426
double get_Y() const
Get the point cY coordinate in the camera frame.
Definition: vpPoint.cpp:408
double get_oZ() const
Get the point oZ coordinate in the object frame.
Definition: vpPoint.cpp:419
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.cpp:424
double get_Z() const
Get the point cZ coordinate in the camera frame.
Definition: vpPoint.cpp:410
double get_oY() const
Get the point oY coordinate in the object frame.
Definition: vpPoint.cpp:417
void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const VP_OVERRIDE
Definition: vpPoint.cpp:270
double get_X() const
Get the point cX coordinate in the camera frame.
Definition: vpPoint.cpp:406
All the data related to a single tracking frame. This contains both the input data (from a real camer...
A base class for all features that can be used and tracked in the vpRBTracker.
virtual void loadJsonConfiguration(const nlohmann::json &j)
KLT-Based features.
bool shouldUseMask() const
Returns whether the tracking algorithm should filter out points that are unlikely to be on the object...
void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE
Extract features from the frame data and the current pose estimate.
void setMinimumMaskConfidence(float confidence)
void onTrackingIterEnd() VP_OVERRIDE
Method called after the tracking iteration has finished.
float getMinimumMaskConfidence() const
Returns the minimum mask confidence that a pixel should have if it should be kept during tracking.
void setFilteringBorderSize(unsigned int border)
virtual ~vpRBKltTracker()=default
double getMinimumDistanceNewPoints() const
Get the minimum distance that a candidate point should have to every other tracked point if it should...
vpKltOpencv & getKltTracker()
Get the underlying KLT tracker. Use this to modify its settings.
double getFilteringMaxReprojectionError() const
Get the maximum reprojection error, in pixels, for a point to be considered as outlier....
bool requiresRGB() const VP_OVERRIDE
Whether this tracker requires RGB image to extract features.
const vpKltOpencv & getKltTracker() const
Get the underlying KLT tracker. Use this to read its settings.
void setMinimumDistanceNewPoints(double distance)
unsigned int getFilteringBorderSize() const
Return the number of pixels in the image border where points should not be tracked....
bool requiresDepth() const VP_OVERRIDE
Whether this tracker requires depth image to extract features.
void setFilteringMaxReprojectionError(double maxError)
void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE
Track the features.
void setShouldUseMask(bool useMask)
unsigned int getMinimumNumberOfPoints() const
Get the minimum acceptable number of points that should be tracked. If KLT tracking has less than thi...
void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpImage< vpRGBa > &IRGB, const vpImage< unsigned char > &depth) const VP_OVERRIDE
virtual void loadJsonConfiguration(const nlohmann::json &j) VP_OVERRIDE
bool requiresSilhouetteCandidates() const VP_OVERRIDE
Whether this tracker requires Silhouette candidates.
void initVVS(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE
void computeVVSIter(const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration) VP_OVERRIDE
void setMinimumNumberOfPoints(unsigned int points)
void onTrackingIterStart() VP_OVERRIDE
Method called when starting a tracking iteration.
Contains an M-estimator and various influence function.
Definition: vpRobust.h:84
double getTheta() const
void interaction(vpMatrix &L, unsigned i) const
vpPoint oX
Initial pose of the object in the camera frame, acquired when the tracked point was first constructed...
double distance(const vpTrackedKltPoint &other) const
double rotationDifferenceToInitial(const vpHomogeneousMatrix &oMc)
Current image coordinates, in normalized image coordinates.
void update(const vpHomogeneousMatrix &cMo)
vpImagePoint currentPos
Surface normal at this point, in the object frame.
void error(vpColVector &e, unsigned i) const
vpColVector normal
Tracked 3D point.
double normalDotProd(const vpHomogeneousMatrix &cMo)