Visual Servoing Platform  version 3.0.0

#include <visp3/klt/vpKltOpencv.h>

Public Member Functions

 vpKltOpencv ()
 
 vpKltOpencv (const vpKltOpencv &copy)
 
virtual ~vpKltOpencv ()
 
void addFeature (const float &x, const float &y)
 
void addFeature (const long &id, const float &x, const float &y)
 
void addFeature (const cv::Point2f &f)
 
void display (const vpImage< unsigned char > &I, const vpColor &color=vpColor::red, unsigned int thickness=1)
 
int getBlockSize () const
 
void getFeature (const int &index, int &id, float &x, float &y) const
 
std::vector< cv::Point2f > getFeatures () const
 
std::vector< long > getFeaturesId () const
 
double getHarrisFreeParameter () const
 
int getMaxFeatures () const
 
double getMinDistance () const
 
int getNbFeatures () const
 
int getNbPrevFeatures () const
 
std::vector< cv::Point2f > getPrevFeatures () const
 
int getPyramidLevels () const
 
double getQuality () const
 
int getWindowSize () const
 
void initTracking (const cv::Mat &I, const cv::Mat &mask=cv::Mat())
 
void initTracking (const cv::Mat &I, const std::vector< cv::Point2f > &pts)
 
void initTracking (const cv::Mat &I, const std::vector< cv::Point2f > &pts, const std::vector< long > &ids)
 
vpKltOpencvoperator= (const vpKltOpencv &copy)
 
void track (const cv::Mat &I)
 
void setBlockSize (const int blockSize)
 
void setHarrisFreeParameter (double harris_k)
 
void setInitialGuess (const std::vector< cv::Point2f > &guess_pts)
 
void setInitialGuess (const std::vector< cv::Point2f > &init_pts, const std::vector< cv::Point2f > &guess_pts, const std::vector< long > &fid)
 
void setMaxFeatures (const int maxCount)
 
void setMinDistance (double minDistance)
 
void setMinEigThreshold (double minEigThreshold)
 
void setPyramidLevels (const int pyrMaxLevel)
 
void setQuality (double qualityLevel)
 
void setTrackerId (int tid)
 
void setUseHarris (const int useHarrisDetector)
 
void setWindowSize (const int winSize)
 
void suppressFeature (const int &index)
 

Static Public Member Functions

static void display (const vpImage< unsigned char > &I, const std::vector< cv::Point2f > &features, const vpColor &color=vpColor::green, unsigned int thickness=1)
 
static void display (const vpImage< vpRGBa > &I, const std::vector< cv::Point2f > &features, const vpColor &color=vpColor::green, unsigned int thickness=1)
 
static void display (const vpImage< unsigned char > &I, const std::vector< cv::Point2f > &features, const std::vector< long > &featuresid, const vpColor &color=vpColor::green, unsigned int thickness=1)
 
static void display (const vpImage< vpRGBa > &I, const std::vector< cv::Point2f > &features, const std::vector< long > &featuresid, const vpColor &color=vpColor::green, unsigned int thickness=1)
 

Protected Attributes

cv::Mat m_gray
 
cv::Mat m_prevGray
 
std::vector< cv::Point2f > m_points [2]
 
std::vector< long > m_points_id
 
int m_maxCount
 
cv::TermCriteria m_termcrit
 
int m_winSize
 
double m_qualityLevel
 
double m_minDistance
 
double m_minEigThreshold
 
double m_harris_k
 
int m_blockSize
 
int m_useHarrisDetector
 
int m_pyrMaxLevel
 
long m_next_points_id
 
bool m_initial_guess
 

Detailed Description

Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV.

The following example available in tutorial-klt-tracker.cpp shows how to use the main functions of the class.

