35 #ifndef VP_RB_KLT_TRACKER_H
36 #define VP_RB_KLT_TRACKER_H
38 #include <visp3/core/vpConfig.h>
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
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>
51 #include <opencv2/core/mat.hpp>
140 if (confidence > 1.f || confidence < 0.f) {
143 m_minMaskConfidence = confidence;
157 #if defined(VISP_HAVE_NLOHMANN_JSON)
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));
196 return dir * cameraNormal;
208 e[i * 2 + 1] = oX.
get_y() - currentPos.
get_v();
213 const double d = sqrt(std::pow(oX.
get_oX() - other.
oX.
get_oX(), 2) +
223 double Zinv = 1.0 / oX.
get_Z();
226 L[i * 2][2] = x * Zinv;
228 L[i * 2][4] = -(1.0 + x * x);
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;
247 cv::Mat m_I, m_Iprev;
250 unsigned int m_numPointsReinit;
251 double m_newPointsDistanceThreshold;
252 unsigned int m_border;
254 double m_maxErrorOutliersPixels;
256 std::map<long, vpTrackedKltPoint> m_points;
259 float m_minMaskConfidence;
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
vpColVector & normalize()
error that can be emitted by ViSP classes.
@ badValue
Used to indicate that a value is not in the allowed range.
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 ...
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Implementation of a matrix and operations on matrices.
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
double get_oX() const
Get the point oX coordinate in the object frame.
void projection(const vpColVector &_cP, vpColVector &_p) const VP_OVERRIDE
double get_y() const
Get the point y coordinate in the image plane.
double get_Y() const
Get the point cY coordinate in the camera frame.
double get_oZ() const
Get the point oZ coordinate in the object frame.
double get_x() const
Get the point x coordinate in the image plane.
double get_Z() const
Get the point cZ coordinate in the camera frame.
double get_oY() const
Get the point oY coordinate in the object frame.
void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const VP_OVERRIDE
double get_X() const
Get the point cX coordinate in the camera frame.
A base class for all features that can be used and tracked in the vpRBTracker.
virtual void loadJsonConfiguration(const nlohmann::json &j)
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.
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)