#include <visp3/core/vpImageConvert.h>
#include <visp3/klt/vpKltOpencv.h>
#include <visp3/gui/vpDisplayOpenCV.h>
#include <visp3/io/vpVideoReader.h>
int main(int argc, const char *argv[])
{
#ifdef VISP_HAVE_OPENCV
try {
bool opt_init_by_click = false;
for (int i=0; i<argc; i++) {
if (std::string(argv[i]) == "--init-by-click")
opt_init_by_click = true;
else if (std::string(argv[i]) == "--help") {
std::cout << "Usage: " << argv[0] << " [--init-by-click] [--help]" << std::endl;
return 0;
}
}
vpVideoReader reader;
reader.setFileName("video-postcard.mpeg");
reader.acquire(I);
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
IplImage * cvI = NULL;
#else
cv::Mat cvI;
#endif
vpDisplayOpenCV d(I, 0, 0, "Klt tracking");
vpKltOpencv tracker;
tracker.setMaxFeatures(200);
tracker.setWindowSize(10);
tracker.setQuality(0.01);
tracker.setMinDistance(15);
tracker.setHarrisFreeParameter(0.04);
tracker.setBlockSize(9);
tracker.setUseHarris(1);
tracker.setPyramidLevels(3);
// Initialise the tracking
if (opt_init_by_click) {
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
std::vector<CvPoint2D32f> feature;
#else
std::vector<cv::Point2f> feature;
#endif
do {
"Left click to select a point, right to start tracking",
if (vpDisplay::getClick(I, ip, button, false)) {
if (button == vpMouseButton::button1) {
feature.push_back(cv::Point2f((float)ip.get_u(), (float)ip.get_v()));
}
}
} while(button != vpMouseButton::button3);
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
tracker.initTracking(cvI, &feature[0], feature.size());
#else
tracker.initTracking(cvI, feature);
#endif
}
else {
tracker.initTracking(cvI);
}
std::cout << "Tracker initialized with " << tracker.getNbFeatures() << " features" << std::endl;
while ( ! reader.end() )
{
reader.acquire(I);
if (opt_init_by_click && reader.getFrameIndex() == reader.getFirstFrameIndex() + 20) {
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
std::vector<CvPoint2D32f> feature;
#else
std::vector<cv::Point2f> feature;
#endif
do {
"Left click to select a point, right to start tracking",
if (vpDisplay::getClick(I, ip, button, false)) {
if (button == vpMouseButton::button1) {
feature.push_back(cv::Point2f((float)ip.get_u(), (float)ip.get_v()));
}
}
} while(button != vpMouseButton::button3);
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
tracker.initTracking(cvI, &feature[0], feature.size());
#else
tracker.initTracking(cvI, feature);
#endif
}
tracker.track(cvI);
tracker.display(I, vpColor::red);
}
#if (VISP_HAVE_OPENCV_VERSION < 0x020408)
cvReleaseImage(&cvI);
#endif
return 0;
}
catch(vpException e) {
std::cout << "Catch an exception: " << e << std::endl;
}
#else
(void)argc;
(void)argv;
#endif
}

A line by line explanation is provided in Tutorial: Keypoint tracking.

Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 75 of file vpKltOpencv.h.

Constructor & Destructor Documentation

vpKltOpencv::vpKltOpencv ( )

Default constructor.

Definition at line 60 of file vpKltOpencv.cpp.

References m_termcrit.

vpKltOpencv::vpKltOpencv ( const vpKltOpencv copy)

Copy constructor.

Definition at line 72 of file vpKltOpencv.cpp.

vpKltOpencv::~vpKltOpencv ( )
virtual

Definition at line 106 of file vpKltOpencv.cpp.

Member Function Documentation

void vpKltOpencv::addFeature ( const float &  x,
const float &  y 
)

Add a keypoint at the end of the feature list. The id of the feature is set to ensure that it is unique.

Parameters
x,y: Coordinates of the feature in the image.
Examples:
tutorial-klt-tracker-with-reinit.cpp.

Definition at line 536 of file vpKltOpencv.cpp.

References m_next_points_id, m_points, and m_points_id.

void vpKltOpencv::addFeature ( const long &  id,
const float &  x,
const float &  y 
)

Add a keypoint at the end of the feature list.

Warning
This function doesn't ensure that the id of the feature is unique. You should rather use addFeature(const float &, const float &) or addFeature(const cv::Point2f &).
Parameters
id: Feature id. Should be unique
x,y: Coordinates of the feature in the image.

Definition at line 554 of file vpKltOpencv.cpp.

References m_next_points_id, m_points, and m_points_id.

void vpKltOpencv::addFeature ( const cv::Point2f &  f)

Add a keypoint at the end of the feature list. The id of the feature is set to ensure that it is unique.

Parameters
f: Coordinates of the feature in the image.

Definition at line 569 of file vpKltOpencv.cpp.

References m_next_points_id, m_points, and m_points_id.

void vpKltOpencv::display ( const vpImage< unsigned char > &  I,
const vpColor color = vpColor::red,
unsigned int  thickness = 1 
)

Display features position and id.

Parameters
I: Image used as background. Display should be initialized on it.
color: Color used to display the features.
thickness: Thickness of the drawings.
Examples:
trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, and tutorial-klt-tracker.cpp.

Definition at line 219 of file vpKltOpencv.cpp.

References m_points, and m_points_id.

void vpKltOpencv::display ( const vpImage< unsigned char > &  I,
const std::vector< cv::Point2f > &  features,
const vpColor color = vpColor::green,
unsigned int  thickness = 1 
)
static

Display features list.

Parameters
I: The image used as background.
features: Vector of features.
color: Color used to display the points.
thickness: Thickness of the points.

Definition at line 237 of file vpKltOpencv.cpp.

References vpDisplay::displayCross(), vpMath::round(), vpImagePoint::set_u(), and vpImagePoint::set_v().

void vpKltOpencv::display ( const vpImage< vpRGBa > &  I,
const std::vector< cv::Point2f > &  features,
const vpColor color = vpColor::green,
unsigned int  thickness = 1 
)
static

Display features list.

Parameters
I: The image used as background.
features: Vector of features.
color: Color used to display the points.
thickness: Thickness of the points.

Definition at line 260 of file vpKltOpencv.cpp.

References vpDisplay::displayCross(), vpMath::round(), vpImagePoint::set_u(), and vpImagePoint::set_v().

void vpKltOpencv::display ( const vpImage< unsigned char > &  I,
const std::vector< cv::Point2f > &  features,
const std::vector< long > &  featuresid,
const vpColor color = vpColor::green,
unsigned int  thickness = 1 
)
static

Display features list with ids.

Parameters
I: The image used as background.
features: Vector of features.
featuresid: Vector of ids corresponding to the features.
color: Color used to display the points.
thickness: Thickness of the points

Definition at line 285 of file vpKltOpencv.cpp.

References vpDisplay::displayCross(), vpDisplay::displayText(), vpMath::round(), vpImagePoint::set_u(), and vpImagePoint::set_v().

void vpKltOpencv::display ( const vpImage< vpRGBa > &  I,
const std::vector< cv::Point2f > &  features,
const std::vector< long > &  featuresid,
const vpColor color = vpColor::green,
unsigned int  thickness = 1 
)
static

Display features list with ids.

Parameters
I: The image used as background.
features: Vector of features.
featuresid: Vector of ids corresponding to the features.
color: Color used to display the points.
thickness: Thickness of the points

Definition at line 316 of file vpKltOpencv.cpp.

References vpDisplay::displayCross(), vpDisplay::displayText(), vpMath::round(), vpImagePoint::set_u(), and vpImagePoint::set_v().

int vpKltOpencv::getBlockSize ( ) const
inline

Get the size of the averaging block used to track the features.

Definition at line 100 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

void vpKltOpencv::getFeature ( const int &  index,
int &  id,
float &  x,
float &  y 
) const

Get the 'index'th feature image coordinates. Beware that getFeature(i,...) may not represent the same feature before and after a tracking iteration (if a feature is lost, features are shifted in the array).

Parameters
index: Index of feature.
id: id of the feature.
x: x coordinate.
y: y coordinate.
Examples:
tutorial-klt-tracker-with-reinit.cpp.

Definition at line 201 of file vpKltOpencv.cpp.

References vpException::badValue, m_points, and m_points_id.

Referenced by vpMbtDistanceKltPoints::computeNbDetectedCurrent(), vpMbtDistanceKltCylinder::computeNbDetectedCurrent(), vpMbKltTracker::getKltImagePoints(), vpMbKltTracker::getKltImagePointsWithId(), vpMbtDistanceKltPoints::init(), and vpMbtDistanceKltCylinder::init().

std::vector<cv::Point2f> vpKltOpencv::getFeatures ( ) const
inline

Get the list of current features.

Examples:
tutorial-klt-tracker-with-reinit.cpp.

Definition at line 103 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::getKltPoints().

std::vector<long> vpKltOpencv::getFeaturesId ( ) const
inline

Get the unique id of each feature.

Definition at line 106 of file vpKltOpencv.h.

double vpKltOpencv::getHarrisFreeParameter ( ) const
inline

Get the free parameter of the Harris detector.

Definition at line 109 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

int vpKltOpencv::getMaxFeatures ( ) const
inline

Get the list of lost feature.

Get the maximum number of features to track in the image.

Examples:
tutorial-klt-tracker-with-reinit.cpp.

Definition at line 113 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::setPose().

double vpKltOpencv::getMinDistance ( ) const
inline

Get the minimal Euclidean distance between detected corners during initialization.

Examples:
tutorial-klt-tracker-with-reinit.cpp.

Definition at line 115 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

int vpKltOpencv::getNbPrevFeatures ( ) const
inline

Get the number of previous features.

Definition at line 119 of file vpKltOpencv.h.

std::vector<cv::Point2f> vpKltOpencv::getPrevFeatures ( ) const
inline

Get the list of previous features.

Definition at line 122 of file vpKltOpencv.h.

int vpKltOpencv::getPyramidLevels ( ) const
inline

Get the list of features id.

Get the maximal pyramid level.

Definition at line 127 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

double vpKltOpencv::getQuality ( ) const
inline

Get the parameter characterizing the minimal accepted quality of image corners.

Definition at line 129 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

int vpKltOpencv::getWindowSize ( ) const
inline

Get the window size used to refine the corner locations.

Definition at line 131 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::setKltOpencv().

void vpKltOpencv::initTracking ( const cv::Mat &  I,
const cv::Mat &  mask = cv::Mat() 
)

Initialise the tracking by extracting KLT keypoints on the provided image.

Parameters
I: Grey level image used as input. This image should have only 1 channel.
mask: Image mask used to restrict the keypoint detection area. If mask is NULL, all the image will be considered.
Exceptions
vpTrackingException::initializationError: If the image I is not initialized, or if the image or the mask have bad coding format.
Examples:
trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, and tutorial-klt-tracker.cpp.

Definition at line 120 of file vpKltOpencv.cpp.

References m_blockSize, m_gray, m_harris_k, m_maxCount, m_minDistance, m_next_points_id, m_points, m_points_id, m_qualityLevel, m_termcrit, and m_winSize.

Referenced by vpMbKltTracker::reinit().

void vpKltOpencv::initTracking ( const cv::Mat &  I,
const std::vector< cv::Point2f > &  pts 
)

Set the points that will be used as initialization during the next call to track().

Parameters
I: Input image.
pts: Vector of points that should be tracked.

Definition at line 493 of file vpKltOpencv.cpp.

References m_gray, m_initial_guess, m_next_points_id, m_points, and m_points_id.

void vpKltOpencv::initTracking ( const cv::Mat &  I,
const std::vector< cv::Point2f > &  pts,
const std::vector< long > &  ids 
)

Definition at line 507 of file vpKltOpencv.cpp.

References m_gray, m_initial_guess, m_next_points_id, m_points, and m_points_id.

void vpKltOpencv::setBlockSize ( const int  blockSize)

Set the size of the averaging block used to track the features.

Warning
The input is a signed integer to be compatible with OpenCV. However, it must be a positive integer.
Parameters
blockSize: Size of an average block for computing a derivative covariation matrix over each pixel neighborhood. Default value is set to 3.
Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 416 of file vpKltOpencv.cpp.

References m_blockSize.

Referenced by vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbKltTracker::resetTracker(), vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setHarrisFreeParameter ( double  harris_k)
void vpKltOpencv::setInitialGuess ( const std::vector< cv::Point2f > &  guess_pts)

Set the points that will be used as initial guess during the next call to track(). A typical usage of this function is to predict the position of the features before the next call to track().

Parameters
guess_pts: Vector of points that should be tracked. The size of this vector should be the same as the one returned by getFeatures(). If this is not the case, an exception is returned. Note also that the id of the points is not modified.
See also
initTracking()

Definition at line 445 of file vpKltOpencv.cpp.

References vpException::badValue, m_initial_guess, and m_points.

Referenced by vpMbKltTracker::setPose().

void vpKltOpencv::setInitialGuess ( const std::vector< cv::Point2f > &  init_pts,
const std::vector< cv::Point2f > &  guess_pts,
const std::vector< long > &  fid 
)

Set the points that will be used as initial guess during the next call to track(). A typical usage of this function is to predict the position of the features before the next call to track().

Parameters
init_pts: Initial points (could be obtained from getPrevFeatures() or getFeatures()).
guess_pts: Prediction of the new position of the initial points. The size of this vector must be the same as the size of the vector of initial points.
fid: Identifiers of the initial points.
See also
getPrevFeatures(),getPrevFeaturesId
getFeatures(), getFeaturesId
initTracking()

Definition at line 471 of file vpKltOpencv.cpp.

References vpException::badValue, m_initial_guess, m_points, and m_points_id.

void vpKltOpencv::setMaxFeatures ( const int  maxCount)
void vpKltOpencv::setMinDistance ( double  minDistance)

Set the minimal Euclidean distance between detected corners during initialization.

Parameters
minDistance: Minimal possible Euclidean distance between the detected corners. Default value is set to 15.
Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 393 of file vpKltOpencv.cpp.

References m_minDistance.

Referenced by vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbKltTracker::resetTracker(), vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setMinEigThreshold ( double  minEigThreshold)

Set the minimal eigen value threshold used to reject a point during the tracking.

Parameters
minEigThreshold: Minimal eigen value threshold. Default value is set to 1e-4.

Definition at line 402 of file vpKltOpencv.cpp.

References m_minEigThreshold.

void vpKltOpencv::setPyramidLevels ( const int  pyrMaxLevel)

Set the maximal pyramid level. If the level is zero, then no pyramid is computed for the optical flow.

Parameters
pyrMaxLevel: 0-based maximal pyramid level number; if set to 0, pyramids are not used (single level), if set to 1, two levels are used, and so on. Default value is set to 3.
Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 428 of file vpKltOpencv.cpp.

References m_pyrMaxLevel.

Referenced by vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbKltTracker::resetTracker(), vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setQuality ( double  qualityLevel)

Set the parameter characterizing the minimal accepted quality of image corners.

Parameters
qualityLevel: Quality level parameter. Default value is set to 0.01. The parameter value is multiplied by the best corner quality measure, which is the minimal eigenvalue or the Harris function response. The corners with the quality measure less than the product are rejected. For example, if the best corner has the quality measure = 1500, and the qualityLevel=0.01, then all the corners with the quality measure less than 15 are rejected.
Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 362 of file vpKltOpencv.cpp.

References m_qualityLevel.

Referenced by vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbKltTracker::resetTracker(), vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setTrackerId ( int  tid)
inline

Does nothing. Just here for compat with previous releases that use OpenCV C api to do the tracking.

Examples:
trackKltOpencv.cpp.

Definition at line 149 of file vpKltOpencv.h.

Referenced by vpMbKltTracker::resetTracker(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setUseHarris ( const int  useHarrisDetector)

Set the parameter indicating whether to use a Harris detector or the minimal eigenvalue of gradient matrices for corner detection.

Parameters
useHarrisDetector: If 1 (default value), use the Harris detector. If 0 use the eigenvalue.
Examples:
trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, and tutorial-klt-tracker.cpp.

Definition at line 382 of file vpKltOpencv.cpp.

References m_useHarrisDetector.

Referenced by vpMbKltTracker::resetTracker(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::setWindowSize ( const int  winSize)

Set the window size used to refine the corner locations.

Parameters
winSize: Half of the side length of the search window. Default value is set to 10. For example, if winSize=5 , then a 5*2+1 $\times$ 5*2+1 = 11 $\times$ 11 search window is used.
Examples:
mbtEdgeKltTracking.cpp, mbtKltTracking.cpp, trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and tutorial-mb-tracker.cpp.

Definition at line 349 of file vpKltOpencv.cpp.

References m_winSize.

Referenced by vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbKltTracker::resetTracker(), vpMbKltTracker::setKltOpencv(), and vpMbKltTracker::vpMbKltTracker().

void vpKltOpencv::suppressFeature ( const int &  index)

Remove the feature with the given index as parameter.

Parameters
index: Index of the feature to remove.

Definition at line 579 of file vpKltOpencv.cpp.

References vpException::badValue, m_points, and m_points_id.

void vpKltOpencv::track ( const cv::Mat &  I)

Track KLT keypoints using the iterative Lucas-Kanade method with pyramids.

Parameters
I: Input image.
Examples:
trackKltOpencv.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, and tutorial-klt-tracker.cpp.

Definition at line 148 of file vpKltOpencv.cpp.

References vpTrackingException::fatalError, m_gray, m_initial_guess, m_minEigThreshold, m_points, m_points_id, m_prevGray, m_pyrMaxLevel, m_termcrit, and m_winSize.

Referenced by vpMbKltTracker::preTracking().

Member Data Documentation

int vpKltOpencv::m_blockSize
protected

Definition at line 165 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and setBlockSize().

cv::Mat vpKltOpencv::m_gray
protected

Definition at line 155 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and track().

double vpKltOpencv::m_harris_k
protected

Definition at line 164 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and setHarrisFreeParameter().

bool vpKltOpencv::m_initial_guess
protected

Definition at line 169 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), setInitialGuess(), and track().

int vpKltOpencv::m_maxCount
protected

Definition at line 158 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and setMaxFeatures().

double vpKltOpencv::m_minDistance
protected

Definition at line 162 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and setMinDistance().

double vpKltOpencv::m_minEigThreshold
protected

Definition at line 163 of file vpKltOpencv.h.

Referenced by operator=(), setMinEigThreshold(), and track().

long vpKltOpencv::m_next_points_id
protected

Definition at line 168 of file vpKltOpencv.h.

Referenced by addFeature(), initTracking(), and operator=().

std::vector<cv::Point2f> vpKltOpencv::m_points[2]
protected

Previous [0] and current [1] keypoint location.

Definition at line 156 of file vpKltOpencv.h.

Referenced by addFeature(), display(), getFeature(), initTracking(), operator=(), setInitialGuess(), suppressFeature(), and track().

std::vector<long> vpKltOpencv::m_points_id
protected

Keypoint id.

Definition at line 157 of file vpKltOpencv.h.

Referenced by addFeature(), display(), getFeature(), initTracking(), operator=(), setInitialGuess(), suppressFeature(), and track().

cv::Mat vpKltOpencv::m_prevGray
protected

Definition at line 155 of file vpKltOpencv.h.

Referenced by operator=(), and track().

int vpKltOpencv::m_pyrMaxLevel
protected

Definition at line 167 of file vpKltOpencv.h.

Referenced by operator=(), setPyramidLevels(), and track().

double vpKltOpencv::m_qualityLevel
protected

Definition at line 161 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), and setQuality().

cv::TermCriteria vpKltOpencv::m_termcrit
protected

Definition at line 159 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), track(), and vpKltOpencv().

int vpKltOpencv::m_useHarrisDetector
protected

Definition at line 166 of file vpKltOpencv.h.

Referenced by operator=(), and setUseHarris().

int vpKltOpencv::m_winSize
protected

Definition at line 160 of file vpKltOpencv.h.

Referenced by initTracking(), operator=(), setWindowSize(), and track().