Merge pull request #2737 from alalek:tracking_api

pull/2754/head
Alexander Alekhin 5 years ago
commit f1c3d0e5e7
  1. 23
      modules/tracking/CMakeLists.txt
  2. 513
      modules/tracking/include/opencv2/tracking.hpp
  3. 13
      modules/tracking/include/opencv2/tracking/feature.hpp
  4. 19
      modules/tracking/include/opencv2/tracking/kalman_filters.hpp
  5. 13
      modules/tracking/include/opencv2/tracking/onlineBoosting.hpp
  6. 9
      modules/tracking/include/opencv2/tracking/onlineMIL.hpp
  7. 14
      modules/tracking/include/opencv2/tracking/tldDataset.hpp
  8. 11
      modules/tracking/include/opencv2/tracking/tracking_by_matching.hpp
  9. 799
      modules/tracking/include/opencv2/tracking/tracking_internals.hpp
  10. 538
      modules/tracking/include/opencv2/tracking/tracking_legacy.hpp
  11. 5
      modules/tracking/misc/java/gen_dict.json
  12. 23
      modules/tracking/misc/java/test/TrackerCreateLegacyTest.java
  13. 38
      modules/tracking/misc/java/test/TrackerCreateTest.java
  14. 5
      modules/tracking/misc/objc/gen_dict.json
  15. 6
      modules/tracking/misc/python/pyopencv_tracking.hpp
  16. 31
      modules/tracking/misc/python/test/test_tracking_contrib.py
  17. 412
      modules/tracking/perf/perf_Tracker.cpp
  18. 17
      modules/tracking/perf/perf_main.cpp
  19. 119
      modules/tracking/perf/perf_trackers.cpp
  20. 8
      modules/tracking/samples/benchmark.cpp
  21. 2
      modules/tracking/samples/csrt.cpp
  22. 11
      modules/tracking/samples/goturnTracker.cpp
  23. 2
      modules/tracking/samples/kcf.cpp
  24. 4
      modules/tracking/samples/multiTracker_dataset.cpp
  25. 6
      modules/tracking/samples/multitracker.cpp
  26. 41
      modules/tracking/samples/samples_utility.hpp
  27. 8
      modules/tracking/samples/tracker.cpp
  28. 8
      modules/tracking/samples/tracker_dataset.cpp
  29. 5
      modules/tracking/samples/tracking_by_matching.cpp
  30. 2
      modules/tracking/samples/tutorial_customizing_cn_tracker.cpp
  31. 3
      modules/tracking/samples/tutorial_introduction_to_tracker.cpp
  32. 6
      modules/tracking/samples/tutorial_multitracker.cpp
  33. 2
      modules/tracking/src/PFSolver.hpp
  34. 11
      modules/tracking/src/augmented_unscented_kalman.cpp
  35. 15
      modules/tracking/src/feature.cpp
  36. 8
      modules/tracking/src/featureColorName.cpp
  37. 144
      modules/tracking/src/gtrTracker.cpp
  38. 80
      modules/tracking/src/gtrTracker.hpp
  39. 1
      modules/tracking/src/gtrUtils.cpp
  40. 1
      modules/tracking/src/gtrUtils.hpp
  41. 8
      modules/tracking/src/kuhn_munkres.cpp
  42. 5
      modules/tracking/src/kuhn_munkres.hpp
  43. 140
      modules/tracking/src/legacy/tracker.legacy.hpp
  44. 159
      modules/tracking/src/legacy/trackerCSRT.legacy.hpp
  45. 173
      modules/tracking/src/legacy/trackerKCF.legacy.hpp
  46. 122
      modules/tracking/src/legacy/trackerMIL.legacy.hpp
  47. 23
      modules/tracking/src/mosseTracker.cpp
  48. 31
      modules/tracking/src/multiTracker.cpp
  49. 12
      modules/tracking/src/multiTracker.hpp
  50. 5
      modules/tracking/src/multiTracker_alt.cpp
  51. 7
      modules/tracking/src/onlineBoosting.cpp
  52. 30
      modules/tracking/src/precomp.hpp
  53. 10
      modules/tracking/src/tldDataset.cpp
  54. 15
      modules/tracking/src/tldDetector.cpp
  55. 13
      modules/tracking/src/tldDetector.hpp
  56. 13
      modules/tracking/src/tldEnsembleClassifier.cpp
  57. 14
      modules/tracking/src/tldEnsembleClassifier.hpp
  58. 14
      modules/tracking/src/tldModel.cpp
  59. 16
      modules/tracking/src/tldModel.hpp
  60. 20
      modules/tracking/src/tldTracker.cpp
  61. 16
      modules/tracking/src/tldTracker.hpp
  62. 11
      modules/tracking/src/tldUtils.cpp
  63. 13
      modules/tracking/src/tldUtils.hpp
  64. 99
      modules/tracking/src/tracker.cpp
  65. 10
      modules/tracking/src/trackerBoosting.cpp
  66. 8
      modules/tracking/src/trackerBoostingModel.cpp
  67. 10
      modules/tracking/src/trackerBoostingModel.hpp
  68. 168
      modules/tracking/src/trackerCSRT.cpp
  69. 6
      modules/tracking/src/trackerCSRTScaleEstimation.cpp
  70. 7
      modules/tracking/src/trackerFeature.cpp
  71. 8
      modules/tracking/src/trackerFeatureSet.cpp
  72. 177
      modules/tracking/src/trackerKCF.cpp
  73. 131
      modules/tracking/src/trackerMIL.cpp
  74. 7
      modules/tracking/src/trackerMILModel.cpp
  75. 9
      modules/tracking/src/trackerMILModel.hpp
  76. 35
      modules/tracking/src/trackerMedianFlow.cpp
  77. 7
      modules/tracking/src/trackerModel.cpp
  78. 8
      modules/tracking/src/trackerSampler.cpp
  79. 17
      modules/tracking/src/trackerSamplerAlgorithm.cpp
  80. 7
      modules/tracking/src/trackerStateEstimator.cpp
  81. 10
      modules/tracking/src/tracking_by_matching.cpp
  82. 5
      modules/tracking/src/tracking_utils.cpp
  83. 9
      modules/tracking/src/tracking_utils.hpp
  84. 11
      modules/tracking/src/unscented_kalman.cpp
  85. 2
      modules/tracking/test/test_aukf.cpp
  86. 20
      modules/tracking/test/test_trackerParametersIO.cpp
  87. 336
      modules/tracking/test/test_trackers.cpp
  88. 2
      modules/tracking/test/test_ukf.cpp
  89. 6
      modules/tracking/tutorials/tutorial_multitracker.markdown

@ -1,3 +1,24 @@
set(the_description "Tracking API")
ocv_define_module(tracking opencv_imgproc opencv_core opencv_video opencv_plot OPTIONAL opencv_dnn opencv_datasets WRAP java python objc)
set(debug_modules "")
if(DEBUG_opencv_tracking)
list(APPEND debug_modules opencv_highgui)
endif()
ocv_define_module(tracking
opencv_imgproc
opencv_core
opencv_video
opencv_plot # samples only
${debug_modules}
OPTIONAL
opencv_dnn
opencv_datasets
opencv_highgui
WRAP
java
python
objc
)
ocv_warnings_disable(CMAKE_CXX_FLAGS -Wno-shadow /wd4458)

@ -1,284 +1,271 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef __OPENCV_TRACKING_HPP__
#define __OPENCV_TRACKING_HPP__
#include "opencv2/core/cvdef.h"
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#ifndef OPENCV_CONTRIB_TRACKING_HPP
#define OPENCV_CONTRIB_TRACKING_HPP
#include "opencv2/core.hpp"
namespace cv {
#ifndef CV_DOXYGEN
inline namespace tracking {
#endif
/** @defgroup tracking Tracking API
@{
@defgroup tracking_detail Tracking API implementation details
@defgroup tracking_legacy Legacy Tracking API
@}
*/
Long-term optical tracking API
------------------------------
Long-term optical tracking is an important issue for many computer vision applications in
real world scenario. The development in this area is very fragmented and this API is an unique
interface useful for plug several algorithms and compare them. This work is partially based on
@cite AAM and @cite AMVOT .
These algorithms start from a bounding box of the target and with their internal representation they
avoid the drift during the tracking. These long-term trackers are able to evaluate online the
quality of the location of the target in the new frame, without ground truth.
There are three main components: the TrackerSampler, the TrackerFeatureSet and the TrackerModel. The
first component is the object that computes the patches over the frame based on the last target
location. The TrackerFeatureSet is the class that manages the Features, is possible plug many kind
of these (HAAR, HOG, LBP, Feature2D, etc). The last component is the internal representation of the
target, it is the appearance model. It stores all state candidates and compute the trajectory (the
most likely target states). The class TrackerTargetState represents a possible state of the target.
The TrackerSampler and the TrackerFeatureSet are the visual representation of the target, instead
the TrackerModel is the statistical model.
A recent benchmark between these algorithms can be found in @cite OOT
Creating Your Own %Tracker
--------------------
If you want to create a new tracker, here's what you have to do. First, decide on the name of the class
for the tracker (to meet the existing style, we suggest something with prefix "tracker", e.g.
trackerMIL, trackerBoosting) -- we shall refer to this choice as to "classname" in subsequent.
- Declare your tracker in modules/tracking/include/opencv2/tracking/tracker.hpp. Your tracker should inherit from
Tracker (please, see the example below). You should declare the specialized Param structure,
where you probably will want to put the data, needed to initialize your tracker. You should
get something similar to :
@code
class CV_EXPORTS_W TrackerMIL : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
//parameters for sampler
float samplerInitInRadius; // radius for gathering positive instances during init
int samplerInitMaxNegNum; // # negative samples to use during init
float samplerSearchWinSize; // size of search window
float samplerTrackInRadius; // radius for gathering positive instances during tracking
int samplerTrackMaxPosNum; // # positive samples to use during tracking
int samplerTrackMaxNegNum; // # negative samples to use during tracking
int featureSetNumFeatures; // #features
void read( const FileNode& fn );
void write( FileStorage& fs ) const;
};
@endcode
of course, you can also add any additional methods of your choice. It should be pointed out,
however, that it is not expected to have a constructor declared, as creation should be done via
the corresponding create() method.
- Finally, you should implement the function with signature :
@code
Ptr<classname> classname::create(const classname::Params &parameters){
...
}
@endcode
That function can (and probably will) return a pointer to some derived class of "classname",
which will probably have a real constructor.
Every tracker has three component TrackerSampler, TrackerFeatureSet and TrackerModel. The first two
are instantiated from Tracker base class, instead the last component is abstract, so you must
implement your TrackerModel.
### TrackerSampler
TrackerSampler is already instantiated, but you should define the sampling algorithm and add the
classes (or single class) to TrackerSampler. You can choose one of the ready implementation as
TrackerSamplerCSC or you can implement your sampling method, in this case the class must inherit
TrackerSamplerAlgorithm. Fill the samplingImpl method that writes the result in "sample" output
argument.
Example of creating specialized TrackerSamplerAlgorithm TrackerSamplerCSC : :
@code
class CV_EXPORTS_W TrackerSamplerCSC : public TrackerSamplerAlgorithm
{
public:
TrackerSamplerCSC( const TrackerSamplerCSC::Params &parameters = TrackerSamplerCSC::Params() );
~TrackerSamplerCSC();
...
/** @addtogroup tracking
@{
Tracking is an important issue for many computer vision applications in real world scenario.
The development in this area is very fragmented and this API is an interface useful for plug several algorithms and compare them.
*/
protected:
bool samplingImpl( const Mat& image, Rect boundingBox, std::vector<Mat>& sample );
...
};
@endcode
Example of adding TrackerSamplerAlgorithm to TrackerSampler : :
@code
//sampler is the TrackerSampler
Ptr<TrackerSamplerAlgorithm> CSCSampler = new TrackerSamplerCSC( CSCparameters );
if( !sampler->addTrackerSamplerAlgorithm( CSCSampler ) )
return false;
//or add CSC sampler with default parameters
//sampler->addTrackerSamplerAlgorithm( "CSC" );
@endcode
@sa
TrackerSamplerCSC, TrackerSamplerAlgorithm
### TrackerFeatureSet
TrackerFeatureSet is already instantiated (as first) , but you should define what kinds of features
you'll use in your tracker. You can use multiple feature types, so you can add a ready
implementation as TrackerFeatureHAAR in your TrackerFeatureSet or develop your own implementation.
In this case, in the computeImpl method put the code that extract the features and in the selection
method optionally put the code for the refinement and selection of the features.
Example of creating specialized TrackerFeature TrackerFeatureHAAR : :
@code
class CV_EXPORTS_W TrackerFeatureHAAR : public TrackerFeature
{
public:
TrackerFeatureHAAR( const TrackerFeatureHAAR::Params &parameters = TrackerFeatureHAAR::Params() );
~TrackerFeatureHAAR();
void selection( Mat& response, int npoints );
...
protected:
bool computeImpl( const std::vector<Mat>& images, Mat& response );
...
/** @brief Base abstract class for the long-term tracker
*/
class CV_EXPORTS_W Tracker
{
protected:
Tracker();
public:
virtual ~Tracker();
};
@endcode
Example of adding TrackerFeature to TrackerFeatureSet : :
@code
//featureSet is the TrackerFeatureSet
Ptr<TrackerFeature> trackerFeature = new TrackerFeatureHAAR( HAARparameters );
featureSet->addTrackerFeature( trackerFeature );
@endcode
@sa
TrackerFeatureHAAR, TrackerFeatureSet
### TrackerModel
TrackerModel is abstract, so in your implementation you must develop your TrackerModel that inherit
from TrackerModel. Fill the method for the estimation of the state "modelEstimationImpl", that
estimates the most likely target location, see @cite AAM table I (ME) for further information. Fill
"modelUpdateImpl" in order to update the model, see @cite AAM table I (MU). In this class you can use
the :cConfidenceMap and :cTrajectory to storing the model. The first represents the model on the all
possible candidate states and the second represents the list of all estimated states.
Example of creating specialized TrackerModel TrackerMILModel : :
@code
class TrackerMILModel : public TrackerModel
{
public:
TrackerMILModel( const Rect& boundingBox );
~TrackerMILModel();
...
/** @brief Initialize the tracker with a known bounding box that surrounded the target
@param image The initial frame
@param boundingBox The initial bounding box
*/
CV_WRAP virtual
void init(InputArray image, const Rect& boundingBox) = 0;
protected:
void modelEstimationImpl( const std::vector<Mat>& responses );
void modelUpdateImpl();
...
/** @brief Update the tracker, find the new most likely bounding box for the target
@param image The current frame
@param boundingBox The bounding box that represent the new target location, if true was returned, not
modified otherwise
};
@endcode
And add it in your Tracker : :
@code
bool TrackerMIL::initImpl( const Mat& image, const Rect2d& boundingBox )
@return True means that target was located and false means that tracker cannot locate target in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
CV_WRAP virtual
bool update(InputArray image, CV_OUT Rect& boundingBox) = 0;
};
/** @brief the CSRT tracker
The implementation is based on @cite Lukezic_IJCV2018 Discriminative Correlation Filter with Channel and Spatial Reliability
*/
class CV_EXPORTS_W TrackerCSRT : public Tracker
{
protected:
TrackerCSRT(); // use ::create()
public:
virtual ~TrackerCSRT() CV_OVERRIDE;
struct CV_EXPORTS_W_SIMPLE Params
{
...
//model is the general TrackerModel field of the general Tracker
model = new TrackerMILModel( boundingBox );
...
}
@endcode
In the last step you should define the TrackerStateEstimator based on your implementation or you can
use one of ready class as TrackerStateEstimatorMILBoosting. It represent the statistical part of the
model that estimates the most likely target state.
Example of creating specialized TrackerStateEstimator TrackerStateEstimatorMILBoosting : :
@code
class CV_EXPORTS_W TrackerStateEstimatorMILBoosting : public TrackerStateEstimator
CV_WRAP Params();
CV_PROP_RW bool use_hog;
CV_PROP_RW bool use_color_names;
CV_PROP_RW bool use_gray;
CV_PROP_RW bool use_rgb;
CV_PROP_RW bool use_channel_weights;
CV_PROP_RW bool use_segmentation;
CV_PROP_RW std::string window_function; //!< Window function: "hann", "cheb", "kaiser"
CV_PROP_RW float kaiser_alpha;
CV_PROP_RW float cheb_attenuation;
CV_PROP_RW float template_size;
CV_PROP_RW float gsl_sigma;
CV_PROP_RW float hog_orientations;
CV_PROP_RW float hog_clip;
CV_PROP_RW float padding;
CV_PROP_RW float filter_lr;
CV_PROP_RW float weights_lr;
CV_PROP_RW int num_hog_channels_used;
CV_PROP_RW int admm_iterations;
CV_PROP_RW int histogram_bins;
CV_PROP_RW float histogram_lr;
CV_PROP_RW int background_ratio;
CV_PROP_RW int number_of_scales;
CV_PROP_RW float scale_sigma_factor;
CV_PROP_RW float scale_model_max_area;
CV_PROP_RW float scale_lr;
CV_PROP_RW float scale_step;
CV_PROP_RW float psr_threshold; //!< we lost the target, if the psr is lower than this.
};
/** @brief Create CSRT tracker instance
@param parameters CSRT parameters TrackerCSRT::Params
*/
static CV_WRAP
Ptr<TrackerCSRT> create(const TrackerCSRT::Params &parameters = TrackerCSRT::Params());
//void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
//bool update(InputArray image, CV_OUT Rect& boundingBox) CV_OVERRIDE;
CV_WRAP virtual void setInitialMask(InputArray mask) = 0;
};
/** @brief the KCF (Kernelized Correlation Filter) tracker
* KCF is a novel tracking framework that utilizes properties of circulant matrix to enhance the processing speed.
* This tracking method is an implementation of @cite KCF_ECCV which is extended to KCF with color-names features (@cite KCF_CN).
* The original paper of KCF is available at <http://www.robots.ox.ac.uk/~joao/publications/henriques_tpami2015.pdf>
* as well as the matlab implementation. For more information about KCF with color-names features, please refer to
* <http://www.cvl.isy.liu.se/research/objrec/visualtracking/colvistrack/index.html>.
*/
class CV_EXPORTS_W TrackerKCF : public Tracker
{
protected:
TrackerKCF(); // use ::create()
public:
virtual ~TrackerKCF() CV_OVERRIDE;
/**
* \brief Feature type to be used in the tracking grayscale, colornames, compressed color-names
* The modes available now:
- "GRAY" -- Use grayscale values as the feature
- "CN" -- Color-names feature
*/
enum MODE {
GRAY = (1 << 0),
CN = (1 << 1),
CUSTOM = (1 << 2)
};
struct CV_EXPORTS_W_SIMPLE Params
{
class TrackerMILTargetState : public TrackerTargetState
{
...
};
CV_WRAP Params();
CV_PROP_RW float detect_thresh; //!< detection confidence threshold
CV_PROP_RW float sigma; //!< gaussian kernel bandwidth
CV_PROP_RW float lambda; //!< regularization
CV_PROP_RW float interp_factor; //!< linear interpolation factor for adaptation
CV_PROP_RW float output_sigma_factor; //!< spatial bandwidth (proportional to target)
CV_PROP_RW float pca_learning_rate; //!< compression learning rate
CV_PROP_RW bool resize; //!< activate the resize feature to improve the processing speed
CV_PROP_RW bool split_coeff; //!< split the training coefficients into two matrices
CV_PROP_RW bool wrap_kernel; //!< wrap around the kernel values
CV_PROP_RW bool compress_feature; //!< activate the pca method to compress the features
CV_PROP_RW int max_patch_size; //!< threshold for the ROI size
CV_PROP_RW int compressed_size; //!< feature size after compression
CV_PROP_RW int desc_pca; //!< compressed descriptors of TrackerKCF::MODE
CV_PROP_RW int desc_npca; //!< non-compressed descriptors of TrackerKCF::MODE
};
/** @brief Create KCF tracker instance
@param parameters KCF parameters TrackerKCF::Params
*/
static CV_WRAP
Ptr<TrackerKCF> create(const TrackerKCF::Params &parameters = TrackerKCF::Params());
//void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
//bool update(InputArray image, CV_OUT Rect& boundingBox) CV_OVERRIDE;
// FIXIT use interface
typedef void (*FeatureExtractorCallbackFN)(const Mat, const Rect, Mat&);
virtual void setFeatureExtractor(FeatureExtractorCallbackFN callback, bool pca_func = false) = 0;
};
public:
TrackerStateEstimatorMILBoosting( int nFeatures = 250 );
~TrackerStateEstimatorMILBoosting();
...
protected:
Ptr<TrackerTargetState> estimateImpl( const std::vector<ConfidenceMap>& confidenceMaps );
void updateImpl( std::vector<ConfidenceMap>& confidenceMaps );
...
/** @brief The MIL algorithm trains a classifier in an online manner to separate the object from the
background.
Multiple Instance Learning avoids the drift problem for a robust tracking. The implementation is
based on @cite MIL .
Original code can be found here <http://vision.ucsd.edu/~bbabenko/project_miltrack.shtml>
*/
class CV_EXPORTS_W TrackerMIL : public Tracker
{
protected:
TrackerMIL(); // use ::create()
public:
virtual ~TrackerMIL() CV_OVERRIDE;
struct CV_EXPORTS_W_SIMPLE Params
{
CV_WRAP Params();
//parameters for sampler
CV_PROP_RW float samplerInitInRadius; //!< radius for gathering positive instances during init
CV_PROP_RW int samplerInitMaxNegNum; //!< # negative samples to use during init
CV_PROP_RW float samplerSearchWinSize; //!< size of search window
CV_PROP_RW float samplerTrackInRadius; //!< radius for gathering positive instances during tracking
CV_PROP_RW int samplerTrackMaxPosNum; //!< # positive samples to use during tracking
CV_PROP_RW int samplerTrackMaxNegNum; //!< # negative samples to use during tracking
CV_PROP_RW int featureSetNumFeatures; //!< # features
};
@endcode
And add it in your TrackerModel : :
@code
//model is the TrackerModel of your Tracker
Ptr<TrackerStateEstimatorMILBoosting> stateEstimator = new TrackerStateEstimatorMILBoosting( params.featureSetNumFeatures );
model->setTrackerStateEstimator( stateEstimator );
@endcode
@sa
TrackerModel, TrackerStateEstimatorMILBoosting, TrackerTargetState
During this step, you should define your TrackerTargetState based on your implementation.
TrackerTargetState base class has only the bounding box (upper-left position, width and height), you
can enrich it adding scale factor, target rotation, etc.
Example of creating specialized TrackerTargetState TrackerMILTargetState : :
@code
class TrackerMILTargetState : public TrackerTargetState
/** @brief Create MIL tracker instance
* @param parameters MIL parameters TrackerMIL::Params
*/
static CV_WRAP
Ptr<TrackerMIL> create(const TrackerMIL::Params &parameters = TrackerMIL::Params());
//void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
//bool update(InputArray image, CV_OUT Rect& boundingBox) CV_OVERRIDE;
};
/** @brief the GOTURN (Generic Object Tracking Using Regression Networks) tracker
*
* GOTURN (@cite GOTURN) is kind of trackers based on Convolutional Neural Networks (CNN). While taking all advantages of CNN trackers,
* GOTURN is much faster due to offline training without online fine-tuning nature.
* GOTURN tracker addresses the problem of single target tracking: given a bounding box label of an object in the first frame of the video,
* we track that object through the rest of the video. NOTE: Current method of GOTURN does not handle occlusions; however, it is fairly
* robust to viewpoint changes, lighting changes, and deformations.
* Inputs of GOTURN are two RGB patches representing Target and Search patches resized to 227x227.
* Outputs of GOTURN are predicted bounding box coordinates, relative to Search patch coordinate system, in format X1,Y1,X2,Y2.
* Original paper is here: <http://davheld.github.io/GOTURN/GOTURN.pdf>
* As long as original authors implementation: <https://github.com/davheld/GOTURN#train-the-tracker>
* Implementation of training algorithm is placed in separately here due to 3d-party dependencies:
* <https://github.com/Auron-X/GOTURN_Training_Toolkit>
* GOTURN architecture goturn.prototxt and trained model goturn.caffemodel are accessible on opencv_extra GitHub repository.
*/
class CV_EXPORTS_W TrackerGOTURN : public Tracker
{
protected:
TrackerGOTURN(); // use ::create()
public:
virtual ~TrackerGOTURN() CV_OVERRIDE;
struct CV_EXPORTS_W_SIMPLE Params
{
public:
TrackerMILTargetState( const Point2f& position, int targetWidth, int targetHeight, bool foreground, const Mat& features );
~TrackerMILTargetState();
...
CV_WRAP Params();
CV_PROP_RW std::string modelTxt;
CV_PROP_RW std::string modelBin;
};
private:
bool isTarget;
Mat targetFeatures;
...
/** @brief Constructor
@param parameters GOTURN parameters TrackerGOTURN::Params
*/
static CV_WRAP
Ptr<TrackerGOTURN> create(const TrackerGOTURN::Params& parameters = TrackerGOTURN::Params());
};
@endcode
//void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
//bool update(InputArray image, CV_OUT Rect& boundingBox) CV_OVERRIDE;
};
*/
//! @}
#include <opencv2/tracking/tracker.hpp>
#include <opencv2/tracking/tldDataset.hpp>
#ifndef CV_DOXYGEN
}
#endif
} // namespace
#endif //__OPENCV_TRACKING_HPP__
#endif // OPENCV_CONTRIB_TRACKING_HPP

@ -53,12 +53,15 @@
* TODO Changed CvHaarEvaluator based on ADABOOSTING implementation (Grabner et al.)
*/
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking
//! @addtogroup tracking_detail
//! @{
inline namespace feature {
#define FEATURES "features"
#define CC_FEATURES FEATURES
@ -409,8 +412,10 @@ inline uchar CvLBPEvaluator::Feature::calc( const Mat &_sum, size_t y ) const
( psum[p[4]] - psum[p[5]] - psum[p[8]] + psum[p[9]] >= cval ? 1 : 0 ) ); // 3
}
} // namespace
//! @}
} /* namespace cv */
}}} // namespace cv
#endif

@ -45,10 +45,14 @@
#include "opencv2/core.hpp"
#include <limits>
namespace cv
{
namespace tracking
{
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking_detail
//! @{
inline namespace kalman_filters {
/** @brief The interface for Unscented Kalman filter and Augmented Unscented Kalman filter.
*/
@ -222,7 +226,10 @@ CV_EXPORTS Ptr<UnscentedKalmanFilter> createUnscentedKalmanFilter( const Unscent
*/
CV_EXPORTS Ptr<UnscentedKalmanFilter> createAugmentedUnscentedKalmanFilter( const AugmentedUnscentedKalmanFilterParams &params );
} // tracking
} // cv
} // namespace
//! @}
}}} // namespace
#endif

@ -44,12 +44,15 @@
#include "opencv2/core.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking
//! @addtogroup tracking_detail
//! @{
inline namespace online_boosting {
//TODO based on the original implementation
//http://vision.ucsd.edu/~bbabenko/project_miltrack.shtml
@ -281,8 +284,10 @@ class ClassifierThreshold
int m_parity;
};
} // namespace
//! @}
} /* namespace cv */
}}} // namespace
#endif

@ -45,10 +45,11 @@
#include "opencv2/core.hpp"
#include <limits>
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking
//! @addtogroup tracking_detail
//! @{
//TODO based on the original implementation
@ -113,6 +114,6 @@ class ClfOnlineStump
//! @}
} /* namespace cv */
}}} // namespace
#endif

@ -44,13 +44,21 @@
#include "opencv2/core.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking_detail
//! @{
namespace tld
{
CV_EXPORTS cv::Rect2d tld_InitDataset(int videoInd, const char* rootPath = "TLD_dataset", int datasetInd = 0);
CV_EXPORTS cv::String tld_getNextDatasetFrame();
}
}
//! @}
}}}
#endif

@ -20,6 +20,12 @@
namespace cv {
namespace detail {
inline namespace tracking {
//! @addtogroup tracking_detail
//! @{
namespace tbm { //Tracking-by-Matching
///
/// \brief The TrackedObject struct defines properties of detected object.
@ -553,5 +559,8 @@ public:
CV_EXPORTS cv::Ptr<ITrackerByMatching> createTrackerByMatching(const TrackerParams &params = TrackerParams());
} // namespace tbm
} // namespace cv
//! @}
}}} // namespace
#endif // #ifndef __OPENCV_TRACKING_TRACKING_BY_MATCHING_HPP__

@ -39,30 +39,264 @@
//
//M*/
#ifndef __OPENCV_TRACKER_HPP__
#define __OPENCV_TRACKER_HPP__
#include "opencv2/core.hpp"
#include "opencv2/imgproc/types_c.h"
#include "feature.hpp"
#include "onlineMIL.hpp"
#include "onlineBoosting.hpp"
#ifndef OPENCV_TRACKING_DETAIL_HPP
#define OPENCV_TRACKING_DETAIL_HPP
/*
* Partially based on:
* ====================================================================================================================
* - [AAM] S. Salti, A. Cavallaro, L. Di Stefano, Adaptive Appearance Modeling for Video Tracking: Survey and Evaluation
* - [AAM] S. Salti, A. Cavallaro, L. Di Stefano, Adaptive Appearance Modeling for Video Tracking: Survey and Evaluation
* - [AMVOT] X. Li, W. Hu, C. Shen, Z. Zhang, A. Dick, A. van den Hengel, A Survey of Appearance Models in Visual Object Tracking
*
* This Tracking API has been designed with PlantUML. If you modify this API please change UML files under modules/tracking/doc/uml
*
*/
namespace cv
{
#include "opencv2/core.hpp"
#include "feature.hpp" // CvHaarEvaluator
#include "onlineBoosting.hpp" // StrongClassifierDirectSelection
#include "onlineMIL.hpp" // ClfMilBoost
namespace cv {
namespace detail {
inline namespace tracking {
/** @addtogroup tracking_detail
@{
Long-term optical tracking API
------------------------------
Long-term optical tracking is an important issue for many computer vision applications in
real world scenario. The development in this area is very fragmented and this API is an unique
interface useful for plug several algorithms and compare them. This work is partially based on
@cite AAM and @cite AMVOT .
These algorithms start from a bounding box of the target and with their internal representation they
avoid the drift during the tracking. These long-term trackers are able to evaluate online the
quality of the location of the target in the new frame, without ground truth.
There are three main components: the TrackerSampler, the TrackerFeatureSet and the TrackerModel. The
first component is the object that computes the patches over the frame based on the last target
location. The TrackerFeatureSet is the class that manages the Features, is possible plug many kind
of these (HAAR, HOG, LBP, Feature2D, etc). The last component is the internal representation of the
target, it is the appearance model. It stores all state candidates and compute the trajectory (the
most likely target states). The class TrackerTargetState represents a possible state of the target.
The TrackerSampler and the TrackerFeatureSet are the visual representation of the target, instead
the TrackerModel is the statistical model.
A recent benchmark between these algorithms can be found in @cite OOT
Creating Your Own %Tracker
--------------------
If you want to create a new tracker, here's what you have to do. First, decide on the name of the class
for the tracker (to meet the existing style, we suggest something with prefix "tracker", e.g.
trackerMIL, trackerBoosting) -- we shall refer to this choice as to "classname" in subsequent.
- Declare your tracker in modules/tracking/include/opencv2/tracking/tracker.hpp. Your tracker should inherit from
Tracker (please, see the example below). You should declare the specialized Param structure,
where you probably will want to put the data, needed to initialize your tracker. You should
get something similar to :
@code
class CV_EXPORTS_W TrackerMIL : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
//parameters for sampler
float samplerInitInRadius; // radius for gathering positive instances during init
int samplerInitMaxNegNum; // # negative samples to use during init
float samplerSearchWinSize; // size of search window
float samplerTrackInRadius; // radius for gathering positive instances during tracking
int samplerTrackMaxPosNum; // # positive samples to use during tracking
int samplerTrackMaxNegNum; // # negative samples to use during tracking
int featureSetNumFeatures; // #features
void read( const FileNode& fn );
void write( FileStorage& fs ) const;
};
@endcode
of course, you can also add any additional methods of your choice. It should be pointed out,
however, that it is not expected to have a constructor declared, as creation should be done via
the corresponding create() method.
- Finally, you should implement the function with signature :
@code
Ptr<classname> classname::create(const classname::Params &parameters){
...
}
@endcode
That function can (and probably will) return a pointer to some derived class of "classname",
which will probably have a real constructor.
Every tracker has three component TrackerSampler, TrackerFeatureSet and TrackerModel. The first two
are instantiated from Tracker base class, instead the last component is abstract, so you must
implement your TrackerModel.
### TrackerSampler
TrackerSampler is already instantiated, but you should define the sampling algorithm and add the
classes (or single class) to TrackerSampler. You can choose one of the ready implementation as
TrackerSamplerCSC or you can implement your sampling method, in this case the class must inherit
TrackerSamplerAlgorithm. Fill the samplingImpl method that writes the result in "sample" output
argument.
Example of creating specialized TrackerSamplerAlgorithm TrackerSamplerCSC : :
@code
class CV_EXPORTS_W TrackerSamplerCSC : public TrackerSamplerAlgorithm
{
public:
TrackerSamplerCSC( const TrackerSamplerCSC::Params &parameters = TrackerSamplerCSC::Params() );
~TrackerSamplerCSC();
...
protected:
bool samplingImpl( const Mat& image, Rect boundingBox, std::vector<Mat>& sample );
...
};
@endcode
Example of adding TrackerSamplerAlgorithm to TrackerSampler : :
@code
//sampler is the TrackerSampler
Ptr<TrackerSamplerAlgorithm> CSCSampler = new TrackerSamplerCSC( CSCparameters );
if( !sampler->addTrackerSamplerAlgorithm( CSCSampler ) )
return false;
//or add CSC sampler with default parameters
//sampler->addTrackerSamplerAlgorithm( "CSC" );
@endcode
@sa
TrackerSamplerCSC, TrackerSamplerAlgorithm
### TrackerFeatureSet
TrackerFeatureSet is already instantiated (as first) , but you should define what kinds of features
you'll use in your tracker. You can use multiple feature types, so you can add a ready
implementation as TrackerFeatureHAAR in your TrackerFeatureSet or develop your own implementation.
In this case, in the computeImpl method put the code that extract the features and in the selection
method optionally put the code for the refinement and selection of the features.
Example of creating specialized TrackerFeature TrackerFeatureHAAR : :
@code
class CV_EXPORTS_W TrackerFeatureHAAR : public TrackerFeature
{
public:
TrackerFeatureHAAR( const TrackerFeatureHAAR::Params &parameters = TrackerFeatureHAAR::Params() );
~TrackerFeatureHAAR();
void selection( Mat& response, int npoints );
...
protected:
bool computeImpl( const std::vector<Mat>& images, Mat& response );
...
};
@endcode
Example of adding TrackerFeature to TrackerFeatureSet : :
@code
//featureSet is the TrackerFeatureSet
Ptr<TrackerFeature> trackerFeature = new TrackerFeatureHAAR( HAARparameters );
featureSet->addTrackerFeature( trackerFeature );
@endcode
@sa
TrackerFeatureHAAR, TrackerFeatureSet
### TrackerModel
TrackerModel is abstract, so in your implementation you must develop your TrackerModel that inherit
from TrackerModel. Fill the method for the estimation of the state "modelEstimationImpl", that
estimates the most likely target location, see @cite AAM table I (ME) for further information. Fill
"modelUpdateImpl" in order to update the model, see @cite AAM table I (MU). In this class you can use
the :cConfidenceMap and :cTrajectory to storing the model. The first represents the model on the all
possible candidate states and the second represents the list of all estimated states.
Example of creating specialized TrackerModel TrackerMILModel : :
@code
class TrackerMILModel : public TrackerModel
{
public:
TrackerMILModel( const Rect& boundingBox );
~TrackerMILModel();
...
protected:
void modelEstimationImpl( const std::vector<Mat>& responses );
void modelUpdateImpl();
...
};
@endcode
And add it in your Tracker : :
@code
bool TrackerMIL::initImpl( const Mat& image, const Rect2d& boundingBox )
{
...
//model is the general TrackerModel field of the general Tracker
model = new TrackerMILModel( boundingBox );
...
}
@endcode
In the last step you should define the TrackerStateEstimator based on your implementation or you can
use one of ready class as TrackerStateEstimatorMILBoosting. It represent the statistical part of the
model that estimates the most likely target state.
Example of creating specialized TrackerStateEstimator TrackerStateEstimatorMILBoosting : :
@code
class CV_EXPORTS_W TrackerStateEstimatorMILBoosting : public TrackerStateEstimator
{
class TrackerMILTargetState : public TrackerTargetState
{
...
};
public:
TrackerStateEstimatorMILBoosting( int nFeatures = 250 );
~TrackerStateEstimatorMILBoosting();
...
protected:
Ptr<TrackerTargetState> estimateImpl( const std::vector<ConfidenceMap>& confidenceMaps );
void updateImpl( std::vector<ConfidenceMap>& confidenceMaps );
...
};
@endcode
And add it in your TrackerModel : :
@code
//model is the TrackerModel of your Tracker
Ptr<TrackerStateEstimatorMILBoosting> stateEstimator = new TrackerStateEstimatorMILBoosting( params.featureSetNumFeatures );
model->setTrackerStateEstimator( stateEstimator );
@endcode
@sa
TrackerModel, TrackerStateEstimatorMILBoosting, TrackerTargetState
During this step, you should define your TrackerTargetState based on your implementation.
TrackerTargetState base class has only the bounding box (upper-left position, width and height), you
can enrich it adding scale factor, target rotation, etc.
Example of creating specialized TrackerTargetState TrackerMILTargetState : :
@code
class TrackerMILTargetState : public TrackerTargetState
{
public:
TrackerMILTargetState( const Point2f& position, int targetWidth, int targetHeight, bool foreground, const Mat& features );
~TrackerMILTargetState();
...
private:
bool isTarget;
Mat targetFeatures;
...
};
@endcode
*/
//! @addtogroup tracking
//! @{
/************************************ TrackerFeature Base Classes ************************************/
@ -517,50 +751,6 @@ class CV_EXPORTS TrackerModel
};
/************************************ Tracker Base Class ************************************/
/** @brief Base abstract class for the long-term tracker:
*/
class CV_EXPORTS_W Tracker : public virtual Algorithm
{
public:
virtual ~Tracker() CV_OVERRIDE;
/** @brief Initialize the tracker with a known bounding box that surrounded the target
@param image The initial frame
@param boundingBox The initial bounding box
@return True if initialization went succesfully, false otherwise
*/
CV_WRAP bool init( InputArray image, const Rect2d& boundingBox );
/** @brief Update the tracker, find the new most likely bounding box for the target
@param image The current frame
@param boundingBox The bounding box that represent the new target location, if true was returned, not
modified otherwise
@return True means that target was located and false means that tracker cannot locate target in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
CV_WRAP bool update( InputArray image, CV_OUT Rect2d& boundingBox );
virtual void read( const FileNode& fn ) CV_OVERRIDE = 0;
virtual void write( FileStorage& fs ) const CV_OVERRIDE = 0;
protected:
virtual bool initImpl( const Mat& image, const Rect2d& boundingBox ) = 0;
virtual bool updateImpl( const Mat& image, Rect2d& boundingBox ) = 0;
bool isInit;
Ptr<TrackerFeatureSet> featureSet;
Ptr<TrackerSampler> sampler;
Ptr<TrackerModel> model;
};
/************************************ Specific TrackerStateEstimator Classes ************************************/
@ -1052,497 +1242,8 @@ class CV_EXPORTS TrackerFeatureLBP : public TrackerFeature
};
/************************************ Specific Tracker Classes ************************************/
/** @brief The MIL algorithm trains a classifier in an online manner to separate the object from the
background.
Multiple Instance Learning avoids the drift problem for a robust tracking. The implementation is
based on @cite MIL .
Original code can be found here <http://vision.ucsd.edu/~bbabenko/project_miltrack.shtml>
*/
class CV_EXPORTS_W TrackerMIL : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
//parameters for sampler
float samplerInitInRadius; //!< radius for gathering positive instances during init
int samplerInitMaxNegNum; //!< # negative samples to use during init
float samplerSearchWinSize; //!< size of search window
float samplerTrackInRadius; //!< radius for gathering positive instances during tracking
int samplerTrackMaxPosNum; //!< # positive samples to use during tracking
int samplerTrackMaxNegNum; //!< # negative samples to use during tracking
int featureSetNumFeatures; //!< # features
void read( const FileNode& fn );
void write( FileStorage& fs ) const;
};
/** @brief Constructor
@param parameters MIL parameters TrackerMIL::Params
*/
static Ptr<TrackerMIL> create(const TrackerMIL::Params &parameters);
CV_WRAP static Ptr<TrackerMIL> create();
virtual ~TrackerMIL() CV_OVERRIDE {}
};
/** @brief the Boosting tracker
This is a real-time object tracking based on a novel on-line version of the AdaBoost algorithm.
The classifier uses the surrounding background as negative examples in update step to avoid the
drifting problem. The implementation is based on @cite OLB .
*/
class CV_EXPORTS_W TrackerBoosting : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
int numClassifiers; //!<the number of classifiers to use in a OnlineBoosting algorithm
float samplerOverlap; //!<search region parameters to use in a OnlineBoosting algorithm
float samplerSearchFactor; //!< search region parameters to use in a OnlineBoosting algorithm
int iterationInit; //!<the initial iterations
int featureSetNumFeatures; //!< # features
/**
* \brief Read parameters from a file
*/
void read( const FileNode& fn );
/**
* \brief Write parameters to a file
*/
void write( FileStorage& fs ) const;
};
/** @brief Constructor
@param parameters BOOSTING parameters TrackerBoosting::Params
*/
static Ptr<TrackerBoosting> create(const TrackerBoosting::Params &parameters);
CV_WRAP static Ptr<TrackerBoosting> create();
virtual ~TrackerBoosting() CV_OVERRIDE {}
};
/** @brief the Median Flow tracker
Implementation of a paper @cite MedianFlow .
The tracker is suitable for very smooth and predictable movements when object is visible throughout
the whole sequence. It's quite and accurate for this type of problems (in particular, it was shown
by authors to outperform MIL). During the implementation period the code at
<http://www.aonsquared.co.uk/node/5>, the courtesy of the author Arthur Amarra, was used for the
reference purpose.
*/
class CV_EXPORTS_W TrackerMedianFlow : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params(); //!<default constructor
//!<note that the default values of parameters are recommended for most of use cases
int pointsInGrid; //!<square root of number of keypoints used; increase it to trade
//!<accurateness for speed
cv::Size winSize; //!<window size parameter for Lucas-Kanade optical flow
int maxLevel; //!<maximal pyramid level number for Lucas-Kanade optical flow
TermCriteria termCriteria; //!<termination criteria for Lucas-Kanade optical flow
cv::Size winSizeNCC; //!<window size around a point for normalized cross-correlation check
double maxMedianLengthOfDisplacementDifference; //!<criterion for loosing the tracked object
void read( const FileNode& /*fn*/ );
void write( FileStorage& /*fs*/ ) const;
};
/** @brief Constructor
@param parameters Median Flow parameters TrackerMedianFlow::Params
*/
static Ptr<TrackerMedianFlow> create(const TrackerMedianFlow::Params &parameters);
CV_WRAP static Ptr<TrackerMedianFlow> create();
virtual ~TrackerMedianFlow() CV_OVERRIDE {}
};
/** @brief the TLD (Tracking, learning and detection) tracker
TLD is a novel tracking framework that explicitly decomposes the long-term tracking task into
tracking, learning and detection.
The tracker follows the object from frame to frame. The detector localizes all appearances that
have been observed so far and corrects the tracker if necessary. The learning estimates detector's
errors and updates it to avoid these errors in the future. The implementation is based on @cite TLD .
The Median Flow algorithm (see cv::TrackerMedianFlow) was chosen as a tracking component in this
implementation, following authors. The tracker is supposed to be able to handle rapid motions, partial
occlusions, object absence etc.
*/
class CV_EXPORTS_W TrackerTLD : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
void read( const FileNode& /*fn*/ );
void write( FileStorage& /*fs*/ ) const;
};
/** @brief Constructor
@param parameters TLD parameters TrackerTLD::Params
*/
static Ptr<TrackerTLD> create(const TrackerTLD::Params &parameters);
CV_WRAP static Ptr<TrackerTLD> create();
virtual ~TrackerTLD() CV_OVERRIDE {}
};
/** @brief the KCF (Kernelized Correlation Filter) tracker
* KCF is a novel tracking framework that utilizes properties of circulant matrix to enhance the processing speed.
* This tracking method is an implementation of @cite KCF_ECCV which is extended to KCF with color-names features (@cite KCF_CN).
* The original paper of KCF is available at <http://www.robots.ox.ac.uk/~joao/publications/henriques_tpami2015.pdf>
* as well as the matlab implementation. For more information about KCF with color-names features, please refer to
* <http://www.cvl.isy.liu.se/research/objrec/visualtracking/colvistrack/index.html>.
*/
class CV_EXPORTS_W TrackerKCF : public Tracker
{
public:
/**
* \brief Feature type to be used in the tracking grayscale, colornames, compressed color-names
* The modes available now:
- "GRAY" -- Use grayscale values as the feature
- "CN" -- Color-names feature
*/
enum MODE {
GRAY = (1 << 0),
CN = (1 << 1),
CUSTOM = (1 << 2)
};
struct CV_EXPORTS Params
{
/**
* \brief Constructor
*/
Params();
/**
* \brief Read parameters from a file
*/
void read(const FileNode& /*fn*/);
/**
* \brief Write parameters to a file
*/
void write(FileStorage& /*fs*/) const;
float detect_thresh; //!< detection confidence threshold
float sigma; //!< gaussian kernel bandwidth
float lambda; //!< regularization
float interp_factor; //!< linear interpolation factor for adaptation
float output_sigma_factor; //!< spatial bandwidth (proportional to target)
float pca_learning_rate; //!< compression learning rate
bool resize; //!< activate the resize feature to improve the processing speed
bool split_coeff; //!< split the training coefficients into two matrices
bool wrap_kernel; //!< wrap around the kernel values
bool compress_feature; //!< activate the pca method to compress the features
int max_patch_size; //!< threshold for the ROI size
int compressed_size; //!< feature size after compression
int desc_pca; //!< compressed descriptors of TrackerKCF::MODE
int desc_npca; //!< non-compressed descriptors of TrackerKCF::MODE
};
virtual void setFeatureExtractor(void(*)(const Mat, const Rect, Mat&), bool pca_func = false) = 0;
/** @brief Constructor
@param parameters KCF parameters TrackerKCF::Params
*/
static Ptr<TrackerKCF> create(const TrackerKCF::Params &parameters);
CV_WRAP static Ptr<TrackerKCF> create();
virtual ~TrackerKCF() CV_OVERRIDE {}
};
/** @brief the GOTURN (Generic Object Tracking Using Regression Networks) tracker
* GOTURN (@cite GOTURN) is kind of trackers based on Convolutional Neural Networks (CNN). While taking all advantages of CNN trackers,
* GOTURN is much faster due to offline training without online fine-tuning nature.
* GOTURN tracker addresses the problem of single target tracking: given a bounding box label of an object in the first frame of the video,
* we track that object through the rest of the video. NOTE: Current method of GOTURN does not handle occlusions; however, it is fairly
* robust to viewpoint changes, lighting changes, and deformations.
* Inputs of GOTURN are two RGB patches representing Target and Search patches resized to 227x227.
* Outputs of GOTURN are predicted bounding box coordinates, relative to Search patch coordinate system, in format X1,Y1,X2,Y2.
* Original paper is here: <http://davheld.github.io/GOTURN/GOTURN.pdf>
* As long as original authors implementation: <https://github.com/davheld/GOTURN#train-the-tracker>
* Implementation of training algorithm is placed in separately here due to 3d-party dependencies:
* <https://github.com/Auron-X/GOTURN_Training_Toolkit>
* GOTURN architecture goturn.prototxt and trained model goturn.caffemodel are accessible on opencv_extra GitHub repository.
*/
class CV_EXPORTS_W TrackerGOTURN : public Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
void read(const FileNode& /*fn*/);
void write(FileStorage& /*fs*/) const;
String modelTxt;
String modelBin;
};
/** @brief Constructor
@param parameters GOTURN parameters TrackerGOTURN::Params
*/
static Ptr<TrackerGOTURN> create(const TrackerGOTURN::Params &parameters);
CV_WRAP static Ptr<TrackerGOTURN> create();
virtual ~TrackerGOTURN() CV_OVERRIDE {}
};
/** @brief the MOSSE (Minimum Output Sum of Squared %Error) tracker
The implementation is based on @cite MOSSE Visual Object Tracking using Adaptive Correlation Filters
@note this tracker works with grayscale images, if passed bgr ones, they will get converted internally.
*/
class CV_EXPORTS_W TrackerMOSSE : public Tracker
{
public:
/** @brief Constructor
*/
CV_WRAP static Ptr<TrackerMOSSE> create();
virtual ~TrackerMOSSE() CV_OVERRIDE {}
};
/************************************ MultiTracker Class ---By Laksono Kurnianggoro---) ************************************/
/** @brief This class is used to track multiple objects using the specified tracker algorithm.
* The %MultiTracker is naive implementation of multiple object tracking.
* It process the tracked objects independently without any optimization accross the tracked objects.
*/
class CV_EXPORTS_W MultiTracker : public Algorithm
{
public:
/**
* \brief Constructor.
*/
CV_WRAP MultiTracker();
/**
* \brief Destructor
*/
~MultiTracker() CV_OVERRIDE;
/**
* \brief Add a new object to be tracked.
*
* @param newTracker tracking algorithm to be used
* @param image input image
* @param boundingBox a rectangle represents ROI of the tracked object
*/
CV_WRAP bool add(Ptr<Tracker> newTracker, InputArray image, const Rect2d& boundingBox);
/**
* \brief Add a set of objects to be tracked.
* @param newTrackers list of tracking algorithms to be used
* @param image input image
* @param boundingBox list of the tracked objects
*/
bool add(std::vector<Ptr<Tracker> > newTrackers, InputArray image, std::vector<Rect2d> boundingBox);
/**
* \brief Update the current tracking status.
* The result will be saved in the internal storage.
* @param image input image
*/
bool update(InputArray image);
/**
* \brief Update the current tracking status.
* @param image input image
* @param boundingBox the tracking result, represent a list of ROIs of the tracked objects.
*/
CV_WRAP bool update(InputArray image, CV_OUT std::vector<Rect2d> & boundingBox);
/**
* \brief Returns a reference to a storage for the tracked objects, each object corresponds to one tracker algorithm
*/
CV_WRAP const std::vector<Rect2d>& getObjects() const;
/**
* \brief Returns a pointer to a new instance of MultiTracker
*/
CV_WRAP static Ptr<MultiTracker> create();
protected:
//!< storage for the tracker algorithms.
std::vector< Ptr<Tracker> > trackerList;
//!< storage for the tracked objects, each object corresponds to one tracker algorithm.
std::vector<Rect2d> objects;
};
/************************************ Multi-Tracker Classes ---By Tyan Vladimir---************************************/
/** @brief Base abstract class for the long-term Multi Object Trackers:
@sa Tracker, MultiTrackerTLD
*/
class CV_EXPORTS MultiTracker_Alt
{
public:
/** @brief Constructor for Multitracker
*/
MultiTracker_Alt()
{
targetNum = 0;
}
/** @brief Add a new target to a tracking-list and initialize the tracker with a known bounding box that surrounded the target
@param image The initial frame
@param boundingBox The initial bounding box of target
@param tracker_algorithm Multi-tracker algorithm
@return True if new target initialization went succesfully, false otherwise
*/
bool addTarget(InputArray image, const Rect2d& boundingBox, Ptr<Tracker> tracker_algorithm);
/** @brief Update all trackers from the tracking-list, find a new most likely bounding boxes for the targets
@param image The current frame
@return True means that all targets were located and false means that tracker couldn't locate one of the targets in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
bool update(InputArray image);
/** @brief Current number of targets in tracking-list
*/
int targetNum;
/** @brief Trackers list for Multi-Object-Tracker
*/
std::vector <Ptr<Tracker> > trackers;
/** @brief Bounding Boxes list for Multi-Object-Tracker
*/
std::vector <Rect2d> boundingBoxes;
/** @brief List of randomly generated colors for bounding boxes display
*/
std::vector<Scalar> colors;
};
/** @brief Multi Object %Tracker for TLD.
TLD is a novel tracking framework that explicitly decomposes
the long-term tracking task into tracking, learning and detection.
The tracker follows the object from frame to frame. The detector localizes all appearances that
have been observed so far and corrects the tracker if necessary. The learning estimates detector's
errors and updates it to avoid these errors in the future. The implementation is based on @cite TLD .
The Median Flow algorithm (see cv::TrackerMedianFlow) was chosen as a tracking component in this
implementation, following authors. The tracker is supposed to be able to handle rapid motions, partial
occlusions, object absence etc.
@sa Tracker, MultiTracker, TrackerTLD
*/
class CV_EXPORTS MultiTrackerTLD : public MultiTracker_Alt
{
public:
/** @brief Update all trackers from the tracking-list, find a new most likely bounding boxes for the targets by
optimized update method using some techniques to speedup calculations specifically for MO TLD. The only limitation
is that all target bounding boxes should have approximately same aspect ratios. Speed boost is around 20%
@param image The current frame.
@return True means that all targets were located and false means that tracker couldn't locate one of the targets in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
bool update_opt(InputArray image);
};
/*********************************** CSRT ************************************/
/** @brief the CSRT tracker
The implementation is based on @cite Lukezic_IJCV2018 Discriminative Correlation Filter with Channel and Spatial Reliability
*/
class CV_EXPORTS_W TrackerCSRT : public Tracker
{
public:
struct CV_EXPORTS Params
{
/**
* \brief Constructor
*/
Params();
/**
* \brief Read parameters from a file
*/
void read(const FileNode& /*fn*/);
/**
* \brief Write parameters to a file
*/
void write(cv::FileStorage& fs) const;
bool use_hog;
bool use_color_names;
bool use_gray;
bool use_rgb;
bool use_channel_weights;
bool use_segmentation;
std::string window_function; //!< Window function: "hann", "cheb", "kaiser"
float kaiser_alpha;
float cheb_attenuation;
float template_size;
float gsl_sigma;
float hog_orientations;
float hog_clip;
float padding;
float filter_lr;
float weights_lr;
int num_hog_channels_used;
int admm_iterations;
int histogram_bins;
float histogram_lr;
int background_ratio;
int number_of_scales;
float scale_sigma_factor;
float scale_model_max_area;
float scale_lr;
float scale_step;
float psr_threshold; //!< we lost the target, if the psr is lower than this.
};
/** @brief Constructor
@param parameters CSRT parameters TrackerCSRT::Params
*/
static Ptr<TrackerCSRT> create(const TrackerCSRT::Params &parameters);
CV_WRAP static Ptr<TrackerCSRT> create();
CV_WRAP virtual void setInitialMask(InputArray mask) = 0;
virtual ~TrackerCSRT() CV_OVERRIDE {}
};
//! @}
} /* namespace cv */
#endif
}}} // namespace
#endif // OPENCV_TRACKING_DETAIL_HPP

@ -0,0 +1,538 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef OPENCV_TRACKING_LEGACY_HPP
#define OPENCV_TRACKING_LEGACY_HPP
/*
* Partially based on:
* ====================================================================================================================
* - [AAM] S. Salti, A. Cavallaro, L. Di Stefano, Adaptive Appearance Modeling for Video Tracking: Survey and Evaluation
* - [AMVOT] X. Li, W. Hu, C. Shen, Z. Zhang, A. Dick, A. van den Hengel, A Survey of Appearance Models in Visual Object Tracking
*
* This Tracking API has been designed with PlantUML. If you modify this API please change UML files under modules/tracking/doc/uml
*
*/
#include "tracking_internals.hpp"
namespace cv {
namespace legacy {
#ifndef CV_DOXYGEN
inline namespace tracking {
#endif
using namespace cv::detail::tracking;
/** @addtogroup tracking_legacy
@{
*/
/************************************ Tracker Base Class ************************************/
/** @brief Base abstract class for the long-term tracker:
*/
class CV_EXPORTS_W Tracker : public virtual Algorithm
{
public:
Tracker();
virtual ~Tracker() CV_OVERRIDE;
/** @brief Initialize the tracker with a known bounding box that surrounded the target
@param image The initial frame
@param boundingBox The initial bounding box
@return True if initialization went succesfully, false otherwise
*/
CV_WRAP bool init( InputArray image, const Rect2d& boundingBox );
/** @brief Update the tracker, find the new most likely bounding box for the target
@param image The current frame
@param boundingBox The bounding box that represent the new target location, if true was returned, not
modified otherwise
@return True means that target was located and false means that tracker cannot locate target in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
CV_WRAP bool update( InputArray image, CV_OUT Rect2d& boundingBox );
virtual void read( const FileNode& fn ) CV_OVERRIDE = 0;
virtual void write( FileStorage& fs ) const CV_OVERRIDE = 0;
protected:
virtual bool initImpl( const Mat& image, const Rect2d& boundingBox ) = 0;
virtual bool updateImpl( const Mat& image, Rect2d& boundingBox ) = 0;
bool isInit;
Ptr<TrackerFeatureSet> featureSet;
Ptr<TrackerSampler> sampler;
Ptr<TrackerModel> model;
};
/************************************ Specific Tracker Classes ************************************/
/** @brief The MIL algorithm trains a classifier in an online manner to separate the object from the
background.
Multiple Instance Learning avoids the drift problem for a robust tracking. The implementation is
based on @cite MIL .
Original code can be found here <http://vision.ucsd.edu/~bbabenko/project_miltrack.shtml>
*/
class CV_EXPORTS_W TrackerMIL : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params : cv::tracking::TrackerMIL::Params
{
void read( const FileNode& fn );
void write( FileStorage& fs ) const;
};
/** @brief Constructor
@param parameters MIL parameters TrackerMIL::Params
*/
static Ptr<legacy::TrackerMIL> create(const TrackerMIL::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerMIL> create();
virtual ~TrackerMIL() CV_OVERRIDE {}
};
/** @brief the Boosting tracker
This is a real-time object tracking based on a novel on-line version of the AdaBoost algorithm.
The classifier uses the surrounding background as negative examples in update step to avoid the
drifting problem. The implementation is based on @cite OLB .
*/
class CV_EXPORTS_W TrackerBoosting : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
int numClassifiers; //!<the number of classifiers to use in a OnlineBoosting algorithm
float samplerOverlap; //!<search region parameters to use in a OnlineBoosting algorithm
float samplerSearchFactor; //!< search region parameters to use in a OnlineBoosting algorithm
int iterationInit; //!<the initial iterations
int featureSetNumFeatures; //!< # features
/**
* \brief Read parameters from a file
*/
void read( const FileNode& fn );
/**
* \brief Write parameters to a file
*/
void write( FileStorage& fs ) const;
};
/** @brief Constructor
@param parameters BOOSTING parameters TrackerBoosting::Params
*/
static Ptr<legacy::TrackerBoosting> create(const TrackerBoosting::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerBoosting> create();
virtual ~TrackerBoosting() CV_OVERRIDE {}
};
/** @brief the Median Flow tracker
Implementation of a paper @cite MedianFlow .
The tracker is suitable for very smooth and predictable movements when object is visible throughout
the whole sequence. It's quite and accurate for this type of problems (in particular, it was shown
by authors to outperform MIL). During the implementation period the code at
<http://www.aonsquared.co.uk/node/5>, the courtesy of the author Arthur Amarra, was used for the
reference purpose.
*/
class CV_EXPORTS_W TrackerMedianFlow : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params
{
Params(); //!<default constructor
//!<note that the default values of parameters are recommended for most of use cases
int pointsInGrid; //!<square root of number of keypoints used; increase it to trade
//!<accurateness for speed
cv::Size winSize; //!<window size parameter for Lucas-Kanade optical flow
int maxLevel; //!<maximal pyramid level number for Lucas-Kanade optical flow
TermCriteria termCriteria; //!<termination criteria for Lucas-Kanade optical flow
cv::Size winSizeNCC; //!<window size around a point for normalized cross-correlation check
double maxMedianLengthOfDisplacementDifference; //!<criterion for loosing the tracked object
void read( const FileNode& /*fn*/ );
void write( FileStorage& /*fs*/ ) const;
};
/** @brief Constructor
@param parameters Median Flow parameters TrackerMedianFlow::Params
*/
static Ptr<legacy::TrackerMedianFlow> create(const TrackerMedianFlow::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerMedianFlow> create();
virtual ~TrackerMedianFlow() CV_OVERRIDE {}
};
/** @brief the TLD (Tracking, learning and detection) tracker
TLD is a novel tracking framework that explicitly decomposes the long-term tracking task into
tracking, learning and detection.
The tracker follows the object from frame to frame. The detector localizes all appearances that
have been observed so far and corrects the tracker if necessary. The learning estimates detector's
errors and updates it to avoid these errors in the future. The implementation is based on @cite TLD .
The Median Flow algorithm (see cv::TrackerMedianFlow) was chosen as a tracking component in this
implementation, following authors. The tracker is supposed to be able to handle rapid motions, partial
occlusions, object absence etc.
*/
class CV_EXPORTS_W TrackerTLD : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
void read( const FileNode& /*fn*/ );
void write( FileStorage& /*fs*/ ) const;
};
/** @brief Constructor
@param parameters TLD parameters TrackerTLD::Params
*/
static Ptr<legacy::TrackerTLD> create(const TrackerTLD::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerTLD> create();
virtual ~TrackerTLD() CV_OVERRIDE {}
};
/** @brief the KCF (Kernelized Correlation Filter) tracker
* KCF is a novel tracking framework that utilizes properties of circulant matrix to enhance the processing speed.
* This tracking method is an implementation of @cite KCF_ECCV which is extended to KCF with color-names features (@cite KCF_CN).
* The original paper of KCF is available at <http://www.robots.ox.ac.uk/~joao/publications/henriques_tpami2015.pdf>
* as well as the matlab implementation. For more information about KCF with color-names features, please refer to
* <http://www.cvl.isy.liu.se/research/objrec/visualtracking/colvistrack/index.html>.
*/
class CV_EXPORTS_W TrackerKCF : public cv::legacy::Tracker
{
public:
/**
* \brief Feature type to be used in the tracking grayscale, colornames, compressed color-names
* The modes available now:
- "GRAY" -- Use grayscale values as the feature
- "CN" -- Color-names feature
*/
typedef enum cv::tracking::TrackerKCF::MODE MODE;
struct CV_EXPORTS Params : cv::tracking::TrackerKCF::Params
{
void read(const FileNode& /*fn*/);
void write(FileStorage& /*fs*/) const;
};
virtual void setFeatureExtractor(void(*)(const Mat, const Rect, Mat&), bool pca_func = false) = 0;
/** @brief Constructor
@param parameters KCF parameters TrackerKCF::Params
*/
static Ptr<legacy::TrackerKCF> create(const TrackerKCF::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerKCF> create();
virtual ~TrackerKCF() CV_OVERRIDE {}
};
#if 0 // legacy variant is not available
/** @brief the GOTURN (Generic Object Tracking Using Regression Networks) tracker
* GOTURN (@cite GOTURN) is kind of trackers based on Convolutional Neural Networks (CNN). While taking all advantages of CNN trackers,
* GOTURN is much faster due to offline training without online fine-tuning nature.
* GOTURN tracker addresses the problem of single target tracking: given a bounding box label of an object in the first frame of the video,
* we track that object through the rest of the video. NOTE: Current method of GOTURN does not handle occlusions; however, it is fairly
* robust to viewpoint changes, lighting changes, and deformations.
* Inputs of GOTURN are two RGB patches representing Target and Search patches resized to 227x227.
* Outputs of GOTURN are predicted bounding box coordinates, relative to Search patch coordinate system, in format X1,Y1,X2,Y2.
* Original paper is here: <http://davheld.github.io/GOTURN/GOTURN.pdf>
* As long as original authors implementation: <https://github.com/davheld/GOTURN#train-the-tracker>
* Implementation of training algorithm is placed in separately here due to 3d-party dependencies:
* <https://github.com/Auron-X/GOTURN_Training_Toolkit>
* GOTURN architecture goturn.prototxt and trained model goturn.caffemodel are accessible on opencv_extra GitHub repository.
*/
class CV_EXPORTS_W TrackerGOTURN : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params
{
Params();
void read(const FileNode& /*fn*/);
void write(FileStorage& /*fs*/) const;
String modelTxt;
String modelBin;
};
/** @brief Constructor
@param parameters GOTURN parameters TrackerGOTURN::Params
*/
static Ptr<legacy::TrackerGOTURN> create(const TrackerGOTURN::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerGOTURN> create();
virtual ~TrackerGOTURN() CV_OVERRIDE {}
};
#endif
/** @brief the MOSSE (Minimum Output Sum of Squared %Error) tracker
The implementation is based on @cite MOSSE Visual Object Tracking using Adaptive Correlation Filters
@note this tracker works with grayscale images, if passed bgr ones, they will get converted internally.
*/
class CV_EXPORTS_W TrackerMOSSE : public cv::legacy::Tracker
{
public:
/** @brief Constructor
*/
CV_WRAP static Ptr<legacy::TrackerMOSSE> create();
virtual ~TrackerMOSSE() CV_OVERRIDE {}
};
/************************************ MultiTracker Class ---By Laksono Kurnianggoro---) ************************************/
/** @brief This class is used to track multiple objects using the specified tracker algorithm.
* The %MultiTracker is naive implementation of multiple object tracking.
* It process the tracked objects independently without any optimization accross the tracked objects.
*/
class CV_EXPORTS_W MultiTracker : public Algorithm
{
public:
/**
* \brief Constructor.
*/
CV_WRAP MultiTracker();
/**
* \brief Destructor
*/
~MultiTracker() CV_OVERRIDE;
/**
* \brief Add a new object to be tracked.
*
* @param newTracker tracking algorithm to be used
* @param image input image
* @param boundingBox a rectangle represents ROI of the tracked object
*/
CV_WRAP bool add(Ptr<cv::legacy::Tracker> newTracker, InputArray image, const Rect2d& boundingBox);
/**
* \brief Add a set of objects to be tracked.
* @param newTrackers list of tracking algorithms to be used
* @param image input image
* @param boundingBox list of the tracked objects
*/
bool add(std::vector<Ptr<legacy::Tracker> > newTrackers, InputArray image, std::vector<Rect2d> boundingBox);
/**
* \brief Update the current tracking status.
* The result will be saved in the internal storage.
* @param image input image
*/
bool update(InputArray image);
/**
* \brief Update the current tracking status.
* @param image input image
* @param boundingBox the tracking result, represent a list of ROIs of the tracked objects.
*/
CV_WRAP bool update(InputArray image, CV_OUT std::vector<Rect2d> & boundingBox);
/**
* \brief Returns a reference to a storage for the tracked objects, each object corresponds to one tracker algorithm
*/
CV_WRAP const std::vector<Rect2d>& getObjects() const;
/**
* \brief Returns a pointer to a new instance of MultiTracker
*/
CV_WRAP static Ptr<MultiTracker> create();
protected:
//!< storage for the tracker algorithms.
std::vector< Ptr<Tracker> > trackerList;
//!< storage for the tracked objects, each object corresponds to one tracker algorithm.
std::vector<Rect2d> objects;
};
/************************************ Multi-Tracker Classes ---By Tyan Vladimir---************************************/
/** @brief Base abstract class for the long-term Multi Object Trackers:
@sa Tracker, MultiTrackerTLD
*/
class CV_EXPORTS MultiTracker_Alt
{
public:
/** @brief Constructor for Multitracker
*/
MultiTracker_Alt()
{
targetNum = 0;
}
/** @brief Add a new target to a tracking-list and initialize the tracker with a known bounding box that surrounded the target
@param image The initial frame
@param boundingBox The initial bounding box of target
@param tracker_algorithm Multi-tracker algorithm
@return True if new target initialization went succesfully, false otherwise
*/
bool addTarget(InputArray image, const Rect2d& boundingBox, Ptr<legacy::Tracker> tracker_algorithm);
/** @brief Update all trackers from the tracking-list, find a new most likely bounding boxes for the targets
@param image The current frame
@return True means that all targets were located and false means that tracker couldn't locate one of the targets in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
bool update(InputArray image);
/** @brief Current number of targets in tracking-list
*/
int targetNum;
/** @brief Trackers list for Multi-Object-Tracker
*/
std::vector <Ptr<Tracker> > trackers;
/** @brief Bounding Boxes list for Multi-Object-Tracker
*/
std::vector <Rect2d> boundingBoxes;
/** @brief List of randomly generated colors for bounding boxes display
*/
std::vector<Scalar> colors;
};
/** @brief Multi Object %Tracker for TLD.
TLD is a novel tracking framework that explicitly decomposes
the long-term tracking task into tracking, learning and detection.
The tracker follows the object from frame to frame. The detector localizes all appearances that
have been observed so far and corrects the tracker if necessary. The learning estimates detector's
errors and updates it to avoid these errors in the future. The implementation is based on @cite TLD .
The Median Flow algorithm (see cv::TrackerMedianFlow) was chosen as a tracking component in this
implementation, following authors. The tracker is supposed to be able to handle rapid motions, partial
occlusions, object absence etc.
@sa Tracker, MultiTracker, TrackerTLD
*/
class CV_EXPORTS MultiTrackerTLD : public MultiTracker_Alt
{
public:
/** @brief Update all trackers from the tracking-list, find a new most likely bounding boxes for the targets by
optimized update method using some techniques to speedup calculations specifically for MO TLD. The only limitation
is that all target bounding boxes should have approximately same aspect ratios. Speed boost is around 20%
@param image The current frame.
@return True means that all targets were located and false means that tracker couldn't locate one of the targets in
current frame. Note, that latter *does not* imply that tracker has failed, maybe target is indeed
missing from the frame (say, out of sight)
*/
bool update_opt(InputArray image);
};
/*********************************** CSRT ************************************/
/** @brief the CSRT tracker
The implementation is based on @cite Lukezic_IJCV2018 Discriminative Correlation Filter with Channel and Spatial Reliability
*/
class CV_EXPORTS_W TrackerCSRT : public cv::legacy::Tracker
{
public:
struct CV_EXPORTS Params : cv::tracking::TrackerCSRT::Params
{
/**
* \brief Read parameters from a file
*/
void read(const FileNode& /*fn*/);
/**
* \brief Write parameters to a file
*/
void write(cv::FileStorage& fs) const;
};
/** @brief Constructor
@param parameters CSRT parameters TrackerCSRT::Params
*/
static Ptr<legacy::TrackerCSRT> create(const TrackerCSRT::Params &parameters);
CV_WRAP static Ptr<legacy::TrackerCSRT> create();
CV_WRAP virtual void setInitialMask(InputArray mask) = 0;
virtual ~TrackerCSRT() CV_OVERRIDE {}
};
CV_EXPORTS_W Ptr<cv::tracking::Tracker> upgradeTrackingAPI(const Ptr<legacy::Tracker>& legacy_tracker);
//! @}
#ifndef CV_DOXYGEN
} // namespace
#endif
}} // namespace
#endif // OPENCV_TRACKING_LEGACY_HPP

@ -0,0 +1,5 @@
{
"namespaces_dict": {
"cv.legacy": "legacy"
}
}

@ -0,0 +1,23 @@
package org.opencv.test.tracking;
import org.opencv.core.Core;
import org.opencv.core.CvException;
import org.opencv.test.OpenCVTestCase;
import org.opencv.tracking.Tracking;
import org.opencv.tracking.legacy_Tracker;
import org.opencv.tracking.legacy_TrackerTLD;
public class TrackerCreateLegacyTest extends OpenCVTestCase {
@Override
protected void setUp() throws Exception {
super.setUp();
}
public void testCreateLegacyTrackerTLD() {
legacy_Tracker tracker = legacy_TrackerTLD.create();
}
}

@ -0,0 +1,38 @@
package org.opencv.test.tracking;
import org.opencv.core.Core;
import org.opencv.core.CvException;
import org.opencv.test.OpenCVTestCase;
import org.opencv.tracking.Tracking;
import org.opencv.tracking.Tracker;
import org.opencv.tracking.TrackerGOTURN;
import org.opencv.tracking.TrackerKCF;
import org.opencv.tracking.TrackerMIL;
public class TrackerCreateTest extends OpenCVTestCase {
@Override
protected void setUp() throws Exception {
super.setUp();
}
public void testCreateTrackerGOTURN() {
try {
Tracker tracker = TrackerGOTURN.create();
assert(tracker != null);
} catch (CvException e) {
// expected, model files may be missing
}
}
public void testCreateTrackerKCF() {
Tracker tracker = TrackerKCF.create();
}
public void testCreateTrackerMIL() {
Tracker tracker = TrackerMIL.create();
}
}

@ -4,5 +4,8 @@
},
"AdditionalImports" : {
"*" : [ "\"tracking.hpp\"" ]
}
},
"namespace_ignore_list" : [
"cv.legacy"
]
}

@ -0,0 +1,6 @@
#ifdef HAVE_OPENCV_TRACKING
typedef TrackerCSRT::Params TrackerCSRT_Params;
typedef TrackerKCF::Params TrackerKCF_Params;
typedef TrackerMIL::Params TrackerMIL_Params;
typedef TrackerGOTURN::Params TrackerGOTURN_Params;
#endif

@ -0,0 +1,31 @@
#!/usr/bin/env python
import os
import numpy as np
import cv2 as cv
from tests_common import NewOpenCVTests, unittest
class tracking_contrib_test(NewOpenCVTests):
def test_createTracker(self):
t = cv.TrackerMIL_create()
t = cv.TrackerKCF_create()
try:
t = cv.TrackerGOTURN_create()
except cv.error as e:
pass # may fail due to missing DL model files
def test_createLegacyTracker(self):
t = cv.legacy.TrackerBoosting_create()
t = cv.legacy.TrackerMIL_create()
t = cv.legacy.TrackerKCF_create()
t = cv.legacy.TrackerMedianFlow_create()
#t = cv.legacy.TrackerGOTURN_create()
t = cv.legacy.TrackerMOSSE_create()
t = cv.legacy.TrackerCSRT_create()
if __name__ == '__main__':
NewOpenCVTests.bootstrap()

@ -1,412 +0,0 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#include "perf_precomp.hpp"
namespace opencv_test { namespace {
//write sanity: ./bin/opencv_perf_tracking --perf_write_sanity=true --perf_min_samples=1
//verify sanity: ./bin/opencv_perf_tracking --perf_min_samples=1
#define TESTSET_NAMES testing::Values("david","dudek","faceocc2")
//#define TESTSET_NAMES testing::internal::ValueArray1<string>("david")
#define SEGMENTS testing::Values(1, 2, 3, 4, 5, 6, 7, 8, 9, 10)
const string TRACKING_DIR = "cv/tracking";
const string FOLDER_IMG = "data";
typedef perf::TestBaseWithParam<tuple<string, int> > tracking;
std::vector<std::string> splitString( std::string s, std::string delimiter )
{
std::vector<string> token;
size_t pos = 0;
while ( ( pos = s.find( delimiter ) ) != std::string::npos )
{
token.push_back( s.substr( 0, pos ) );
s.erase( 0, pos + delimiter.length() );
}
token.push_back( s );
return token;
}
void checkData( const string& datasetMeta, int& startFrame, string& prefix, string& suffix )
{
//get informations on the current test data
FileStorage fs;
fs.open( datasetMeta, FileStorage::READ );
fs["start"] >> startFrame;
fs["prefix"] >> prefix;
fs["suffix"] >> suffix;
fs.release();
}
bool getGroundTruth( const string& gtFile, vector<Rect>& gtBBs )
{
std::ifstream gt;
//open the ground truth
gt.open( gtFile.c_str() );
if( !gt.is_open() )
{
return false;
}
string line;
Rect currentBB;
while ( getline( gt, line ) )
{
vector<string> tokens = splitString( line, "," );
if( tokens.size() != 4 )
{
return false;
}
gtBBs.push_back(
Rect( atoi( tokens.at( 0 ).c_str() ), atoi( tokens.at( 1 ).c_str() ), atoi( tokens.at( 2 ).c_str() ), atoi( tokens.at( 3 ).c_str() ) ) );
}
return true;
}
void getSegment( int segmentId, int numSegments, int bbCounter, int& startFrame, int& endFrame )
{
//compute the start and the and for each segment
int gtStartFrame = startFrame;
int numFrame = bbCounter / numSegments;
startFrame += ( segmentId - 1 ) * numFrame;
endFrame = startFrame + numFrame;
if( ( segmentId ) == numSegments )
endFrame = bbCounter + gtStartFrame - 1;
}
void getMatOfRects( const vector<Rect>& bbs, Mat& bbs_mat )
{
for ( int b = 0, size = (int)bbs.size(); b < size; b++ )
{
bbs_mat.at<float>( b, 0 ) = (float)bbs[b].x;
bbs_mat.at<float>( b, 1 ) = (float)bbs[b].y;
bbs_mat.at<float>( b, 2 ) = (float)bbs[b].width;
bbs_mat.at<float>( b, 3 ) = (float)bbs[b].height;
}
}
PERF_TEST_P(tracking, mil, testing::Combine(TESTSET_NAMES, SEGMENTS))
{
string video = get<0>( GetParam() );
int segmentId = get<1>( GetParam() );
int startFrame;
string prefix;
string suffix;
string datasetMeta = getDataPath( TRACKING_DIR + "/" + video + "/" + video + ".yml" );
checkData( datasetMeta, startFrame, prefix, suffix );
int gtStartFrame = startFrame;
vector<Rect> gtBBs;
string gtFile = getDataPath( TRACKING_DIR + "/" + video + "/gt.txt" );
if( !getGroundTruth( gtFile, gtBBs ) )
FAIL()<< "Ground truth file " << gtFile << " can not be read" << endl;
int bbCounter = (int)gtBBs.size();
Mat frame;
bool initialized = false;
vector<Rect> bbs;
Ptr<Tracker> tracker = TrackerMIL::create();
string folder = TRACKING_DIR + "/" + video + "/" + FOLDER_IMG;
int numSegments = ( sizeof ( SEGMENTS)/sizeof(int) );
int endFrame = 0;
getSegment( segmentId, numSegments, bbCounter, startFrame, endFrame );
Rect currentBBi = gtBBs[startFrame - gtStartFrame];
Rect2d currentBB(currentBBi);
TEST_CYCLE_N(1)
{
VideoCapture c;
c.open( getDataPath( TRACKING_DIR + "/" + video + "/" + FOLDER_IMG + "/" + video + ".webm" ) );
c.set( CAP_PROP_POS_FRAMES, startFrame );
for ( int frameCounter = startFrame; frameCounter < endFrame; frameCounter++ )
{
c >> frame;
if( frame.empty() )
{
break;
}
if( !initialized )
{
if( !tracker->init( frame, currentBB ) )
{
FAIL()<< "Could not initialize tracker" << endl;
return;
}
initialized = true;
}
else if( initialized )
{
tracker->update( frame, currentBB );
}
bbs.push_back( currentBB );
}
}
//save the bounding boxes in a Mat
Mat bbs_mat( (int)bbs.size(), 4, CV_32F );
getMatOfRects( bbs, bbs_mat );
SANITY_CHECK( bbs_mat, 15, ERROR_RELATIVE );
}
PERF_TEST_P(tracking, boosting, testing::Combine(TESTSET_NAMES, SEGMENTS))
{
string video = get<0>( GetParam() );
int segmentId = get<1>( GetParam() );
int startFrame;
string prefix;
string suffix;
string datasetMeta = getDataPath( TRACKING_DIR + "/" + video + "/" + video + ".yml" );
checkData( datasetMeta, startFrame, prefix, suffix );
int gtStartFrame = startFrame;
vector<Rect> gtBBs;
string gtFile = getDataPath( TRACKING_DIR + "/" + video + "/gt.txt" );
if( !getGroundTruth( gtFile, gtBBs ) )
FAIL()<< "Ground truth file " << gtFile << " can not be read" << endl;
int bbCounter = (int)gtBBs.size();
Mat frame;
bool initialized = false;
vector<Rect> bbs;
Ptr<Tracker> tracker = TrackerBoosting::create();
string folder = TRACKING_DIR + "/" + video + "/" + FOLDER_IMG;
int numSegments = ( sizeof ( SEGMENTS)/sizeof(int) );
int endFrame = 0;
getSegment( segmentId, numSegments, bbCounter, startFrame, endFrame );
Rect currentBBi = gtBBs[startFrame - gtStartFrame];
Rect2d currentBB(currentBBi);
TEST_CYCLE_N(1)
{
VideoCapture c;
c.open( getDataPath( TRACKING_DIR + "/" + video + "/" + FOLDER_IMG + "/" + video + ".webm" ) );
c.set( CAP_PROP_POS_FRAMES, startFrame );
for ( int frameCounter = startFrame; frameCounter < endFrame; frameCounter++ )
{
c >> frame;
if( frame.empty() )
{
break;
}
if( !initialized )
{
if( !tracker->init( frame, currentBB ) )
{
FAIL()<< "Could not initialize tracker" << endl;
return;
}
initialized = true;
}
else if( initialized )
{
tracker->update( frame, currentBB );
}
bbs.push_back( currentBB );
}
}
//save the bounding boxes in a Mat
Mat bbs_mat( (int)bbs.size(), 4, CV_32F );
getMatOfRects( bbs, bbs_mat );
SANITY_CHECK( bbs_mat, 15, ERROR_RELATIVE );
}
PERF_TEST_P(tracking, tld, testing::Combine(TESTSET_NAMES, SEGMENTS))
{
string video = get<0>( GetParam() );
int segmentId = get<1>( GetParam() );
int startFrame;
string prefix;
string suffix;
string datasetMeta = getDataPath( TRACKING_DIR + "/" + video + "/" + video + ".yml" );
checkData( datasetMeta, startFrame, prefix, suffix );
int gtStartFrame = startFrame;
vector<Rect> gtBBs;
string gtFile = getDataPath( TRACKING_DIR + "/" + video + "/gt.txt" );
if( !getGroundTruth( gtFile, gtBBs ) )
FAIL()<< "Ground truth file " << gtFile << " can not be read" << endl;
int bbCounter = (int)gtBBs.size();
Mat frame;
bool initialized = false;
vector<Rect> bbs;
Ptr<Tracker> tracker = TrackerTLD::create();
string folder = TRACKING_DIR + "/" + video + "/" + FOLDER_IMG;
int numSegments = ( sizeof ( SEGMENTS)/sizeof(int) );
int endFrame = 0;
getSegment( segmentId, numSegments, bbCounter, startFrame, endFrame );
Rect currentBBi = gtBBs[startFrame - gtStartFrame];
Rect2d currentBB(currentBBi);
TEST_CYCLE_N(1)
{
VideoCapture c;
c.open( getDataPath( TRACKING_DIR + "/" + video + "/" + FOLDER_IMG + "/" + video + ".webm" ) );
c.set( CAP_PROP_POS_FRAMES, startFrame );
for ( int frameCounter = startFrame; frameCounter < endFrame; frameCounter++ )
{
c >> frame;
if( frame.empty() )
{
break;
}
if( !initialized )
{
if( !tracker->init( frame, currentBB ) )
{
FAIL()<< "Could not initialize tracker" << endl;
return;
}
initialized = true;
}
else if( initialized )
{
tracker->update( frame, currentBB );
}
bbs.push_back( currentBB );
}
}
//save the bounding boxes in a Mat
Mat bbs_mat( (int)bbs.size(), 4, CV_32F );
getMatOfRects( bbs, bbs_mat );
SANITY_CHECK( bbs_mat, 15, ERROR_RELATIVE );
}
PERF_TEST_P(tracking, GOTURN, testing::Combine(TESTSET_NAMES, SEGMENTS))
{
string video = get<0>(GetParam());
int segmentId = get<1>(GetParam());
int startFrame;
string prefix;
string suffix;
string datasetMeta = getDataPath(TRACKING_DIR + "/" + video + "/" + video + ".yml");
checkData(datasetMeta, startFrame, prefix, suffix);
int gtStartFrame = startFrame;
vector<Rect> gtBBs;
string gtFile = getDataPath(TRACKING_DIR + "/" + video + "/gt.txt");
if (!getGroundTruth(gtFile, gtBBs))
FAIL() << "Ground truth file " << gtFile << " can not be read" << endl;
int bbCounter = (int)gtBBs.size();
Mat frame;
bool initialized = false;
vector<Rect> bbs;
Ptr<Tracker> tracker = TrackerGOTURN::create();
string folder = TRACKING_DIR + "/" + video + "/" + FOLDER_IMG;
int numSegments = (sizeof(SEGMENTS) / sizeof(int));
int endFrame = 0;
getSegment(segmentId, numSegments, bbCounter, startFrame, endFrame);
Rect currentBBi = gtBBs[startFrame - gtStartFrame];
Rect2d currentBB(currentBBi);
TEST_CYCLE_N(1)
{
VideoCapture c;
c.open(getDataPath(TRACKING_DIR + "/" + video + "/" + FOLDER_IMG + "/" + video + ".webm"));
c.set(CAP_PROP_POS_FRAMES, startFrame);
for (int frameCounter = startFrame; frameCounter < endFrame; frameCounter++)
{
c >> frame;
if (frame.empty())
{
break;
}
if (!initialized)
{
if (!tracker->init(frame, currentBB))
{
FAIL() << "Could not initialize tracker" << endl;
return;
}
initialized = true;
}
else if (initialized)
{
tracker->update(frame, currentBB);
}
bbs.push_back(currentBB);
}
}
//save the bounding boxes in a Mat
Mat bbs_mat((int)bbs.size(), 4, CV_32F);
getMatOfRects(bbs, bbs_mat);
SANITY_CHECK(bbs_mat, 15, ERROR_RELATIVE);
}
}} // namespace

@ -3,4 +3,19 @@
// of this distribution and at http://opencv.org/license.html.
#include "perf_precomp.hpp"
CV_PERF_TEST_MAIN(tracking)
static
void initTrackingTests()
{
const char* extraTestDataPath =
#ifdef WINRT
NULL;
#else
getenv("OPENCV_DNN_TEST_DATA_PATH");
#endif
if (extraTestDataPath)
cvtest::addDataSearchPath(extraTestDataPath);
cvtest::addDataSearchSubDirectory(""); // override "cv" prefix below to access without "../dnn" hacks
}
CV_PERF_TEST_MAIN(tracking, initTrackingTests())

@ -0,0 +1,119 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "perf_precomp.hpp"
#include <opencv2/tracking/tracking_legacy.hpp>
namespace opencv_test { namespace {
using namespace perf;
//using namespace cv::tracking;
typedef tuple<string, int, Rect> TrackingParams_t;
std::vector<TrackingParams_t> getTrackingParams()
{
std::vector<TrackingParams_t> params {
TrackingParams_t("david/data/david.webm", 300, Rect(163,62,47,56)),
TrackingParams_t("dudek/data/dudek.webm", 1, Rect(123,87,132,176)),
TrackingParams_t("faceocc2/data/faceocc2.webm", 1, Rect(118,57,82,98))
};
return params;
}
class Tracking : public perf::TestBaseWithParam<TrackingParams_t>
{
public:
template<typename ROI_t = Rect2d, typename Tracker>
void runTrackingTest(const Ptr<Tracker>& tracker, const TrackingParams_t& params);
};
template<typename ROI_t, typename Tracker>
void Tracking::runTrackingTest(const Ptr<Tracker>& tracker, const TrackingParams_t& params)
{
const int N = 10;
string video = get<0>(params);
int startFrame = get<1>(params);
//int endFrame = startFrame + N;
Rect boundingBox = get<2>(params);
string videoPath = findDataFile(std::string("cv/tracking/") + video);
VideoCapture c;
c.open(videoPath);
ASSERT_TRUE(c.isOpened()) << videoPath;
#if 0
// c.set(CAP_PROP_POS_FRAMES, startFrame);
#else
if (startFrame)
std::cout << "startFrame = " << startFrame << std::endl;
for (int i = 0; i < startFrame; i++)
{
Mat dummy_frame;
c >> dummy_frame;
ASSERT_FALSE(dummy_frame.empty()) << i << ": " << videoPath;
}
#endif
// decode frames into memory (don't measure decoding performance)
std::vector<Mat> frames;
for (int i = 0; i < N; ++i)
{
Mat frame;
c >> frame;
ASSERT_FALSE(frame.empty()) << "i=" << i;
frames.push_back(frame);
}
std::cout << "frame size = " << frames[0].size() << std::endl;
PERF_SAMPLE_BEGIN();
{
tracker->init(frames[0], (ROI_t)boundingBox);
for (int i = 1; i < N; ++i)
{
ROI_t rc;
tracker->update(frames[i], rc);
ASSERT_FALSE(rc.empty());
}
}
PERF_SAMPLE_END();
SANITY_CHECK_NOTHING();
}
//==================================================================================================
PERF_TEST_P(Tracking, MIL, testing::ValuesIn(getTrackingParams()))
{
auto tracker = TrackerMIL::create();
runTrackingTest<Rect>(tracker, GetParam());
}
PERF_TEST_P(Tracking, Boosting, testing::ValuesIn(getTrackingParams()))
{
auto tracker = legacy::TrackerBoosting::create();
runTrackingTest(tracker, GetParam());
}
PERF_TEST_P(Tracking, TLD, testing::ValuesIn(getTrackingParams()))
{
auto tracker = legacy::TrackerTLD::create();
runTrackingTest(tracker, GetParam());
}
PERF_TEST_P(Tracking, GOTURN, testing::ValuesIn(getTrackingParams()))
{
std::string model = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.prototxt");
std::string weights = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.caffemodel", false);
TrackerGOTURN::Params params;
params.modelTxt = model;
params.modelBin = weights;
auto tracker = TrackerGOTURN::create(params);
runTrackingTest<Rect>(tracker, GetParam());
}
}} // namespace

@ -93,7 +93,7 @@ struct AlgoWrap
Ptr<Tracker> tracker;
bool lastRes;
Rect2d lastBox;
Rect lastBox;
State lastState;
// visual
@ -112,14 +112,14 @@ struct AlgoWrap
void eval(const Mat &frame, const Rect2d &gtBox, bool isVerbose)
{
// RUN
lastBox = Rect2d();
lastBox = Rect();
int64 frameTime = getTickCount();
lastRes = tracker->update(frame, lastBox);
frameTime = getTickCount() - frameTime;
// RESULTS
double intersectArea = (gtBox & lastBox).area();
double unionArea = (gtBox | lastBox).area();
double intersectArea = (gtBox & (Rect2d)lastBox).area();
double unionArea = (gtBox | (Rect2d)lastBox).area();
numTotal++;
numResponse += (lastRes && isGoodBox(lastBox)) ? 1 : 0;
numPresent += isGoodBox(gtBox) ? 1 : 0;

@ -41,7 +41,7 @@ int main(int argc, char** argv)
cap >> frame;
// target bounding box
Rect2d roi;
Rect roi;
if (argc > 2) {
// read first line of ground-truth file
std::string groundtruthPath = argv[2];

@ -50,6 +50,7 @@
#include "opencv2/datasets/track_alov.hpp"
#include <opencv2/core/utility.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/tracking.hpp>
#include <opencv2/videoio.hpp>
#include <opencv2/highgui.hpp>
@ -65,7 +66,7 @@ static Mat image;
static bool paused;
static bool selectObjects = false;
static bool startSelection = false;
Rect2d boundingBox;
static Rect boundingBox;
static const char* keys =
{ "{@dataset_path || Dataset path }"
@ -140,7 +141,7 @@ int main(int argc, char *argv[])
setMouseCallback("GOTURN Tracking", onMouse, 0);
//Create GOTURN tracker
Ptr<Tracker> tracker = TrackerGOTURN::create();
auto tracker = TrackerGOTURN::create();
//Load and init full ALOV300++ dataset with a given datasetID, as alternative you can use loadAnnotatedOnly(..)
//to load only frames with labelled ground truth ~ every 5-th frame
@ -181,11 +182,7 @@ int main(int argc, char *argv[])
if (!initialized && selectObjects)
{
//Initialize the tracker and add targets
if (!tracker->init(frame, boundingBox))
{
cout << "Tracker Init Error!!!";
return 0;
}
tracker->init(frame, boundingBox);
rectangle(frame, boundingBox, Scalar(0, 0, 255), 2, 1);
initialized = true;
}

@ -41,7 +41,7 @@ int main( int argc, char** argv ){
// get bounding box
cap >> frame;
Rect2d roi= selectROI("tracker", frame, true, false);
Rect roi = selectROI("tracker", frame, true, false);
//quit if ROI was not selected
if(roi.width==0 || roi.height==0)

@ -148,7 +148,7 @@ int main(int argc, char *argv[])
namedWindow("Tracking API", 0);
setMouseCallback("Tracking API", onMouse, 0);
MultiTrackerTLD mt;
legacy::MultiTrackerTLD mt;
//Init Dataset
Ptr<TRACK_vot> dataset = TRACK_vot::create();
dataset->load(datasetRootPath);
@ -185,7 +185,7 @@ int main(int argc, char *argv[])
//Initialize the tracker and add targets
for (int i = 0; i < (int)boundingBoxes.size(); i++)
{
if (!mt.addTarget(frame, boundingBoxes[i], createTrackerByName(tracker_algorithm)))
if (!mt.addTarget(frame, boundingBoxes[i], createTrackerByName_legacy(tracker_algorithm)))
{
cout << "Trackers Init Error!!!";
return 0;

@ -73,7 +73,7 @@ int main( int argc, char** argv ){
trackingAlg = argv[2];
// create the tracker
MultiTracker trackers;
legacy::MultiTracker trackers;
// container of the tracked objects
vector<Rect> ROIs;
@ -93,10 +93,10 @@ int main( int argc, char** argv ){
if(ROIs.size()<1)
return 0;
std::vector<Ptr<Tracker> > algorithms;
std::vector<Ptr<legacy::Tracker> > algorithms;
for (size_t i = 0; i < ROIs.size(); i++)
{
algorithms.push_back(createTrackerByName(trackingAlg));
algorithms.push_back(createTrackerByName_legacy(trackingAlg));
objects.push_back(ROIs[i]);
}

@ -2,25 +2,28 @@
#define _SAMPLES_UTILITY_HPP_
#include <opencv2/tracking.hpp>
#include <opencv2/tracking/tracking_legacy.hpp>
inline cv::Ptr<cv::Tracker> createTrackerByName(cv::String name)
inline cv::Ptr<cv::Tracker> createTrackerByName(const std::string& name)
{
using namespace cv;
cv::Ptr<cv::Tracker> tracker;
if (name == "KCF")
tracker = cv::TrackerKCF::create();
else if (name == "TLD")
tracker = cv::TrackerTLD::create();
tracker = legacy::upgradeTrackingAPI(legacy::TrackerTLD::create());
else if (name == "BOOSTING")
tracker = cv::TrackerBoosting::create();
tracker = legacy::upgradeTrackingAPI(legacy::TrackerBoosting::create());
else if (name == "MEDIAN_FLOW")
tracker = cv::TrackerMedianFlow::create();
tracker = legacy::upgradeTrackingAPI(legacy::TrackerMedianFlow::create());
else if (name == "MIL")
tracker = cv::TrackerMIL::create();
else if (name == "GOTURN")
tracker = cv::TrackerGOTURN::create();
else if (name == "MOSSE")
tracker = cv::TrackerMOSSE::create();
tracker = legacy::upgradeTrackingAPI(legacy::TrackerMOSSE::create());
else if (name == "CSRT")
tracker = cv::TrackerCSRT::create();
else
@ -29,4 +32,32 @@ inline cv::Ptr<cv::Tracker> createTrackerByName(cv::String name)
return tracker;
}
inline cv::Ptr<cv::legacy::Tracker> createTrackerByName_legacy(const std::string& name)
{
using namespace cv;
cv::Ptr<cv::legacy::Tracker> tracker;
if (name == "KCF")
tracker = legacy::TrackerKCF::create();
else if (name == "TLD")
tracker = legacy::TrackerTLD::create();
else if (name == "BOOSTING")
tracker = legacy::TrackerBoosting::create();
else if (name == "MEDIAN_FLOW")
tracker = legacy::TrackerMedianFlow::create();
else if (name == "MIL")
tracker = legacy::TrackerMIL::create();
else if (name == "GOTURN")
CV_Error(cv::Error::StsNotImplemented, "FIXIT: migration on new API is required");
else if (name == "MOSSE")
tracker = legacy::TrackerMOSSE::create();
else if (name == "CSRT")
tracker = legacy::TrackerCSRT::create();
else
CV_Error(cv::Error::StsBadArg, "Invalid tracking algorithm name\n");
return tracker;
}
#endif

@ -88,7 +88,7 @@ int main( int argc, char** argv ){
namedWindow( "Tracking API", 1 );
Mat image;
Rect2d boundingBox;
Rect boundingBox;
bool paused = false;
//instantiates the specific Tracker
@ -134,11 +134,7 @@ int main( int argc, char** argv ){
if( !initialized )
{
//initializes the tracker
if( !tracker->init( frame, boundingBox ) )
{
cout << "***Could not initialize tracker...***\n";
return -1;
}
tracker->init(frame, boundingBox);
initialized = true;
}
else if( initialized )

@ -66,7 +66,7 @@ using namespace cv::datasets;
//#define RECORD_VIDEO_FLG
static Mat image;
static Rect2d boundingBox;
static Rect boundingBox;
static bool paused;
static bool selectObject = false;
static bool startSelection = false;
@ -186,11 +186,7 @@ int main(int argc, char *argv[])
if (!initialized && selectObject)
{
//initializes the tracker
if (!tracker->init(frame, boundingBox))
{
cout << "***Could not initialize tracker...***\n";
return -1;
}
tracker->init(frame, boundingBox);
initialized = true;
}
else if (initialized)

@ -8,7 +8,8 @@
using namespace std;
using namespace cv;
using namespace cv::tbm;
using namespace cv::detail::tracking;
using namespace cv::detail::tracking::tbm;
static const char* keys =
{ "{video_name | | video name }"
@ -123,7 +124,7 @@ private:
cv::Ptr<ITrackerByMatching>
createTrackerByMatchingWithFastDescriptor() {
cv::tbm::TrackerParams params;
tbm::TrackerParams params;
cv::Ptr<ITrackerByMatching> tracker = createTrackerByMatching(params);

@ -25,7 +25,7 @@ int main( int argc, char** argv ){
}
// declares all required variables
Rect2d roi;
Rect roi;
Mat frame;
//! [param]

@ -1,4 +1,5 @@
#include <opencv2/core/utility.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/tracking.hpp>
#include <opencv2/videoio.hpp>
#include <opencv2/highgui.hpp>
@ -24,7 +25,7 @@ int main( int argc, char** argv ){
// declares all required variables
//! [vars]
Rect2d roi;
Rect roi;
Mat frame;
//! [vars]

@ -40,7 +40,7 @@ int main( int argc, char** argv ){
// create the tracker
//! [create]
MultiTracker trackers;
legacy::MultiTracker trackers;
//! [create]
// container of the tracked objects
@ -67,10 +67,10 @@ int main( int argc, char** argv ){
// initialize the tracker
//! [init]
std::vector<Ptr<Tracker> > algorithms;
std::vector<Ptr<legacy::Tracker> > algorithms;
for (size_t i = 0; i < ROIs.size(); i++)
{
algorithms.push_back(createTrackerByName(trackingAlg));
algorithms.push_back(createTrackerByName_legacy(trackingAlg));
objects.push_back(ROIs[i]);
}

@ -1,5 +1,3 @@
#include "opencv2/core.hpp"
#include "opencv2/core/core_c.h"
#include <algorithm>
#include <typeinfo>
#include <cmath>

@ -42,10 +42,10 @@
#include "precomp.hpp"
#include "opencv2/tracking/kalman_filters.hpp"
namespace cv
{
namespace tracking
{
namespace cv {
namespace detail {
inline namespace tracking {
inline namespace kalman_filters {
void AugmentedUnscentedKalmanFilterParams::
init( int dp, int mp, int cp, double processNoiseCovDiag, double measurementNoiseCovDiag,
@ -394,5 +394,4 @@ Ptr<UnscentedKalmanFilter> createAugmentedUnscentedKalmanFilter(const AugmentedU
return kfu;
}
} // tracking
} // cv
}}}} // namespace

@ -42,8 +42,9 @@
#include "precomp.hpp"
#include "opencv2/tracking/feature.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TODO This implementation is based on apps/traincascade/
@ -309,14 +310,14 @@ void CvHaarEvaluator::FeatureHaar::generateRandomFeature( Size patchSize )
position.y = rand() % ( patchSize.height );
position.x = rand() % ( patchSize.width );
baseDim.width = (int) ( ( 1 - sqrt( 1 - (float) rand() / RAND_MAX ) ) * patchSize.width );
baseDim.height = (int) ( ( 1 - sqrt( 1 - (float) rand() / RAND_MAX ) ) * patchSize.height );
baseDim.width = (int) ( ( 1 - sqrt( 1 - (float) rand() * (float)(1.0 / RAND_MAX) ) ) * patchSize.width );
baseDim.height = (int) ( ( 1 - sqrt( 1 - (float) rand() * (float)(1.0 / RAND_MAX) ) ) * patchSize.height );
//select types
//float probType[11] = {0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0909f, 0.0950f};
float probType[11] =
{ 0.2f, 0.2f, 0.2f, 0.2f, 0.2f, 0.2f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f };
float prob = (float) rand() / RAND_MAX;
float prob = (float) rand() * (float)(1.0 / RAND_MAX);
if( prob < probType[0] )
{
@ -686,7 +687,7 @@ void CvHaarEvaluator::FeatureHaar::generateRandomFeature( Size patchSize )
valid = true;
}
else
CV_Error(CV_StsAssert, "");
CV_Error(Error::StsAssert, "");
}
m_initSize = patchSize;
@ -1069,4 +1070,4 @@ void CvLBPEvaluator::Feature::write( FileStorage &fs ) const
fs << CC_RECT << "[:" << rect.x << rect.y << rect.width << rect.height << "]";
}
} /* namespace cv */
}}} // namespace

@ -42,7 +42,10 @@
#include "precomp.hpp"
#include <stdlib.h>
namespace cv{
namespace cv {
namespace detail {
inline namespace tracking {
const float ColorNames[][10]={
{0.45975f,0.014802f,0.044289f,-0.028193f,0.001151f,-0.0050145f,0.34522f,0.018362f,0.23994f,0.1689f},
{0.47157f,0.021424f,0.041444f,-0.030215f,0.0019002f,-0.0029264f,0.32875f,0.0082059f,0.2502f,0.17007f},
@ -32813,4 +32816,5 @@ namespace cv{
{0.0030858f,-0.016151f,0.013017f,0.0072284f,-0.53357f,0.30985f,0.0041336f,-0.012531f,0.00142f,-0.33842f},
{0.0087778f,-0.015645f,0.004769f,0.011785f,-0.54199f,0.31505f,0.00020476f,-0.020282f,0.00021236f,-0.34675f}
};
}
}}} // namespace

@ -38,96 +38,75 @@
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#include "opencv2/opencv_modules.hpp"
#include "gtrTracker.hpp"
#include "precomp.hpp"
#ifdef HAVE_OPENCV_DNN
#include "opencv2/dnn.hpp"
#endif
namespace cv
{
namespace cv {
inline namespace tracking {
TrackerGOTURN::Params::Params()
TrackerGOTURN::TrackerGOTURN()
{
modelTxt = "goturn.prototxt";
modelBin = "goturn.caffemodel";
// nothing
}
void TrackerGOTURN::Params::read(const cv::FileNode& /*fn*/){}
void TrackerGOTURN::Params::write(cv::FileStorage& /*fs*/) const {}
Ptr<TrackerGOTURN> TrackerGOTURN::create(const TrackerGOTURN::Params &parameters)
TrackerGOTURN::~TrackerGOTURN()
{
#ifdef HAVE_OPENCV_DNN
return Ptr<gtr::TrackerGOTURNImpl>(new gtr::TrackerGOTURNImpl(parameters));
#else
(void)(parameters);
CV_Error(cv::Error::StsNotImplemented , "to use GOTURN, the tracking module needs to be built with opencv_dnn !");
#endif
// nothing
}
Ptr<TrackerGOTURN> TrackerGOTURN::create()
TrackerGOTURN::Params::Params()
{
return TrackerGOTURN::create(TrackerGOTURN::Params());
modelTxt = "goturn.prototxt";
modelBin = "goturn.caffemodel";
}
#ifdef HAVE_OPENCV_DNN
namespace gtr
{
class TrackerGOTURNModel : public TrackerModel{
class TrackerGOTURNImpl : public TrackerGOTURN
{
public:
TrackerGOTURNModel(TrackerGOTURN::Params){}
Rect2d getBoundingBox(){ return boundingBox_; }
void setBoudingBox(Rect2d boundingBox) {
TrackerGOTURNImpl(const TrackerGOTURN::Params &parameters)
: params(parameters)
{
// Load GOTURN architecture from *.prototxt and pretrained weights from *.caffemodel
net = dnn::readNetFromCaffe(params.modelTxt, params.modelBin);
CV_Assert(!net.empty());
}
void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
bool update(InputArray image, Rect& boundingBox) CV_OVERRIDE;
void setBoudingBox(Rect boundingBox)
{
if (image_.empty())
CV_Error(Error::StsInternal, "Set image first");
boundingBox_ = boundingBox & Rect2d(Point(0, 0), image_.size());
boundingBox_ = boundingBox & Rect(Point(0, 0), image_.size());
}
Mat getImage(){ return image_; }
void setImage(const Mat& image){ image.copyTo(image_); }
protected:
Rect2d boundingBox_;
Mat image_;
void modelEstimationImpl(const std::vector<Mat>&) CV_OVERRIDE {}
void modelUpdateImpl() CV_OVERRIDE {}
};
TrackerGOTURNImpl::TrackerGOTURNImpl(const TrackerGOTURN::Params &parameters) :
params(parameters){
isInit = false;
};
void TrackerGOTURNImpl::read(const cv::FileNode& fn)
{
params.read(fn);
}
TrackerGOTURN::Params params;
void TrackerGOTURNImpl::write(cv::FileStorage& fs) const
{
params.write(fs);
}
dnn::Net net;
Rect boundingBox_;
Mat image_;
};
bool TrackerGOTURNImpl::initImpl(const Mat& image, const Rect2d& boundingBox)
void TrackerGOTURNImpl::init(InputArray image, const Rect& boundingBox)
{
//Make a simple model from frame and bounding box
model = Ptr<TrackerGOTURNModel>(new TrackerGOTURNModel(params));
((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->setImage(image);
((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->setBoudingBox(boundingBox);
//Load GOTURN architecture from *.prototxt and pretrained weights from *.caffemodel
net = dnn::readNetFromCaffe(params.modelTxt, params.modelBin);
return true;
image_ = image.getMat().clone();
setBoudingBox(boundingBox);
}
bool TrackerGOTURNImpl::updateImpl(const Mat& image, Rect2d& boundingBox)
bool TrackerGOTURNImpl::update(InputArray image, Rect& boundingBox)
{
int INPUT_SIZE = 227;
//Using prevFrame & prevBB from model and curFrame GOTURN calculating curBB
Mat curFrame = image.clone();
Mat prevFrame = ((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->getImage();
Rect2d prevBB = ((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->getBoundingBox();
Rect2d curBB;
InputArray curFrame = image;
Mat prevFrame = image_;
Rect2d prevBB = boundingBox_;
Rect curBB;
float padTargetPatch = 2.0;
Rect2f searchPatchRect, targetPatchRect;
@ -154,12 +133,12 @@ bool TrackerGOTURNImpl::updateImpl(const Mat& image, Rect2d& boundingBox)
copyMakeBorder(curFrame, curFramePadded, (int)targetPatchRect.height, (int)targetPatchRect.height, (int)targetPatchRect.width, (int)targetPatchRect.width, BORDER_REPLICATE);
searchPatch = curFramePadded(targetPatchRect).clone();
//Preprocess
//Resize
// Preprocess
// Resize
resize(targetPatch, targetPatch, Size(INPUT_SIZE, INPUT_SIZE), 0, 0, INTER_LINEAR_EXACT);
resize(searchPatch, searchPatch, Size(INPUT_SIZE, INPUT_SIZE), 0, 0, INTER_LINEAR_EXACT);
//Convert to Float type and subtract mean
// Convert to Float type and subtract mean
Mat targetBlob = dnn::blobFromImage(targetPatch, 1.0f, Size(), Scalar::all(128), false);
Mat searchBlob = dnn::blobFromImage(searchPatch, 1.0f, Size(), Scalar::all(128), false);
@ -168,22 +147,31 @@ bool TrackerGOTURNImpl::updateImpl(const Mat& image, Rect2d& boundingBox)
Mat resMat = net.forward("scale").reshape(1, 1);
curBB.x = targetPatchRect.x + (resMat.at<float>(0) * targetPatchRect.width / INPUT_SIZE) - targetPatchRect.width;
curBB.y = targetPatchRect.y + (resMat.at<float>(1) * targetPatchRect.height / INPUT_SIZE) - targetPatchRect.height;
curBB.width = (resMat.at<float>(2) - resMat.at<float>(0)) * targetPatchRect.width / INPUT_SIZE;
curBB.height = (resMat.at<float>(3) - resMat.at<float>(1)) * targetPatchRect.height / INPUT_SIZE;
curBB.x = cvRound(targetPatchRect.x + (resMat.at<float>(0) * targetPatchRect.width / INPUT_SIZE) - targetPatchRect.width);
curBB.y = cvRound(targetPatchRect.y + (resMat.at<float>(1) * targetPatchRect.height / INPUT_SIZE) - targetPatchRect.height);
curBB.width = cvRound((resMat.at<float>(2) - resMat.at<float>(0)) * targetPatchRect.width / INPUT_SIZE);
curBB.height = cvRound((resMat.at<float>(3) - resMat.at<float>(1)) * targetPatchRect.height / INPUT_SIZE);
//Predicted BB
boundingBox = curBB;
//Set new model image and BB from current frame
((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->setImage(curFrame);
((TrackerGOTURNModel*)static_cast<TrackerModel*>(model))->setBoudingBox(curBB);
// Predicted BB
boundingBox = curBB & Rect(Point(0, 0), image_.size());
// Set new model image and BB from current frame
image_ = image.getMat().clone();
setBoudingBox(curBB);
return true;
}
Ptr<TrackerGOTURN> TrackerGOTURN::create(const TrackerGOTURN::Params& parameters)
{
return makePtr<TrackerGOTURNImpl>(parameters);
}
#else // OPENCV_HAVE_DNN
Ptr<TrackerGOTURN> TrackerGOTURN::create(const TrackerGOTURN::Params& parameters)
{
(void)(parameters);
CV_Error(cv::Error::StsNotImplemented, "to use GOTURN, the tracking module needs to be built with opencv_dnn !");
}
#endif // OPENCV_HAVE_DNN
}
}} // namespace

@ -1,80 +0,0 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef OPENCV_GOTURN_TRACKER
#define OPENCV_GOTURN_TRACKER
#include "precomp.hpp"
#include "opencv2/video/tracking.hpp"
#include "gtrUtils.hpp"
#include "opencv2/imgproc.hpp"
#include <algorithm>
#include <limits.h>
#include "opencv2/opencv_modules.hpp"
#ifdef HAVE_OPENCV_DNN
#include "opencv2/dnn.hpp"
namespace cv
{
namespace gtr
{
class TrackerGOTURNImpl : public TrackerGOTURN
{
public:
TrackerGOTURNImpl(const TrackerGOTURN::Params &parameters = TrackerGOTURN::Params());
void read(const FileNode& fn) CV_OVERRIDE;
void write(FileStorage& fs) const CV_OVERRIDE;
bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE;
bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE;
TrackerGOTURN::Params params;
dnn::Net net;
};
}
}
#endif
#endif

@ -39,6 +39,7 @@
//
//M*/
#include "precomp.hpp"
#include "gtrUtils.hpp"

@ -1,7 +1,6 @@
#ifndef OPENCV_GTR_UTILS
#define OPENCV_GTR_UTILS
#include "precomp.hpp"
#include <vector>
namespace cv

@ -2,12 +2,17 @@
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "precomp.hpp"
#include "kuhn_munkres.hpp"
#include <algorithm>
#include <limits>
#include <vector>
namespace cv {
namespace detail {
inline namespace tracking {
KuhnMunkres::KuhnMunkres() : n_() {}
std::vector<size_t> KuhnMunkres::Solve(const cv::Mat& dissimilarity_matrix) {
@ -166,3 +171,6 @@ void KuhnMunkres::Run() {
}
}
}
}}} // namespace

@ -10,6 +10,9 @@
#include <memory>
#include <vector>
namespace cv {
namespace detail {
inline namespace tracking {
///
/// \brief The KuhnMunkres class
@ -52,4 +55,6 @@ private:
int FindInCol(int col, int what);
void Run();
};
}}} // namespace
#endif // #ifndef __OPENCV_TRACKING_KUHN_MUNKRES_HPP__

@ -0,0 +1,140 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
Tracker::Tracker()
{
isInit = false;
}
Tracker::~Tracker()
{
}
bool Tracker::init( InputArray image, const Rect2d& boundingBox )
{
if( isInit )
{
return false;
}
if( image.empty() )
return false;
sampler = Ptr<TrackerSampler>( new TrackerSampler() );
featureSet = Ptr<TrackerFeatureSet>( new TrackerFeatureSet() );
model = Ptr<TrackerModel>();
bool initTracker = initImpl( image.getMat(), boundingBox );
//check if the model component is initialized
if (!model)
{
CV_Error( -1, "The model is not initialized" );
}
if( initTracker )
{
isInit = true;
}
return initTracker;
}
bool Tracker::update( InputArray image, Rect2d& boundingBox )
{
if( !isInit )
{
return false;
}
if( image.empty() )
return false;
return updateImpl( image.getMat(), boundingBox );
}
class LegacyTrackerWrapper : public cv::tracking::Tracker
{
const Ptr<legacy::Tracker> legacy_tracker_;
public:
LegacyTrackerWrapper(const Ptr<legacy::Tracker>& legacy_tracker) : legacy_tracker_(legacy_tracker)
{
CV_Assert(legacy_tracker_);
}
virtual ~LegacyTrackerWrapper() CV_OVERRIDE {};
void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE
{
CV_DbgAssert(legacy_tracker_);
legacy_tracker_->init(image, (Rect2d)boundingBox);
}
bool update(InputArray image, CV_OUT Rect& boundingBox) CV_OVERRIDE
{
CV_DbgAssert(legacy_tracker_);
Rect2d boundingBox2d;
bool res = legacy_tracker_->update(image, boundingBox2d);
int x1 = cvRound(boundingBox2d.x);
int y1 = cvRound(boundingBox2d.y);
int x2 = cvRound(boundingBox2d.x + boundingBox2d.width);
int y2 = cvRound(boundingBox2d.y + boundingBox2d.height);
boundingBox = Rect(x1, y1, x2 - x1, y2 - y1) & Rect(Point(0, 0), image.size());
return res;
}
};
CV_EXPORTS_W Ptr<cv::tracking::Tracker> upgradeTrackingAPI(const Ptr<legacy::Tracker>& legacy_tracker)
{
return makePtr<LegacyTrackerWrapper>(legacy_tracker);
}
}}} // namespace

@ -0,0 +1,159 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
namespace impl {
class TrackerCSRTImpl CV_FINAL : public legacy::TrackerCSRT
{
public:
cv::tracking::impl::TrackerCSRTImpl impl;
TrackerCSRTImpl(const legacy::TrackerCSRT::Params &parameters)
: impl(parameters)
{
isInit = false;
}
void read(const FileNode& fn) CV_OVERRIDE
{
static_cast<legacy::TrackerCSRT::Params&>(impl.params).read(fn);
}
void write(FileStorage& fs) const CV_OVERRIDE
{
static_cast<const legacy::TrackerCSRT::Params&>(impl.params).write(fs);
}
bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE
{
impl.init(image, boundingBox);
model = impl.model;
sampler = makePtr<TrackerSampler>();
featureSet = makePtr<TrackerFeatureSet>();
isInit = true;
return true;
}
bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE
{
Rect bb;
bool res = impl.update(image, bb);
boundingBox = bb;
return res;
}
virtual void setInitialMask(InputArray mask) CV_OVERRIDE
{
impl.setInitialMask(mask);
}
};
} // namespace
void legacy::TrackerCSRT::Params::read(const FileNode& fn)
{
*this = TrackerCSRT::Params();
if(!fn["padding"].empty())
fn["padding"] >> padding;
if(!fn["template_size"].empty())
fn["template_size"] >> template_size;
if(!fn["gsl_sigma"].empty())
fn["gsl_sigma"] >> gsl_sigma;
if(!fn["hog_orientations"].empty())
fn["hog_orientations"] >> hog_orientations;
if(!fn["num_hog_channels_used"].empty())
fn["num_hog_channels_used"] >> num_hog_channels_used;
if(!fn["hog_clip"].empty())
fn["hog_clip"] >> hog_clip;
if(!fn["use_hog"].empty())
fn["use_hog"] >> use_hog;
if(!fn["use_color_names"].empty())
fn["use_color_names"] >> use_color_names;
if(!fn["use_gray"].empty())
fn["use_gray"] >> use_gray;
if(!fn["use_rgb"].empty())
fn["use_rgb"] >> use_rgb;
if(!fn["window_function"].empty())
fn["window_function"] >> window_function;
if(!fn["kaiser_alpha"].empty())
fn["kaiser_alpha"] >> kaiser_alpha;
if(!fn["cheb_attenuation"].empty())
fn["cheb_attenuation"] >> cheb_attenuation;
if(!fn["filter_lr"].empty())
fn["filter_lr"] >> filter_lr;
if(!fn["admm_iterations"].empty())
fn["admm_iterations"] >> admm_iterations;
if(!fn["number_of_scales"].empty())
fn["number_of_scales"] >> number_of_scales;
if(!fn["scale_sigma_factor"].empty())
fn["scale_sigma_factor"] >> scale_sigma_factor;
if(!fn["scale_model_max_area"].empty())
fn["scale_model_max_area"] >> scale_model_max_area;
if(!fn["scale_lr"].empty())
fn["scale_lr"] >> scale_lr;
if(!fn["scale_step"].empty())
fn["scale_step"] >> scale_step;
if(!fn["use_channel_weights"].empty())
fn["use_channel_weights"] >> use_channel_weights;
if(!fn["weights_lr"].empty())
fn["weights_lr"] >> weights_lr;
if(!fn["use_segmentation"].empty())
fn["use_segmentation"] >> use_segmentation;
if(!fn["histogram_bins"].empty())
fn["histogram_bins"] >> histogram_bins;
if(!fn["background_ratio"].empty())
fn["background_ratio"] >> background_ratio;
if(!fn["histogram_lr"].empty())
fn["histogram_lr"] >> histogram_lr;
if(!fn["psr_threshold"].empty())
fn["psr_threshold"] >> psr_threshold;
CV_Assert(number_of_scales % 2 == 1);
CV_Assert(use_gray || use_color_names || use_hog || use_rgb);
}
void legacy::TrackerCSRT::Params::write(FileStorage& fs) const
{
fs << "padding" << padding;
fs << "template_size" << template_size;
fs << "gsl_sigma" << gsl_sigma;
fs << "hog_orientations" << hog_orientations;
fs << "num_hog_channels_used" << num_hog_channels_used;
fs << "hog_clip" << hog_clip;
fs << "use_hog" << use_hog;
fs << "use_color_names" << use_color_names;
fs << "use_gray" << use_gray;
fs << "use_rgb" << use_rgb;
fs << "window_function" << window_function;
fs << "kaiser_alpha" << kaiser_alpha;
fs << "cheb_attenuation" << cheb_attenuation;
fs << "filter_lr" << filter_lr;
fs << "admm_iterations" << admm_iterations;
fs << "number_of_scales" << number_of_scales;
fs << "scale_sigma_factor" << scale_sigma_factor;
fs << "scale_model_max_area" << scale_model_max_area;
fs << "scale_lr" << scale_lr;
fs << "scale_step" << scale_step;
fs << "use_channel_weights" << use_channel_weights;
fs << "weights_lr" << weights_lr;
fs << "use_segmentation" << use_segmentation;
fs << "histogram_bins" << histogram_bins;
fs << "background_ratio" << background_ratio;
fs << "histogram_lr" << histogram_lr;
fs << "psr_threshold" << psr_threshold;
}
}} // namespace
Ptr<legacy::TrackerCSRT> legacy::TrackerCSRT::create(const legacy::TrackerCSRT::Params &parameters)
{
return makePtr<legacy::tracking::impl::TrackerCSRTImpl>(parameters);
}
Ptr<legacy::TrackerCSRT> legacy::TrackerCSRT::create()
{
return create(legacy::TrackerCSRT::Params());
}
} // namespace

@ -0,0 +1,173 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
namespace impl {
/*---------------------------
| TrackerKCF
|---------------------------*/
class TrackerKCFImpl CV_FINAL : public legacy::TrackerKCF
{
public:
cv::tracking::impl::TrackerKCFImpl impl;
TrackerKCFImpl(const legacy::TrackerKCF::Params &parameters)
: impl(parameters)
{
isInit = false;
}
void read(const FileNode& fn) CV_OVERRIDE
{
static_cast<legacy::TrackerKCF::Params&>(impl.params).read(fn);
}
void write(FileStorage& fs) const CV_OVERRIDE
{
static_cast<const legacy::TrackerKCF::Params&>(impl.params).write(fs);
}
bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE
{
impl.init(image, boundingBox);
model = impl.model;
sampler = makePtr<TrackerSampler>();
featureSet = makePtr<TrackerFeatureSet>();
isInit = true;
return true;
}
bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE
{
Rect bb;
bool res = impl.update(image, bb);
boundingBox = bb;
return res;
}
void setFeatureExtractor(void (*f)(const Mat, const Rect, Mat&), bool pca_func = false) CV_OVERRIDE
{
impl.setFeatureExtractor(f, pca_func);
}
};
} // namespace
void legacy::TrackerKCF::Params::read(const cv::FileNode& fn)
{
*this = TrackerKCF::Params();
if (!fn["detect_thresh"].empty())
fn["detect_thresh"] >> detect_thresh;
if (!fn["sigma"].empty())
fn["sigma"] >> sigma;
if (!fn["lambda"].empty())
fn["lambda"] >> lambda;
if (!fn["interp_factor"].empty())
fn["interp_factor"] >> interp_factor;
if (!fn["output_sigma_factor"].empty())
fn["output_sigma_factor"] >> output_sigma_factor;
if (!fn["resize"].empty())
fn["resize"] >> resize;
if (!fn["max_patch_size"].empty())
fn["max_patch_size"] >> max_patch_size;
if (!fn["split_coeff"].empty())
fn["split_coeff"] >> split_coeff;
if (!fn["wrap_kernel"].empty())
fn["wrap_kernel"] >> wrap_kernel;
if (!fn["desc_npca"].empty())
fn["desc_npca"] >> desc_npca;
if (!fn["desc_pca"].empty())
fn["desc_pca"] >> desc_pca;
if (!fn["compress_feature"].empty())
fn["compress_feature"] >> compress_feature;
if (!fn["compressed_size"].empty())
fn["compressed_size"] >> compressed_size;
if (!fn["pca_learning_rate"].empty())
fn["pca_learning_rate"] >> pca_learning_rate;
}
void legacy::TrackerKCF::Params::write(cv::FileStorage& fs) const
{
fs << "detect_thresh" << detect_thresh;
fs << "sigma" << sigma;
fs << "lambda" << lambda;
fs << "interp_factor" << interp_factor;
fs << "output_sigma_factor" << output_sigma_factor;
fs << "resize" << resize;
fs << "max_patch_size" << max_patch_size;
fs << "split_coeff" << split_coeff;
fs << "wrap_kernel" << wrap_kernel;
fs << "desc_npca" << desc_npca;
fs << "desc_pca" << desc_pca;
fs << "compress_feature" << compress_feature;
fs << "compressed_size" << compressed_size;
fs << "pca_learning_rate" << pca_learning_rate;
}
}} // namespace legacy::tracking
Ptr<legacy::TrackerKCF> legacy::TrackerKCF::create(const legacy::TrackerKCF::Params &parameters)
{
return makePtr<legacy::tracking::impl::TrackerKCFImpl>(parameters);
}
Ptr<legacy::TrackerKCF> legacy::TrackerKCF::create()
{
return create(legacy::TrackerKCF::Params());
}
}

@ -0,0 +1,122 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
namespace impl {
class TrackerMILImpl CV_FINAL : public legacy::TrackerMIL
{
public:
cv::tracking::impl::TrackerMILImpl impl;
TrackerMILImpl(const legacy::TrackerMIL::Params &parameters)
: impl(parameters)
{
isInit = false;
}
void read(const FileNode& fn) CV_OVERRIDE
{
static_cast<legacy::TrackerMIL::Params&>(impl.params).read(fn);
}
void write(FileStorage& fs) const CV_OVERRIDE
{
static_cast<const legacy::TrackerMIL::Params&>(impl.params).write(fs);
}
bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE
{
impl.init(image, boundingBox);
model = impl.model;
featureSet = impl.featureSet;
sampler = impl.sampler;
isInit = true;
return true;
}
bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE
{
Rect bb;
bool res = impl.update(image, bb);
boundingBox = bb;
return res;
}
};
} // namespace
void legacy::TrackerMIL::Params::read(const cv::FileNode& fn)
{
samplerInitInRadius = fn["samplerInitInRadius"];
samplerSearchWinSize = fn["samplerSearchWinSize"];
samplerInitMaxNegNum = fn["samplerInitMaxNegNum"];
samplerTrackInRadius = fn["samplerTrackInRadius"];
samplerTrackMaxPosNum = fn["samplerTrackMaxPosNum"];
samplerTrackMaxNegNum = fn["samplerTrackMaxNegNum"];
featureSetNumFeatures = fn["featureSetNumFeatures"];
}
void legacy::TrackerMIL::Params::write(cv::FileStorage& fs) const
{
fs << "samplerInitInRadius" << samplerInitInRadius;
fs << "samplerSearchWinSize" << samplerSearchWinSize;
fs << "samplerInitMaxNegNum" << samplerInitMaxNegNum;
fs << "samplerTrackInRadius" << samplerTrackInRadius;
fs << "samplerTrackMaxPosNum" << samplerTrackMaxPosNum;
fs << "samplerTrackMaxNegNum" << samplerTrackMaxNegNum;
fs << "featureSetNumFeatures" << featureSetNumFeatures;
}
}} // namespace
Ptr<legacy::TrackerMIL> legacy::TrackerMIL::create(const legacy::TrackerMIL::Params &parameters)
{
return makePtr<legacy::tracking::impl::TrackerMILImpl>(parameters);
}
Ptr<legacy::TrackerMIL> legacy::TrackerMIL::create()
{
return create(legacy::TrackerMIL::Params());
}
} // namespace

@ -13,24 +13,28 @@
// Cracki: for the idea of only converting the used patch to gray
//
#include "opencv2/tracking.hpp"
#include "precomp.hpp"
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace tracking {
inline namespace tracking {
namespace impl {
namespace {
struct DummyModel : TrackerModel
struct DummyModel : detail::tracking::TrackerModel
{
virtual void modelUpdateImpl() CV_OVERRIDE {}
virtual void modelEstimationImpl( const std::vector<Mat>& ) CV_OVERRIDE {}
};
const double eps=0.00001; // for normalization
const double rate=0.2; // learning rate
const double psrThreshold=5.7; // no detection, if PSR is smaller than this
} // namespace
struct MosseImpl CV_FINAL : TrackerMOSSE
struct MosseImpl CV_FINAL : legacy::TrackerMOSSE
{
protected:
@ -237,13 +241,12 @@ public:
}; // MosseImpl
} // tracking
}} // namespace
Ptr<TrackerMOSSE> TrackerMOSSE::create()
Ptr<legacy::tracking::TrackerMOSSE> legacy::tracking::TrackerMOSSE::create()
{
return makePtr<tracking::MosseImpl>();
return makePtr<impl::MosseImpl>();
}
} // cv
} // namespace

@ -39,10 +39,17 @@
//
//M*/
#include "precomp.hpp"
#include "multiTracker.hpp"
namespace cv
{
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
using namespace impl;
//Multitracker
bool MultiTracker_Alt::addTarget(InputArray image, const Rect2d& boundingBox, Ptr<Tracker> tracker_algorithm)
{
@ -249,12 +256,18 @@ namespace cv
return success;
}
}} // namespace
inline namespace tracking {
namespace impl {
void detect_all(const Mat& img, const Mat& imgBlurred, std::vector<Rect2d>& res, std::vector < std::vector < tld::TLDDetector::LabeledPatch > > &patches, std::vector<bool> &detect_flgs,
std::vector<Ptr<Tracker> > &trackers)
std::vector<Ptr<legacy::Tracker> > &trackers)
{
//TLD Tracker data extraction
Tracker* trackerPtr = trackers[0];
cv::tld::TrackerTLDImpl* tracker = static_cast<tld::TrackerTLDImpl*>(trackerPtr);
legacy::Tracker* trackerPtr = trackers[0];
tld::TrackerTLDImpl* tracker = static_cast<tld::TrackerTLDImpl*>(trackerPtr);
//TLD Model Extraction
tld::TrackerTLDModel* tldModel = ((tld::TrackerTLDModel*)static_cast<TrackerModel*>(tracker->getModel()));
Size initSize = tldModel->getMinSize();
@ -445,11 +458,11 @@ namespace cv
#ifdef HAVE_OPENCL
void ocl_detect_all(const Mat& img, const Mat& imgBlurred, std::vector<Rect2d>& res, std::vector < std::vector < tld::TLDDetector::LabeledPatch > > &patches, std::vector<bool> &detect_flgs,
std::vector<Ptr<Tracker> > &trackers)
std::vector<Ptr<legacy::Tracker> > &trackers)
{
//TLD Tracker data extraction
Tracker* trackerPtr = trackers[0];
cv::tld::TrackerTLDImpl* tracker = static_cast<tld::TrackerTLDImpl*>(trackerPtr);
legacy::Tracker* trackerPtr = trackers[0];
tld::TrackerTLDImpl* tracker = static_cast<tld::TrackerTLDImpl*>(trackerPtr);
//TLD Model Extraction
tld::TrackerTLDModel* tldModel = ((tld::TrackerTLDModel*)static_cast<TrackerModel*>(tracker->getModel()));
Size initSize = tldModel->getMinSize();
@ -656,4 +669,4 @@ namespace cv
}
#endif
}
}}} // namespace

@ -42,18 +42,18 @@
#ifndef OPENCV_MULTITRACKER
#define OPENCV_MULTITRACKER
#include "precomp.hpp"
#include "tldTracker.hpp"
#include "tldUtils.hpp"
#include <math.h>
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
void detect_all(const Mat& img, const Mat& imgBlurred, std::vector<Rect2d>& res, std::vector < std::vector < tld::TLDDetector::LabeledPatch > > &patches,
std::vector<bool>& detect_flgs, std::vector<Ptr<Tracker> >& trackers);
std::vector<bool>& detect_flgs, std::vector<Ptr<legacy::Tracker> >& trackers);
#ifdef HAVE_OPENCL
void ocl_detect_all(const Mat& img, const Mat& imgBlurred, std::vector<Rect2d>& res, std::vector < std::vector < tld::TLDDetector::LabeledPatch > > &patches,
std::vector<bool>& detect_flgs, std::vector<Ptr<Tracker> >& trackers);
std::vector<bool>& detect_flgs, std::vector<Ptr<legacy::Tracker> >& trackers);
#endif
}
}}} // namespace
#endif

@ -40,8 +40,11 @@
//M*/
#include "precomp.hpp"
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
// constructor
MultiTracker::MultiTracker(){};
@ -105,4 +108,4 @@ namespace cv {
return makePtr<MultiTracker>();
}
} /* namespace cv */
}}} // namespace

@ -42,8 +42,9 @@
#include "precomp.hpp"
#include "opencv2/tracking/onlineBoosting.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
StrongClassifierDirectSelection::StrongClassifierDirectSelection( int numBaseClf, int numWeakClf, Size patchSz, const Rect& sampleROI,
bool useFeatureEx, int iterationInit )
@ -732,4 +733,4 @@ int ClassifierThreshold::eval( float value )
return ( ( ( m_parity * ( value - m_threshold ) ) > 0 ) ? 1 : -1 );
}
} /* namespace cv */
}}} // namespace

@ -42,18 +42,29 @@
#ifndef __OPENCV_PRECOMP_H__
#define __OPENCV_PRECOMP_H__
#include "cvconfig.h"
#include "opencv2/tracking.hpp"
#include "opencv2/core/utility.hpp"
#include "opencv2/core.hpp"
#include "opencv2/core/ocl.hpp"
#include <typeinfo>
#include "opencv2/core/hal/hal.hpp"
namespace cv
{
extern const float ColorNames[][10];
#include "opencv2/video/tracking.hpp"
#include "opencv2/tracking.hpp"
namespace tracking {
#include "opencv2/tracking/tracking_internals.hpp"
namespace cv { inline namespace tracking {
namespace impl { }
using namespace impl;
using namespace cv::detail::tracking;
}} // namespace
namespace cv {
namespace detail {
inline namespace tracking {
extern const float ColorNames[][10];
/* Cholesky decomposition
The function performs Cholesky decomposition <https://en.wikipedia.org/wiki/Cholesky_decomposition>.
@ -102,7 +113,6 @@ namespace cv
return success;
}
} // tracking
} // cv
}}} // namespace
#endif

@ -39,10 +39,13 @@
//
//M*/
#include "precomp.hpp"
#include "opencv2/tracking/tldDataset.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
namespace tld
{
char tldRootPath[100];
@ -182,4 +185,5 @@ namespace cv
}
}
}
}}}

@ -39,15 +39,15 @@
//
//M*/
#include "precomp.hpp"
#include "tldDetector.hpp"
#include "tracking_utils.hpp"
#include <opencv2/core/utility.hpp>
namespace cv
{
namespace tld
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
// Calculate offsets for classifiers
void TLDDetector::prepareClassifiers(int rowstep)
{
@ -619,5 +619,4 @@ namespace cv
return ((p2 - p * p) > VARIANCE_THRESHOLD * *originalVariance);
}
}
}
}}}} // namespace

@ -42,15 +42,15 @@
#ifndef OPENCV_TLD_DETECTOR
#define OPENCV_TLD_DETECTOR
#include "precomp.hpp"
#include "opencl_kernels_tracking.hpp"
#include "tldEnsembleClassifier.hpp"
#include "tldUtils.hpp"
namespace cv
{
namespace tld
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
const int STANDARD_PATCH_SIZE = 15;
const int NEG_EXAMPLES_IN_INIT_MODEL = 300;
const int MAX_EXAMPLES_IN_MODEL = 500;
@ -116,7 +116,6 @@ namespace cv
};
}
}
}}}} // namespace
#endif

@ -39,12 +39,14 @@
//
//M*/
#include "precomp.hpp"
#include "tldEnsembleClassifier.hpp"
namespace cv
{
namespace tld
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
// Constructor
TLDEnsembleClassifier::TLDEnsembleClassifier(const std::vector<Vec4b>& meas, int beg, int end) :lastStep_(-1)
{
@ -194,5 +196,4 @@ namespace cv
return (int)classifiers.size();
}
}
}
}}}} // namespace

@ -40,12 +40,12 @@
//M*/
#include <vector>
#include "precomp.hpp"
namespace cv
{
namespace tld
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
class TLDEnsembleClassifier
{
public:
@ -64,5 +64,5 @@ namespace cv
std::vector<Point2i> offset;
int lastStep_;
};
}
}
}}}} // namespace

@ -39,14 +39,14 @@
//
//M*/
#include "precomp.hpp"
#include "tldModel.hpp"
#include <opencv2/core/utility.hpp>
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
namespace cv
{
namespace tld
{
//Constructor
TrackerTLDModel::TrackerTLDModel(TrackerTLD::Params params, const Mat& image, const Rect2d& boundingBox, Size minSize):
timeStampPositiveNext(0), timeStampNegativeNext(0), minSize_(minSize), params_(params), boundingBox_(boundingBox)
@ -361,5 +361,5 @@ namespace cv
dfprintf((port, "\tpositiveExamples.size() = %d\n", (int)positiveExamples.size()));
dfprintf((port, "\tnegativeExamples.size() = %d\n", (int)negativeExamples.size()));
}
}
}
}}}} // namespace

@ -45,10 +45,15 @@
#include "tldDetector.hpp"
#include "tldUtils.hpp"
namespace cv
{
namespace tld
{
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
using namespace cv::legacy;
class TrackerTLDModel : public TrackerModel
{
public:
@ -84,7 +89,6 @@ namespace cv
RNG rng;
};
}
}
}}}} // namespace
#endif

@ -39,10 +39,15 @@
//
//M*/
#include "precomp.hpp"
#include "opencv2/tracking/tracking_legacy.hpp"
#include "tldTracker.hpp"
namespace cv
{
namespace cv {
namespace legacy {
inline namespace tracking {
using namespace impl;
using namespace impl::tld;
TrackerTLD::Params::Params(){}
@ -60,8 +65,11 @@ Ptr<TrackerTLD> TrackerTLD::create()
return Ptr<tld::TrackerTLDImpl>(new tld::TrackerTLDImpl());
}
namespace tld
{
}} // namespace
inline namespace tracking {
namespace impl {
namespace tld {
TrackerTLDImpl::TrackerTLDImpl(const TrackerTLD::Params &parameters) :
params( parameters )
@ -323,6 +331,4 @@ void Data::printme(FILE* port)
dfprintf((port, "\tminSize = %dx%d\n", minSize.width, minSize.height));
}
}
}
}}}} // namespace

@ -42,18 +42,17 @@
#ifndef OPENCV_TLD_TRACKER
#define OPENCV_TLD_TRACKER
#include "precomp.hpp"
#include "opencv2/video/tracking.hpp"
#include "opencv2/imgproc.hpp"
#include "tldModel.hpp"
#include<algorithm>
#include<limits.h>
#include <algorithm>
#include <limits.h>
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
namespace tld
{
class TrackerProxy
{
public:
@ -168,7 +167,6 @@ public:
};
}
}
}}}} // namespace
#endif

@ -39,13 +39,14 @@
//
//M*/
#include "precomp.hpp"
#include "tldUtils.hpp"
namespace cv
{
namespace tld
{
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
//Debug functions and variables
Rect2d etalon(14.0, 110.0, 20.0, 20.0);
@ -192,4 +193,4 @@ void resample(const Mat& img, const Rect2d& r2, Mat_<uchar>& samples)
}
}}
}}}} // namespace

@ -1,12 +1,11 @@
#ifndef OPENCV_TLD_UTILS
#define OPENCV_TLD_UTILS
#include "precomp.hpp"
namespace cv {
inline namespace tracking {
namespace impl {
namespace tld {
namespace cv
{
namespace tld
{
//debug functions and variables
#define ALEX_DEBUG
#ifdef ALEX_DEBUG
@ -48,7 +47,7 @@ namespace cv
double variance(const Mat& img);
void getClosestN(std::vector<Rect2d>& scanGrid, Rect2d bBox, int n, std::vector<Rect2d>& res);
double scaleAndBlur(const Mat& originalImg, int scale, Mat& scaledImg, Mat& blurredImg, Size GaussBlurKernelSize, double scaleStep);
}
}
}}}} // namespace
#endif

@ -1,100 +1,23 @@
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2013, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "precomp.hpp"
namespace cv
{
/*
* Tracker
*/
namespace cv {
inline namespace tracking {
Tracker::~Tracker()
Tracker::Tracker()
{
// nothing
}
bool Tracker::init( InputArray image, const Rect2d& boundingBox )
Tracker::~Tracker()
{
if( isInit )
{
return false;
}
if( image.empty() )
return false;
sampler = Ptr<TrackerSampler>( new TrackerSampler() );
featureSet = Ptr<TrackerFeatureSet>( new TrackerFeatureSet() );
model = Ptr<TrackerModel>();
bool initTracker = initImpl( image.getMat(), boundingBox );
//check if the model component is initialized
if (!model)
{
CV_Error( -1, "The model is not initialized" );
}
if( initTracker )
{
isInit = true;
}
return initTracker;
// nothing
}
bool Tracker::update( InputArray image, Rect2d& boundingBox )
{
}} // namespace
if( !isInit )
{
return false;
}
if( image.empty() )
return false;
return updateImpl( image.getMat(), boundingBox );
}
} /* namespace cv */
#include "legacy/tracker.legacy.hpp"

@ -42,8 +42,12 @@
#include "precomp.hpp"
#include "trackerBoostingModel.hpp"
namespace cv
{
#include "opencv2/tracking/tracking_legacy.hpp"
namespace cv {
namespace legacy {
inline namespace tracking {
using namespace impl;
class TrackerBoostingImpl : public TrackerBoosting
{
@ -319,4 +323,4 @@ bool TrackerBoostingImpl::updateImpl( const Mat& image, Rect2d& boundingBox )
return true;
}
} /* namespace cv */
}}} // namespace

@ -39,14 +39,16 @@
//
//M*/
#include "precomp.hpp"
#include "trackerBoostingModel.hpp"
/**
* TrackerBoostingModel
*/
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
TrackerBoostingModel::TrackerBoostingModel( const Rect& boundingBox )
{
@ -119,4 +121,4 @@ void TrackerBoostingModel::responseToConfidenceMap( const std::vector<Mat>& resp
}
}
}
}}} // namespace

@ -42,11 +42,9 @@
#ifndef __OPENCV_TRACKER_BOOSTING_MODEL_HPP__
#define __OPENCV_TRACKER_BOOSTING_MODEL_HPP__
#include "precomp.hpp"
#include "opencv2/core.hpp"
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
/**
* \brief Implementation of TrackerModel for BOOSTING algorithm
@ -103,6 +101,6 @@ class TrackerBoostingModel : public TrackerModel
int mode;
};
} /* namespace cv */
}}} // namespace
#endif

@ -8,35 +8,38 @@
#include "trackerCSRTUtils.hpp"
#include "trackerCSRTScaleEstimation.hpp"
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
/**
* \brief Implementation of TrackerModel for CSRT algorithm
*/
class TrackerCSRTModel : public TrackerModel
class TrackerCSRTModel CV_FINAL : public TrackerModel
{
public:
TrackerCSRTModel(TrackerCSRT::Params /*params*/){}
TrackerCSRTModel(){}
~TrackerCSRTModel(){}
protected:
void modelEstimationImpl(const std::vector<Mat>& /*responses*/) CV_OVERRIDE {}
void modelUpdateImpl() CV_OVERRIDE {}
};
class TrackerCSRTImpl : public TrackerCSRT
class TrackerCSRTImpl CV_FINAL : public TrackerCSRT
{
public:
TrackerCSRTImpl(const TrackerCSRT::Params &parameters = TrackerCSRT::Params());
void read(const FileNode& fn) CV_OVERRIDE;
void write(FileStorage& fs) const CV_OVERRIDE;
TrackerCSRTImpl(const Params &parameters = Params());
protected:
TrackerCSRT::Params params;
Params params;
bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE;
Ptr<TrackerCSRTModel> model;
// Tracker API
virtual void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
virtual bool update(InputArray image, Rect& boundingBox) CV_OVERRIDE;
virtual void setInitialMask(InputArray mask) CV_OVERRIDE;
bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE;
protected:
void update_csr_filter(const Mat &image, const Mat &my_mask);
void update_histograms(const Mat &image, const Rect &region);
void extract_histograms(const Mat &image, cv::Rect region, Histogram &hf, Histogram &hb);
@ -49,7 +52,6 @@ protected:
Point2f estimate_new_position(const Mat &image);
std::vector<Mat> get_features(const Mat &patch, const Size2i &feature_size);
private:
bool check_mask_area(const Mat &mat, const double obj_area);
float current_scale_factor;
Mat window;
@ -75,28 +77,10 @@ private:
int cell_size;
};
Ptr<TrackerCSRT> TrackerCSRT::create(const TrackerCSRT::Params &parameters)
{
return Ptr<TrackerCSRTImpl>(new TrackerCSRTImpl(parameters));
}
Ptr<TrackerCSRT> TrackerCSRT::create()
{
return Ptr<TrackerCSRTImpl>(new TrackerCSRTImpl());
}
TrackerCSRTImpl::TrackerCSRTImpl(const TrackerCSRT::Params &parameters) :
params(parameters)
{
isInit = false;
}
void TrackerCSRTImpl::read(const cv::FileNode& fn)
{
params.read(fn);
}
void TrackerCSRTImpl::write(cv::FileStorage& fs) const
{
params.write(fs);
// nothing
}
void TrackerCSRTImpl::setInitialMask(InputArray mask)
@ -463,13 +447,13 @@ Point2f TrackerCSRTImpl::estimate_new_position(const Mat &image)
// *********************************************************************
// * Update API function *
// *********************************************************************
bool TrackerCSRTImpl::updateImpl(const Mat& image_, Rect2d& boundingBox)
bool TrackerCSRTImpl::update(InputArray image_, Rect& boundingBox)
{
Mat image;
if(image_.channels() == 1) //treat gray image as color image
cvtColor(image_, image, COLOR_GRAY2BGR);
else
image = image_;
image = image_.getMat();
object_center = estimate_new_position(image);
if (object_center.x < 0 && object_center.y < 0)
@ -506,13 +490,13 @@ bool TrackerCSRTImpl::updateImpl(const Mat& image_, Rect2d& boundingBox)
// *********************************************************************
// * Init API function *
// *********************************************************************
bool TrackerCSRTImpl::initImpl(const Mat& image_, const Rect2d& boundingBox)
void TrackerCSRTImpl::init(InputArray image_, const Rect& boundingBox)
{
Mat image;
if(image_.channels() == 1) //treat gray image as color image
cvtColor(image_, image, COLOR_GRAY2BGR);
else
image = image_;
image = image_.getMat();
current_scale_factor = 1.0;
image_size = image.size();
@ -545,8 +529,7 @@ bool TrackerCSRTImpl::initImpl(const Mat& image_, const Rect2d& boundingBox)
} else if(params.window_function.compare("kaiser") == 0) {
window = get_kaiser_win(Size(yf.cols,yf.rows), params.kaiser_alpha);
} else {
std::cout << "Not a valid window function" << std::endl;
return false;
CV_Error(Error::StsBadArg, "Not a valid window function");
}
Size2i scaled_obj_size = Size2i(cvFloor(original_target_size.width * rescale_ratio / cell_size),
@ -616,11 +599,11 @@ bool TrackerCSRTImpl::initImpl(const Mat& image_, const Rect2d& boundingBox)
dsst = DSST(image, bounding_box, template_size, params.number_of_scales, params.scale_step,
params.scale_model_max_area, params.scale_sigma_factor, params.scale_lr);
model=Ptr<TrackerCSRTModel>(new TrackerCSRTModel(params));
isInit = true;
return true;
model=makePtr<TrackerCSRTModel>();
}
} // namespace impl
TrackerCSRT::Params::Params()
{
use_channel_weights = true;
@ -652,94 +635,21 @@ TrackerCSRT::Params::Params()
psr_threshold = 0.035f;
}
void TrackerCSRT::Params::read(const FileNode& fn)
TrackerCSRT::TrackerCSRT()
{
*this = TrackerCSRT::Params();
if(!fn["padding"].empty())
fn["padding"] >> padding;
if(!fn["template_size"].empty())
fn["template_size"] >> template_size;
if(!fn["gsl_sigma"].empty())
fn["gsl_sigma"] >> gsl_sigma;
if(!fn["hog_orientations"].empty())
fn["hog_orientations"] >> hog_orientations;
if(!fn["num_hog_channels_used"].empty())
fn["num_hog_channels_used"] >> num_hog_channels_used;
if(!fn["hog_clip"].empty())
fn["hog_clip"] >> hog_clip;
if(!fn["use_hog"].empty())
fn["use_hog"] >> use_hog;
if(!fn["use_color_names"].empty())
fn["use_color_names"] >> use_color_names;
if(!fn["use_gray"].empty())
fn["use_gray"] >> use_gray;
if(!fn["use_rgb"].empty())
fn["use_rgb"] >> use_rgb;
if(!fn["window_function"].empty())
fn["window_function"] >> window_function;
if(!fn["kaiser_alpha"].empty())
fn["kaiser_alpha"] >> kaiser_alpha;
if(!fn["cheb_attenuation"].empty())
fn["cheb_attenuation"] >> cheb_attenuation;
if(!fn["filter_lr"].empty())
fn["filter_lr"] >> filter_lr;
if(!fn["admm_iterations"].empty())
fn["admm_iterations"] >> admm_iterations;
if(!fn["number_of_scales"].empty())
fn["number_of_scales"] >> number_of_scales;
if(!fn["scale_sigma_factor"].empty())
fn["scale_sigma_factor"] >> scale_sigma_factor;
if(!fn["scale_model_max_area"].empty())
fn["scale_model_max_area"] >> scale_model_max_area;
if(!fn["scale_lr"].empty())
fn["scale_lr"] >> scale_lr;
if(!fn["scale_step"].empty())
fn["scale_step"] >> scale_step;
if(!fn["use_channel_weights"].empty())
fn["use_channel_weights"] >> use_channel_weights;
if(!fn["weights_lr"].empty())
fn["weights_lr"] >> weights_lr;
if(!fn["use_segmentation"].empty())
fn["use_segmentation"] >> use_segmentation;
if(!fn["histogram_bins"].empty())
fn["histogram_bins"] >> histogram_bins;
if(!fn["background_ratio"].empty())
fn["background_ratio"] >> background_ratio;
if(!fn["histogram_lr"].empty())
fn["histogram_lr"] >> histogram_lr;
if(!fn["psr_threshold"].empty())
fn["psr_threshold"] >> psr_threshold;
CV_Assert(number_of_scales % 2 == 1);
CV_Assert(use_gray || use_color_names || use_hog || use_rgb);
// nothing
}
void TrackerCSRT::Params::write(FileStorage& fs) const
TrackerCSRT::~TrackerCSRT()
{
fs << "padding" << padding;
fs << "template_size" << template_size;
fs << "gsl_sigma" << gsl_sigma;
fs << "hog_orientations" << hog_orientations;
fs << "num_hog_channels_used" << num_hog_channels_used;
fs << "hog_clip" << hog_clip;
fs << "use_hog" << use_hog;
fs << "use_color_names" << use_color_names;
fs << "use_gray" << use_gray;
fs << "use_rgb" << use_rgb;
fs << "window_function" << window_function;
fs << "kaiser_alpha" << kaiser_alpha;
fs << "cheb_attenuation" << cheb_attenuation;
fs << "filter_lr" << filter_lr;
fs << "admm_iterations" << admm_iterations;
fs << "number_of_scales" << number_of_scales;
fs << "scale_sigma_factor" << scale_sigma_factor;
fs << "scale_model_max_area" << scale_model_max_area;
fs << "scale_lr" << scale_lr;
fs << "scale_step" << scale_step;
fs << "use_channel_weights" << use_channel_weights;
fs << "weights_lr" << weights_lr;
fs << "use_segmentation" << use_segmentation;
fs << "histogram_bins" << histogram_bins;
fs << "background_ratio" << background_ratio;
fs << "histogram_lr" << histogram_lr;
fs << "psr_threshold" << psr_threshold;
// nothing
}
} /* namespace cv */
Ptr<TrackerCSRT> TrackerCSRT::create(const TrackerCSRT::Params &parameters)
{
return makePtr<TrackerCSRTImpl>(parameters);
}
}} // namespace
#include "legacy/trackerCSRT.legacy.hpp"

@ -127,7 +127,7 @@ DSST::DSST(const Mat &image,
mulSpectrums(ysf, Fscale_resp, sf_num, 0 , true);
Mat sf_den_all;
mulSpectrums(Fscale_resp, Fscale_resp, sf_den_all, 0, true);
reduce(sf_den_all, sf_den, 0, CV_REDUCE_SUM, -1);
reduce(sf_den_all, sf_den, 0, REDUCE_SUM, -1);
}
DSST::~DSST()
@ -178,7 +178,7 @@ void DSST::update(const Mat &image, const Point2f object_center)
mulSpectrums(ysf, Fscale_features, new_sf_num, DFT_ROWS, true);
Mat sf_den_all;
mulSpectrums(Fscale_features, Fscale_features, new_sf_den_all, DFT_ROWS, true);
reduce(new_sf_den_all, new_sf_den, 0, CV_REDUCE_SUM, -1);
reduce(new_sf_den_all, new_sf_den, 0, REDUCE_SUM, -1);
sf_num = (1 - learn_rate) * sf_num + learn_rate * new_sf_num;
sf_den = (1 - learn_rate) * sf_den + learn_rate * new_sf_den;
@ -194,7 +194,7 @@ float DSST::getScale(const Mat &image, const Point2f object_center)
mulSpectrums(Fscale_features, sf_num, Fscale_features, 0, false);
Mat scale_resp;
reduce(Fscale_features, scale_resp, 0, CV_REDUCE_SUM, -1);
reduce(Fscale_features, scale_resp, 0, REDUCE_SUM, -1);
scale_resp = divide_complex_matrices(scale_resp, sf_den + 0.01f);
idft(scale_resp, scale_resp, DFT_REAL_OUTPUT|DFT_SCALE);
Point max_loc;

@ -41,8 +41,9 @@
#include "precomp.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerFeature
@ -321,4 +322,4 @@ void TrackerFeatureLBP::selection( Mat& /*response*/, int /*npoints*/)
}
} /* namespace cv */
}}} // namespace

@ -41,8 +41,9 @@
#include "precomp.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerFeatureSet
@ -139,4 +140,5 @@ void TrackerFeatureSet::clearResponses()
responses.clear();
}
} /* namespace cv */
}}} // namespace

@ -40,55 +40,50 @@
//M*/
#include "precomp.hpp"
#include "opencl_kernels_tracking.hpp"
#include <complex>
#include <cmath>
namespace cv {
inline namespace tracking {
namespace impl {
/*---------------------------
| TrackerKCFModel
|---------------------------*/
namespace cv{
/**
* \brief Implementation of TrackerModel for KCF algorithm
*/
class TrackerKCFModel : public TrackerModel{
public:
TrackerKCFModel(TrackerKCF::Params /*params*/){}
TrackerKCFModel(){}
~TrackerKCFModel(){}
protected:
void modelEstimationImpl( const std::vector<Mat>& /*responses*/ ) CV_OVERRIDE {}
void modelUpdateImpl() CV_OVERRIDE {}
};
} /* namespace cv */
/*---------------------------
| TrackerKCF
|---------------------------*/
namespace cv{
/*
* Prototype
*/
class TrackerKCFImpl : public TrackerKCF {
public:
TrackerKCFImpl( const TrackerKCF::Params &parameters = TrackerKCF::Params() );
void read( const FileNode& /*fn*/ ) CV_OVERRIDE;
void write( FileStorage& /*fs*/ ) const CV_OVERRIDE;
void setFeatureExtractor(void (*f)(const Mat, const Rect, Mat&), bool pca_func = false) CV_OVERRIDE;
class TrackerKCFImpl CV_FINAL : public TrackerKCF
{
public:
TrackerKCFImpl(const TrackerKCF::Params &parameters);
protected:
/*
* basic functions and vars
*/
bool initImpl( const Mat& /*image*/, const Rect2d& boundingBox ) CV_OVERRIDE;
bool updateImpl( const Mat& image, Rect2d& boundingBox ) CV_OVERRIDE;
virtual void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
virtual bool update(InputArray image, Rect& boundingBox) CV_OVERRIDE;
void setFeatureExtractor(void (*f)(const Mat, const Rect, Mat&), bool pca_func = false) CV_OVERRIDE;
TrackerKCF::Params params;
Ptr<TrackerKCFModel> model;
/*
* KCF functions and vars
*/
protected:
void createHanningWindow(OutputArray dest, const cv::Size winSize, const int type) const;
void inline fft2(const Mat src, std::vector<Mat> & dest, std::vector<Mat> & layers_data) const;
void inline fft2(const Mat src, Mat & dest) const;
@ -113,7 +108,7 @@ namespace cv{
bool inline oclTransposeMM(const Mat src, float alpha, UMat &dst);
#endif
private:
private:
float output_sigma;
Rect2d roi;
Mat hann; //hann window filter
@ -164,21 +159,14 @@ namespace cv{
#endif
int frame;
};
};
/*
* Constructor
*/
Ptr<TrackerKCF> TrackerKCF::create(const TrackerKCF::Params &parameters){
return Ptr<TrackerKCFImpl>(new TrackerKCFImpl(parameters));
}
Ptr<TrackerKCF> TrackerKCF::create(){
return Ptr<TrackerKCFImpl>(new TrackerKCFImpl());
}
TrackerKCFImpl::TrackerKCFImpl( const TrackerKCF::Params &parameters ) :
params( parameters )
{
isInit = false;
resizeImage = false;
use_custom_extractor_pca = false;
use_custom_extractor_npca = false;
@ -195,14 +183,6 @@ namespace cv{
#endif
}
void TrackerKCFImpl::read( const cv::FileNode& fn ){
params.read( fn );
}
void TrackerKCFImpl::write( cv::FileStorage& fs ) const {
params.write( fs );
}
/*
* Initialization:
* - creating hann window filter
@ -210,7 +190,8 @@ namespace cv{
* - creating a gaussian response for the training ground-truth
* - perform FFT to the gaussian response
*/
bool TrackerKCFImpl::initImpl( const Mat& image, const Rect2d& boundingBox ){
void TrackerKCFImpl::init(InputArray image, const Rect& boundingBox)
{
frame=0;
roi.x = cvRound(boundingBox.x);
roi.y = cvRound(boundingBox.y);
@ -262,7 +243,7 @@ namespace cv{
params.desc_pca &= ~(CN);
params.desc_npca &= ~(CN);
}
model=Ptr<TrackerKCFModel>(new TrackerKCFModel(params));
model = makePtr<TrackerKCFModel>();
// record the non-compressed descriptors
if((params.desc_npca & GRAY) == GRAY)descriptors_npca.push_back(GRAY);
@ -286,27 +267,29 @@ namespace cv{
|| use_custom_extractor_npca
);
//return true only if roi has intersection with the image
if((roi & Rect2d(0,0, resizeImage ? image.cols / 2 : image.cols,
resizeImage ? image.rows / 2 : image.rows)) == Rect2d())
return false;
return true;
// ensure roi has intersection with the image
Rect2d image_roi(0, 0,
image.cols() / (resizeImage ? 2 : 1),
image.rows() / (resizeImage ? 2 : 1));
CV_Assert(!(roi & image_roi).empty());
}
/*
* Main part of the KCF algorithm
*/
bool TrackerKCFImpl::updateImpl( const Mat& image, Rect2d& boundingBox ){
bool TrackerKCFImpl::update(InputArray image, Rect& boundingBoxResult)
{
double minVal, maxVal; // min-max response
Point minLoc,maxLoc; // min-max location
Mat img=image.clone();
// check the channels of the input image, grayscale is preferred
CV_Assert(img.channels() == 1 || img.channels() == 3);
CV_Assert(image.channels() == 1 || image.channels() == 3);
Mat img;
// resize the image whenever needed
if(resizeImage)resize(img,img,Size(img.cols/2,img.rows/2),0,0,INTER_LINEAR_EXACT);
if (resizeImage)
resize(image, img, Size(image.cols()/2, image.rows()/2), 0, 0, INTER_LINEAR_EXACT);
else
image.copyTo(img);
// detection part
if(frame>0){
@ -377,6 +360,7 @@ namespace cv{
}
// update the bounding box
Rect2d boundingBox;
boundingBox.x=(resizeImage?roi.x*2:roi.x)+(resizeImage?roi.width*2:roi.width)/4;
boundingBox.y=(resizeImage?roi.y*2:roi.y)+(resizeImage?roi.height*2:roi.height)/4;
boundingBox.width = (resizeImage?roi.width*2:roi.width)/2;
@ -475,6 +459,13 @@ namespace cv{
}
frame++;
int x1 = cvRound(boundingBox.x);
int y1 = cvRound(boundingBox.y);
int x2 = cvRound(boundingBox.x + boundingBox.width);
int y2 = cvRound(boundingBox.y + boundingBox.height);
boundingBoxResult = Rect(x1, y1, x2 - x1, y2 - y1) & Rect(Point(0, 0), image.size());
return true;
}
@ -664,7 +655,7 @@ namespace cv{
Rect region=_roi;
// return false if roi is outside the image
if((roi & Rect2d(0,0, img.cols, img.rows)) == Rect2d() )
if ((roi & Rect2d(0, 0, img.cols, img.rows)).empty())
return false;
// extract patch inside the image
@ -903,10 +894,11 @@ namespace cv{
}
/*----------------------------------------------------------------------*/
/*
* Parameters
*/
TrackerKCF::Params::Params(){
} // namespace
TrackerKCF::Params::Params()
{
detect_thresh = 0.5f;
sigma=0.2f;
lambda=0.0001f;
@ -923,69 +915,24 @@ namespace cv{
compress_feature=true;
compressed_size=2;
pca_learning_rate=0.15f;
}
void TrackerKCF::Params::read( const cv::FileNode& fn ){
*this = TrackerKCF::Params();
if (!fn["detect_thresh"].empty())
fn["detect_thresh"] >> detect_thresh;
if (!fn["sigma"].empty())
fn["sigma"] >> sigma;
}
if (!fn["lambda"].empty())
fn["lambda"] >> lambda;
if (!fn["interp_factor"].empty())
fn["interp_factor"] >> interp_factor;
TrackerKCF::TrackerKCF()
{
// nothing
}
if (!fn["output_sigma_factor"].empty())
fn["output_sigma_factor"] >> output_sigma_factor;
TrackerKCF::~TrackerKCF()
{
// nothing
}
if (!fn["resize"].empty())
fn["resize"] >> resize;
Ptr<TrackerKCF> TrackerKCF::create(const TrackerKCF::Params &parameters)
{
return makePtr<TrackerKCFImpl>(parameters);
}
if (!fn["max_patch_size"].empty())
fn["max_patch_size"] >> max_patch_size;
}} // namespace
if (!fn["split_coeff"].empty())
fn["split_coeff"] >> split_coeff;
if (!fn["wrap_kernel"].empty())
fn["wrap_kernel"] >> wrap_kernel;
if (!fn["desc_npca"].empty())
fn["desc_npca"] >> desc_npca;
if (!fn["desc_pca"].empty())
fn["desc_pca"] >> desc_pca;
if (!fn["compress_feature"].empty())
fn["compress_feature"] >> compress_feature;
if (!fn["compressed_size"].empty())
fn["compressed_size"] >> compressed_size;
if (!fn["pca_learning_rate"].empty())
fn["pca_learning_rate"] >> pca_learning_rate;
}
void TrackerKCF::Params::write( cv::FileStorage& fs ) const{
fs << "detect_thresh" << detect_thresh;
fs << "sigma" << sigma;
fs << "lambda" << lambda;
fs << "interp_factor" << interp_factor;
fs << "output_sigma_factor" << output_sigma_factor;
fs << "resize" << resize;
fs << "max_patch_size" << max_patch_size;
fs << "split_coeff" << split_coeff;
fs << "wrap_kernel" << wrap_kernel;
fs << "desc_npca" << desc_npca;
fs << "desc_pca" << desc_pca;
fs << "compress_feature" << compress_feature;
fs << "compressed_size" << compressed_size;
fs << "pca_learning_rate" << pca_learning_rate;
}
} /* namespace cv */
#include "legacy/trackerKCF.legacy.hpp"

@ -42,32 +42,30 @@
#include "precomp.hpp"
#include "trackerMILModel.hpp"
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
class TrackerMILImpl : public TrackerMIL
class TrackerMILImpl CV_FINAL : public TrackerMIL
{
public:
TrackerMILImpl( const TrackerMIL::Params &parameters = TrackerMIL::Params() );
void read( const FileNode& fn ) CV_OVERRIDE;
void write( FileStorage& fs ) const CV_OVERRIDE;
public:
TrackerMILImpl(const TrackerMIL::Params &parameters);
virtual void init(InputArray image, const Rect& boundingBox) CV_OVERRIDE;
virtual bool update(InputArray image, Rect& boundingBox) CV_OVERRIDE;
protected:
void compute_integral( const Mat & img, Mat & ii_img );
bool initImpl( const Mat& image, const Rect2d& boundingBox ) CV_OVERRIDE;
bool updateImpl( const Mat& image, Rect2d& boundingBox ) CV_OVERRIDE;
void compute_integral( const Mat & img, Mat & ii_img );
TrackerMIL::Params params;
TrackerMIL::Params params;
Ptr<TrackerMILModel> model;
Ptr<TrackerSampler> sampler;
Ptr<TrackerFeatureSet> featureSet;
};
/*
* TrackerMIL
*/
} // namespace
/*
* Parameters
*/
TrackerMIL::Params::Params()
{
samplerInitInRadius = 3;
@ -79,68 +77,30 @@ TrackerMIL::Params::Params()
featureSetNumFeatures = 250;
}
void TrackerMIL::Params::read( const cv::FileNode& fn )
{
samplerInitInRadius = fn["samplerInitInRadius"];
samplerSearchWinSize = fn["samplerSearchWinSize"];
samplerInitMaxNegNum = fn["samplerInitMaxNegNum"];
samplerTrackInRadius = fn["samplerTrackInRadius"];
samplerTrackMaxPosNum = fn["samplerTrackMaxPosNum"];
samplerTrackMaxNegNum = fn["samplerTrackMaxNegNum"];
featureSetNumFeatures = fn["featureSetNumFeatures"];
}
void TrackerMIL::Params::write( cv::FileStorage& fs ) const
{
fs << "samplerInitInRadius" << samplerInitInRadius;
fs << "samplerSearchWinSize" << samplerSearchWinSize;
fs << "samplerInitMaxNegNum" << samplerInitMaxNegNum;
fs << "samplerTrackInRadius" << samplerTrackInRadius;
fs << "samplerTrackMaxPosNum" << samplerTrackMaxPosNum;
fs << "samplerTrackMaxNegNum" << samplerTrackMaxNegNum;
fs << "featureSetNumFeatures" << featureSetNumFeatures;
}
/*
* Constructor
*/
Ptr<TrackerMIL> TrackerMIL::create(const TrackerMIL::Params &parameters){
return Ptr<TrackerMILImpl>(new TrackerMILImpl(parameters));
}
Ptr<TrackerMIL> TrackerMIL::create(){
return Ptr<TrackerMILImpl>(new TrackerMILImpl());
}
TrackerMILImpl::TrackerMILImpl( const TrackerMIL::Params &parameters ) :
params( parameters )
{
isInit = false;
}
namespace impl {
void TrackerMILImpl::read( const cv::FileNode& fn )
TrackerMILImpl::TrackerMILImpl(const TrackerMIL::Params &parameters)
: params(parameters)
{
params.read( fn );
}
void TrackerMILImpl::write( cv::FileStorage& fs ) const
{
params.write( fs );
// nothing
}
void TrackerMILImpl::compute_integral( const Mat & img, Mat & ii_img )
{
Mat ii;
std::vector<Mat> ii_imgs;
integral( img, ii, CV_32F );
integral( img, ii, CV_32F ); // FIXIT split first
split( ii, ii_imgs );
ii_img = ii_imgs[0];
}
bool TrackerMILImpl::initImpl( const Mat& image, const Rect2d& boundingBox )
void TrackerMILImpl::init(InputArray image, const Rect& boundingBox)
{
srand (1);
sampler = makePtr<TrackerSampler>();
featureSet = makePtr<TrackerFeatureSet>();
Mat intImage;
compute_integral( image, intImage );
compute_integral(image.getMat(), intImage);
TrackerSamplerCSC::Params CSCparameters;
CSCparameters.initInRad = params.samplerInitInRadius;
CSCparameters.searchWinSize = params.samplerSearchWinSize;
@ -149,9 +109,8 @@ bool TrackerMILImpl::initImpl( const Mat& image, const Rect2d& boundingBox )
CSCparameters.trackMaxPosNum = params.samplerTrackMaxPosNum;
CSCparameters.trackMaxNegNum = params.samplerTrackMaxNegNum;
Ptr<TrackerSamplerAlgorithm> CSCSampler = Ptr<TrackerSamplerCSC>( new TrackerSamplerCSC( CSCparameters ) );
if( !sampler->addTrackerSamplerAlgorithm( CSCSampler ) )
return false;
Ptr<TrackerSamplerAlgorithm> CSCSampler = makePtr<TrackerSamplerCSC>(CSCparameters);
CV_Assert(sampler->addTrackerSamplerAlgorithm(CSCSampler));
//or add CSC sampler with default parameters
//sampler->addTrackerSamplerAlgorithm( "CSC" );
@ -166,8 +125,8 @@ bool TrackerMILImpl::initImpl( const Mat& image, const Rect2d& boundingBox )
sampler->sampling( intImage, boundingBox );
std::vector<Mat> negSamples = sampler->getSamples();
if( posSamples.empty() || negSamples.empty() )
return false;
CV_Assert(!posSamples.empty());
CV_Assert(!negSamples.empty());
//compute HAAR features
TrackerFeatureHAAR::Params HAARparameters;
@ -183,7 +142,7 @@ bool TrackerMILImpl::initImpl( const Mat& image, const Rect2d& boundingBox )
featureSet->extraction( negSamples );
const std::vector<Mat> negResponse = featureSet->getResponses();
model = Ptr<TrackerMILModel>( new TrackerMILModel( boundingBox ) );
model = makePtr<TrackerMILModel>(boundingBox);
Ptr<TrackerStateEstimatorMILBoosting> stateEstimator = Ptr<TrackerStateEstimatorMILBoosting>(
new TrackerStateEstimatorMILBoosting( params.featureSetNumFeatures ) );
model->setTrackerStateEstimator( stateEstimator );
@ -194,14 +153,12 @@ bool TrackerMILImpl::initImpl( const Mat& image, const Rect2d& boundingBox )
model.staticCast<TrackerMILModel>()->setMode( TrackerMILModel::MODE_NEGATIVE, negSamples );
model->modelEstimation( negResponse );
model->modelUpdate();
return true;
}
bool TrackerMILImpl::updateImpl( const Mat& image, Rect2d& boundingBox )
bool TrackerMILImpl::update(InputArray image, Rect& boundingBox)
{
Mat intImage;
compute_integral( image, intImage );
compute_integral(image.getMat(), intImage);
//get the last location [AAM] X(k-1)
Ptr<TrackerTargetState> lastLocation = model->getLastTargetState();
@ -285,4 +242,24 @@ bool TrackerMILImpl::updateImpl( const Mat& image, Rect2d& boundingBox )
return true;
}
} /* namespace cv */
} // namespace
TrackerMIL::TrackerMIL()
{
// nothing
}
TrackerMIL::~TrackerMIL()
{
// nothing
}
Ptr<TrackerMIL> TrackerMIL::create(const TrackerMIL::Params &parameters)
{
return makePtr<TrackerMILImpl>(parameters);
}
}} // namespace
#include "legacy/trackerMIL.legacy.hpp"

@ -46,8 +46,9 @@
* TrackerMILModel
*/
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
TrackerMILModel::TrackerMILModel( const Rect& boundingBox )
{
@ -122,4 +123,4 @@ void TrackerMILModel::setMode( int trainingMode, const std::vector<Mat>& samples
mode = trainingMode;
}
}
}}} // namespace

@ -42,10 +42,9 @@
#ifndef __OPENCV_TRACKER_MIL_MODEL_HPP__
#define __OPENCV_TRACKER_MIL_MODEL_HPP__
#include "opencv2/core.hpp"
namespace cv
{
namespace cv {
inline namespace tracking {
namespace impl {
/**
* \brief Implementation of TrackerModel for MIL algorithm
@ -98,6 +97,6 @@ class TrackerMILModel : public TrackerModel
int height; //initial height of the boundingBox
};
} /* namespace cv */
}}} // namespace
#endif

@ -40,15 +40,15 @@
//M*/
#include "precomp.hpp"
#include "opencv2/video/tracking.hpp"
#include "opencv2/imgproc.hpp"
#include "opencv2/tracking/tracking_legacy.hpp"
#include "tracking_utils.hpp"
#include <algorithm>
#include <limits.h>
namespace
{
using namespace cv;
namespace cv {
inline namespace tracking {
namespace impl {
#undef MEDIAN_FLOW_TRACKER_DEBUG_LOGS
#ifdef MEDIAN_FLOW_TRACKER_DEBUG_LOGS
@ -72,7 +72,8 @@ using namespace cv;
* optimize (allocation<-->reallocation)
*/
class TrackerMedianFlowImpl : public TrackerMedianFlow{
class TrackerMedianFlowImpl : public legacy::TrackerMedianFlow
{
public:
TrackerMedianFlowImpl(TrackerMedianFlow::Params paramsIn = TrackerMedianFlow::Params()) {params=paramsIn;isInit=false;}
void read( const FileNode& fn ) CV_OVERRIDE;
@ -95,6 +96,7 @@ private:
TrackerMedianFlow::Params params;
};
static
Mat getPatch(Mat image, Size patch_size, Point2f patch_center)
{
Mat patch;
@ -119,7 +121,7 @@ Mat getPatch(Mat image, Size patch_size, Point2f patch_center)
class TrackerMedianFlowModel : public TrackerModel{
public:
TrackerMedianFlowModel(TrackerMedianFlow::Params /*params*/){}
TrackerMedianFlowModel(legacy::TrackerMedianFlow::Params /*params*/){}
Rect2d getBoundingBox(){return boundingBox_;}
void setBoudingBox(Rect2d boundingBox){boundingBox_=boundingBox;}
Mat getImage(){return image_;}
@ -391,10 +393,11 @@ void TrackerMedianFlowImpl::check_NCC(const Mat& oldImage,const Mat& newImage,
}
}
} /* anonymous namespace */
}} // namespace
namespace legacy {
inline namespace tracking {
namespace cv
{
/*
* Parameters
*/
@ -442,11 +445,13 @@ void TrackerMedianFlow::Params::write( cv::FileStorage& fs ) const{
fs << "maxMedianLengthOfDisplacementDifference" << maxMedianLengthOfDisplacementDifference;
}
Ptr<TrackerMedianFlow> TrackerMedianFlow::create(const TrackerMedianFlow::Params &parameters){
return Ptr<TrackerMedianFlowImpl>(new TrackerMedianFlowImpl(parameters));
Ptr<TrackerMedianFlow> TrackerMedianFlow::create(const TrackerMedianFlow::Params &parameters)
{
return makePtr<impl::TrackerMedianFlowImpl>(parameters);
}
Ptr<TrackerMedianFlow> TrackerMedianFlow::create(){
return Ptr<TrackerMedianFlowImpl>(new TrackerMedianFlowImpl());
Ptr<TrackerMedianFlow> TrackerMedianFlow::create()
{
return create(TrackerMedianFlow::Params());
}
} /* namespace cv */
}}} // namespace

@ -41,8 +41,9 @@
#include "precomp.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerModel
@ -174,4 +175,4 @@ void TrackerTargetState::setTargetHeight( int height )
targetHeight = height;
}
} /* namespace cv */
}}} // namespace

@ -41,8 +41,9 @@
#include "precomp.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerSampler
@ -139,4 +140,5 @@ void TrackerSampler::clearSamples()
samples.clear();
}
} /* namespace cv */
}}} // namespace

@ -40,18 +40,12 @@
//M*/
#include "precomp.hpp"
#include <time.h>
#include "PFSolver.hpp"
#include "TrackingFunctionPF.hpp"
#ifdef _WIN32
#define TIME( arg ) (((double) clock()) / CLOCKS_PER_SEC)
#else
#define TIME( arg ) (time( arg ))
#endif
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerSamplerAlgorithm
@ -114,7 +108,7 @@ TrackerSamplerCSC::TrackerSamplerCSC( const TrackerSamplerCSC::Params &parameter
{
className = "CSC";
mode = MODE_INIT_POS;
rng = RNG( uint64( TIME( 0 ) ) );
rng = theRNG();
}
@ -410,4 +404,5 @@ bool TrackerSamplerPF::samplingImpl( const Mat& image, Rect boundingBox, std::ve
return true;
}
} /* namespace cv */
}}} // namespace

@ -41,8 +41,9 @@
#include "precomp.hpp"
namespace cv
{
namespace cv {
namespace detail {
inline namespace tracking {
/*
* TrackerStateEstimator
@ -441,4 +442,4 @@ void TrackerStateEstimatorSVM::updateImpl( std::vector<ConfidenceMap>& /*confide
}
} /* namespace cv */
}}} // namespace

@ -2,6 +2,8 @@
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "precomp.hpp"
#include <map>
#include <set>
#include <string>
@ -25,7 +27,11 @@
#define TBM_CHECK_LE(actual, expected) CV_CheckLE(actual, expected, "Assertion error:")
#define TBM_CHECK_GE(actual, expected) CV_CheckGE(actual, expected, "Assertion error:")
using namespace cv::tbm;
namespace cv {
namespace detail {
inline namespace tracking {
using namespace tbm;
CosDistance::CosDistance(const cv::Size &descriptor_size)
: descriptor_size_(descriptor_size) {
@ -1335,3 +1341,5 @@ void TrackerByMatching::PrintConfusionMatrices() const {
std::cout << cm << std::endl << std::endl;
}
}
}}} // namespace

@ -2,9 +2,10 @@
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
#include "precomp.hpp"
#include "tracking_utils.hpp"
using namespace cv;
namespace cv {
double tracking_internal::computeNCC(const Mat& patch1, const Mat& patch2)
{
@ -67,3 +68,5 @@ double tracking_internal::computeNCC(const Mat& patch1, const Mat& patch2)
return (sq2 == 0) ? sq1 / abs(sq1) : (prod - s1 * s2 / N) / sq1 / sq2;
}
}
} // namespace

@ -3,12 +3,11 @@
// of this distribution and at http://opencv.org/license.html.
#ifndef __OPENCV_TRACKING_UTILS_HPP__
#include "precomp.hpp"
#include <algorithm>
namespace cv {
namespace tracking_internal
{
namespace tracking_internal {
/** Computes normalized corellation coefficient between the two patches (they should be
* of the same size).*/
double computeNCC(const Mat& patch1, const Mat& patch2);
@ -42,6 +41,6 @@ namespace tracking_internal
std::vector<T> copy(values);
return getMedianAndDoPartition(copy);
}
}
}
}} // namespace
#endif

@ -42,10 +42,10 @@
#include "precomp.hpp"
#include "opencv2/tracking/kalman_filters.hpp"
namespace cv
{
namespace tracking
{
namespace cv {
namespace detail {
inline namespace tracking {
inline namespace kalman_filters {
void UnscentedKalmanFilterParams::
init( int dp, int mp, int cp, double processNoiseCovDiag, double measurementNoiseCovDiag,
@ -369,5 +369,4 @@ Ptr<UnscentedKalmanFilter> createUnscentedKalmanFilter(const UnscentedKalmanFilt
return kfu;
}
} // tracking
} // cv
}}}} // namespace

@ -43,7 +43,7 @@
#include "opencv2/tracking/kalman_filters.hpp"
namespace opencv_test { namespace {
using namespace cv::tracking;
using namespace cv::detail;
// In this two tests Augmented Unscented Kalman Filter are applied to the dynamic system from example "The reentry problem" from
// "A New Extension of the Kalman Filter to Nonlinear Systems" by Simon J. Julier and Jeffrey K. Uhlmann.

@ -4,11 +4,15 @@
#include "test_precomp.hpp"
#include <opencv2/tracking/tracking_legacy.hpp>
//using namespace cv::tracking::legacy;
namespace opencv_test { namespace {
TEST(MEDIAN_FLOW_Parameters, IO)
{
TrackerMedianFlow::Params parameters;
legacy::TrackerMedianFlow::Params parameters;
parameters.maxLevel = 10;
parameters.maxMedianLengthOfDisplacementDifference = 11;
@ -25,7 +29,7 @@ TEST(MEDIAN_FLOW_Parameters, IO)
FileStorage fsReader(serializedParameters, FileStorage::READ + FileStorage::MEMORY);
TrackerMedianFlow::Params readParameters;
legacy::TrackerMedianFlow::Params readParameters;
readParameters.read(fsReader.root());
ASSERT_EQ(parameters.maxLevel, readParameters.maxLevel);
@ -41,11 +45,11 @@ TEST(MEDIAN_FLOW_Parameters, IO)
TEST(MEDIAN_FLOW_Parameters, Default_Value_If_Absent)
{
TrackerMedianFlow::Params defaultParameters;
legacy::TrackerMedianFlow::Params defaultParameters;
FileStorage fsReader(String("%YAML 1.0"), FileStorage::READ + FileStorage::MEMORY);
TrackerMedianFlow::Params readParameters;
legacy::TrackerMedianFlow::Params readParameters;
readParameters.read(fsReader.root());
ASSERT_EQ(defaultParameters.maxLevel, readParameters.maxLevel);
@ -60,7 +64,7 @@ TEST(MEDIAN_FLOW_Parameters, Default_Value_If_Absent)
TEST(KCF_Parameters, IO)
{
TrackerKCF::Params parameters;
legacy::TrackerKCF::Params parameters;
parameters.sigma = 0.3f;
parameters.lambda = 0.02f;
@ -83,7 +87,7 @@ TEST(KCF_Parameters, IO)
FileStorage fsReader(serializedParameters, FileStorage::READ + FileStorage::MEMORY);
TrackerKCF::Params readParameters;
legacy::TrackerKCF::Params readParameters;
readParameters.read(fsReader.root());
ASSERT_DOUBLE_EQ(parameters.sigma, readParameters.sigma);
@ -103,11 +107,11 @@ TEST(KCF_Parameters, IO)
TEST(KCF_Parameters, Default_Value_If_Absent)
{
TrackerKCF::Params defaultParameters;
legacy::TrackerKCF::Params defaultParameters;
FileStorage fsReader(String("%YAML 1.0"), FileStorage::READ + FileStorage::MEMORY);
TrackerKCF::Params readParameters;
legacy::TrackerKCF::Params readParameters;
readParameters.read(fsReader.root());
ASSERT_DOUBLE_EQ(defaultParameters.sigma, readParameters.sigma);

@ -41,7 +41,16 @@
#include "test_precomp.hpp"
#define TEST_LEGACY
#include <opencv2/tracking/tracking_legacy.hpp>
//#define DEBUG_TEST
#ifdef DEBUG_TEST
#include <opencv2/highgui.hpp>
#endif
namespace opencv_test { namespace {
//using namespace cv::tracking;
#define TESTSET_NAMES testing::Values("david","dudek","faceocc2")
@ -73,19 +82,52 @@ enum BBTransformations
Scale_1_2 = 12
};
namespace {
std::vector<std::string> splitString(const std::string& s_, const std::string& delimiter)
{
std::string s = s_;
std::vector<string> token;
size_t pos = 0;
while ( ( pos = s.find( delimiter ) ) != std::string::npos )
{
token.push_back( s.substr( 0, pos ) );
s.erase( 0, pos + delimiter.length() );
}
token.push_back( s );
return token;
}
float calcDistance(const Rect& a, const Rect& b)
{
Point2f p_a( (float)(a.x + a.width / 2), (float)(a.y + a.height / 2) );
Point2f p_b( (float)(b.x + b.width / 2), (float)(b.y + b.height / 2) );
return sqrt( pow( p_a.x - p_b.x, 2 ) + pow( p_a.y - p_b.y, 2 ) );
}
float calcOverlap(const Rect& a, const Rect& b)
{
float rectIntersectionArea = (float)(a & b).area();
return rectIntersectionArea / (a.area() + b.area() - rectIntersectionArea);
}
} // namespace
template<typename Tracker, typename ROI_t = Rect2d>
class TrackerTest
{
public:
public:
TrackerTest(Ptr<Tracker> _tracker, string _video, float _distanceThreshold,
float _overlapThreshold, int _shift = NoTransform, int _segmentIdx = 1, int _numSegments = 10 );
virtual ~TrackerTest();
virtual void run();
TrackerTest(const Ptr<Tracker>& tracker, const string& video, float distanceThreshold,
float overlapThreshold, int shift = NoTransform, int segmentIdx = 1, int numSegments = 10);
~TrackerTest() {}
void run();
protected:
protected:
void checkDataTest();
void distanceAndOvrerlapTest();
void distanceAndOverlapTest();
Ptr<Tracker> tracker;
string video;
@ -103,16 +145,13 @@ class TrackerTest
int endFrame;
vector<int> validSequence;
private:
float calcDistance( Rect a, Rect b );
float calcOverlap( Rect a, Rect b );
Rect applyShift(Rect bb);
std::vector<std::string> splitString( std::string s, std::string delimiter );
private:
Rect applyShift(const Rect& bb);
};
TrackerTest::TrackerTest(Ptr<Tracker> _tracker, string _video, float _distanceThreshold,
float _overlapThreshold, int _shift, int _segmentIdx, int _numSegments ) :
template<typename Tracker, typename ROI_t>
TrackerTest<Tracker, ROI_t>::TrackerTest(const Ptr<Tracker>& _tracker, const string& _video, float _distanceThreshold,
float _overlapThreshold, int _shift, int _segmentIdx, int _numSegments ) :
tracker( _tracker ),
video( _video ),
overlapThreshold( _overlapThreshold ),
@ -121,41 +160,13 @@ TrackerTest::TrackerTest(Ptr<Tracker> _tracker, string _video, float _distanceTh
shift(_shift),
numSegments(_numSegments)
{
// nothing
}
TrackerTest::~TrackerTest()
{
}
std::vector<std::string> TrackerTest::splitString( std::string s, std::string delimiter )
{
std::vector<string> token;
size_t pos = 0;
while ( ( pos = s.find( delimiter ) ) != std::string::npos )
{
token.push_back( s.substr( 0, pos ) );
s.erase( 0, pos + delimiter.length() );
}
token.push_back( s );
return token;
}
float TrackerTest::calcDistance( Rect a, Rect b )
{
Point2f p_a( (float)(a.x + a.width / 2), (float)(a.y + a.height / 2) );
Point2f p_b( (float)(b.x + b.width / 2), (float)(b.y + b.height / 2) );
return sqrt( pow( p_a.x - p_b.x, 2 ) + pow( p_a.y - p_b.y, 2 ) );
}
float TrackerTest::calcOverlap( Rect a, Rect b )
{
float rectIntersectionArea = (float)(a & b).area();
return rectIntersectionArea / (a.area() + b.area() - rectIntersectionArea);
}
Rect TrackerTest::applyShift(Rect bb)
template<typename Tracker, typename ROI_t>
Rect TrackerTest<Tracker, ROI_t>::applyShift(const Rect& bb_)
{
Rect bb = bb_;
Point center( bb.x + ( bb.width / 2 ), bb.y + ( bb.height / 2 ) );
int xLimit = bb.x + bb.width - 1;
@ -244,51 +255,77 @@ Rect TrackerTest::applyShift(Rect bb)
return bb;
}
void TrackerTest::distanceAndOvrerlapTest()
template<typename Tracker, typename ROI_t>
void TrackerTest<Tracker, ROI_t>::distanceAndOverlapTest()
{
Mat frame;
bool initialized = false;
int fc = ( startFrame - gtStartFrame );
bbs.at( fc ) = applyShift(bbs.at( fc ));
Rect currentBBi = bbs.at( fc );
Rect2d currentBB(currentBBi);
ROI_t currentBB(currentBBi);
float sumDistance = 0;
float sumOverlap = 0;
string folder = cvtest::TS::ptr()->get_data_path() + "/" + TRACKING_DIR + "/" + video + "/" + FOLDER_IMG;
string videoPath = folder + "/" + video + ".webm";
VideoCapture c;
c.open( folder + "/" + video + ".webm" );
c.set( CAP_PROP_POS_FRAMES, startFrame );
c.open(videoPath);
ASSERT_TRUE(c.isOpened()) << videoPath;
#if 0
c.set(CAP_PROP_POS_FRAMES, startFrame);
#else
if (startFrame)
std::cout << "startFrame = " << startFrame << std::endl;
for (int i = 0; i < startFrame; i++)
{
Mat dummy_frame;
c >> dummy_frame;
ASSERT_FALSE(dummy_frame.empty()) << i << ": " << videoPath;
}
#endif
for ( int frameCounter = startFrame; frameCounter < endFrame; frameCounter++ )
{
Mat frame;
c >> frame;
if( frame.empty() )
{
break;
}
ASSERT_FALSE(frame.empty()) << "frameCounter=" << frameCounter << " video=" << videoPath;
if( !initialized )
{
#if 0
if( !tracker->init( frame, currentBB ) )
{
FAIL()<< "Could not initialize tracker" << endl;
return;
}
#else
tracker->init(frame, currentBB);
#endif
std::cout << "frame size = " << frame.size() << std::endl;
initialized = true;
}
else if( initialized )
{
if( frameCounter >= (int) bbs.size() )
break;
break;
tracker->update( frame, currentBB );
}
float curDistance = calcDistance( currentBB, bbs.at( fc ) );
float curOverlap = calcOverlap( currentBB, bbs.at( fc ) );
#ifdef DEBUG_TEST
Mat result;
repeat(frame, 1, 2, result);
rectangle(result, currentBB, Scalar(0, 255, 0), 1);
Rect roi2(frame.cols, 0, frame.cols, frame.rows);
rectangle(result(roi2), bbs.at(fc), Scalar(0, 0, 255), 1);
imshow("result", result);
waitKey(1);
#endif
sumDistance += curDistance;
sumOverlap += curOverlap;
fc++;
@ -297,20 +334,12 @@ void TrackerTest::distanceAndOvrerlapTest()
float meanDistance = sumDistance / (endFrame - startFrame);
float meanOverlap = sumOverlap / (endFrame - startFrame);
if( meanDistance > distanceThreshold )
{
FAIL()<< "Incorrect distance: curr = " << meanDistance << ", max = " << distanceThreshold << endl;
return;
}
if( meanOverlap < overlapThreshold )
{
FAIL()<< "Incorrect overlap: curr = " << meanOverlap << ", min = " << overlapThreshold << endl;
return;
}
EXPECT_LE(meanDistance, distanceThreshold);
EXPECT_GE(meanOverlap, overlapThreshold);
}
void TrackerTest::checkDataTest()
template<typename Tracker, typename ROI_t>
void TrackerTest<Tracker, ROI_t>::checkDataTest()
{
FileStorage fs;
@ -324,10 +353,7 @@ void TrackerTest::checkDataTest()
std::ifstream gt;
//open the ground truth
gt.open( gtFile.c_str() );
if( !gt.is_open() )
{
FAIL()<< "Ground truth file " << gtFile << " can not be read" << endl;
}
ASSERT_TRUE(gt.is_open()) << gtFile;
string line;
int bbCounter = 0;
while ( getline( gt, line ) )
@ -372,20 +398,14 @@ void TrackerTest::checkDataTest()
std::ifstream gt2;
//open the ground truth
gt2.open( gtFile.c_str() );
if( !gt2.is_open() )
{
FAIL()<< "Ground truth file " << gtFile << " can not be read" << endl;
}
ASSERT_TRUE(gt2.is_open()) << gtFile;
string line2;
int bbCounter2 = 0;
while ( getline( gt2, line2 ) )
{
vector<string> tokens = splitString( line2, "," );
Rect bb( atoi( tokens.at( 0 ).c_str() ), atoi( tokens.at( 1 ).c_str() ), atoi( tokens.at( 2 ).c_str() ), atoi( tokens.at( 3 ).c_str() ) );
if( tokens.size() != 4 )
{
FAIL()<< "Incorrect ground truth file";
}
ASSERT_EQ((size_t)4, tokens.size()) << "Incorrect ground truth file " << gtFile;
bbs.push_back( bb );
bbCounter2++;
@ -396,17 +416,12 @@ void TrackerTest::checkDataTest()
endFrame = (int)bbs.size();
}
void TrackerTest::run()
template<typename Tracker, typename ROI_t>
void TrackerTest<Tracker, ROI_t>::run()
{
srand( 1 );
SCOPED_TRACE( "A" );
srand( 1 ); // FIXIT remove that, ensure that there is no "rand()" in implementation
if( !tracker )
{
FAIL()<< "Error in the instantiation of the tracker" << endl;
return;
}
ASSERT_TRUE(tracker);
checkDataTest();
@ -414,7 +429,7 @@ void TrackerTest::run()
if( ::testing::Test::HasFatalFailure() )
return;
distanceAndOvrerlapTest();
distanceAndOverlapTest();
}
/****************************************************************************************\
@ -433,167 +448,240 @@ PARAM_TEST_CASE(DistanceAndOverlap, string)
TEST_P(DistanceAndOverlap, MedianFlow)
{
TrackerTest test( TrackerMedianFlow::create(), dataset, 35, .5f, NoTransform, 1, 1);
TrackerTest<legacy::Tracker> test(legacy::TrackerMedianFlow::create(), dataset, 35, .5f, NoTransform, 1, 1);
test.run();
}
TEST_P(DistanceAndOverlap, MIL)
{
TrackerTest test( TrackerMIL::create(), dataset, 30, .65f, NoTransform);
TrackerTest<Tracker, Rect> test(TrackerMIL::create(), dataset, 30, .65f, NoTransform);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, MIL_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerMIL::create(), dataset, 30, .65f, NoTransform);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, Boosting)
{
TrackerTest test( TrackerBoosting::create(), dataset, 70, .7f, NoTransform);
TrackerTest<legacy::Tracker> test(legacy::TrackerBoosting::create(), dataset, 70, .7f, NoTransform);
test.run();
}
TEST_P(DistanceAndOverlap, KCF)
{
TrackerTest test( TrackerKCF::create(), dataset, 20, .35f, NoTransform, 5);
TrackerTest<Tracker, Rect> test(TrackerKCF::create(), dataset, 20, .35f, NoTransform, 5);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, KCF_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerKCF::create(), dataset, 20, .35f, NoTransform, 5);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, TLD)
{
TrackerTest test( TrackerTLD::create(), dataset, 40, .45f, NoTransform);
TrackerTest<legacy::Tracker> test(legacy::TrackerTLD::create(), dataset, 40, .45f, NoTransform);
test.run();
}
TEST_P(DistanceAndOverlap, MOSSE)
{
TrackerTest test( TrackerMOSSE::create(), dataset, 22, .7f, NoTransform);
TrackerTest<legacy::Tracker> test(legacy::TrackerMOSSE::create(), dataset, 22, .7f, NoTransform);
test.run();
}
TEST_P(DistanceAndOverlap, CSRT)
{
TrackerTest test( TrackerCSRT::create(), dataset, 22, .7f, NoTransform);
TrackerTest<Tracker, Rect> test(TrackerCSRT::create(), dataset, 22, .7f, NoTransform);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, CSRT_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerCSRT::create(), dataset, 22, .7f, NoTransform);
test.run();
}
#endif
/***************************************************************************************/
//Tests with shifted initial window
TEST_P(DistanceAndOverlap, Shifted_Data_MedianFlow)
{
TrackerTest test( TrackerMedianFlow::create(), dataset, 80, .2f, CenterShiftLeft, 1, 1);
TrackerTest<legacy::Tracker> test(legacy::TrackerMedianFlow::create(), dataset, 80, .2f, CenterShiftLeft, 1, 1);
test.run();
}
TEST_P(DistanceAndOverlap, Shifted_Data_MIL)
{
TrackerTest test( TrackerMIL::create(), dataset, 30, .6f, CenterShiftLeft);
TrackerTest<Tracker, Rect> test(TrackerMIL::create(), dataset, 30, .6f, CenterShiftLeft);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Shifted_Data_MIL_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerMIL::create(), dataset, 30, .6f, CenterShiftLeft);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, Shifted_Data_Boosting)
{
TrackerTest test( TrackerBoosting::create(), dataset, 80, .65f, CenterShiftLeft);
TrackerTest<legacy::Tracker> test(legacy::TrackerBoosting::create(), dataset, 80, .65f, CenterShiftLeft);
test.run();
}
TEST_P(DistanceAndOverlap, Shifted_Data_KCF)
{
TrackerTest test( TrackerKCF::create(), dataset, 20, .4f, CenterShiftLeft, 5);
TrackerTest<Tracker, Rect> test(TrackerKCF::create(), dataset, 20, .4f, CenterShiftLeft, 5);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Shifted_Data_KCF_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerKCF::create(), dataset, 20, .4f, CenterShiftLeft, 5);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, Shifted_Data_TLD)
{
TrackerTest test( TrackerTLD::create(), dataset, 30, .35f, CenterShiftLeft);
TrackerTest<legacy::Tracker> test(legacy::TrackerTLD::create(), dataset, 30, .35f, CenterShiftLeft);
test.run();
}
TEST_P(DistanceAndOverlap, Shifted_Data_MOSSE)
{
TrackerTest test( TrackerMOSSE::create(), dataset, 13, .69f, CenterShiftLeft);
TrackerTest<legacy::Tracker> test(legacy::TrackerMOSSE::create(), dataset, 13, .69f, CenterShiftLeft);
test.run();
}
TEST_P(DistanceAndOverlap, Shifted_Data_CSRT)
{
TrackerTest test( TrackerCSRT::create(), dataset, 13, .69f, CenterShiftLeft);
TrackerTest<Tracker, Rect> test(TrackerCSRT::create(), dataset, 13, .69f, CenterShiftLeft);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Shifted_Data_CSRT_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerCSRT::create(), dataset, 13, .69f, CenterShiftLeft);
test.run();
}
#endif
/***************************************************************************************/
//Tests with scaled initial window
TEST_P(DistanceAndOverlap, Scaled_Data_MedianFlow)
{
TrackerTest test( TrackerMedianFlow::create(), dataset, 25, .5f, Scale_1_1, 1, 1);
TrackerTest<legacy::Tracker> test(legacy::TrackerMedianFlow::create(), dataset, 25, .5f, Scale_1_1, 1, 1);
test.run();
}
TEST_P(DistanceAndOverlap, Scaled_Data_MIL)
{
TrackerTest test( TrackerMIL::create(), dataset, 30, .7f, Scale_1_1);
TrackerTest<Tracker, Rect> test(TrackerMIL::create(), dataset, 30, .7f, Scale_1_1);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Scaled_Data_MIL_legacy)
{
TrackerTest<legacy::Tracker> test(legacy::TrackerMIL::create(), dataset, 30, .7f, Scale_1_1);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, Scaled_Data_Boosting)
{
TrackerTest test( TrackerBoosting::create(), dataset, 80, .7f, Scale_1_1);
TrackerTest<legacy::Tracker> test(legacy::TrackerBoosting::create(), dataset, 80, .7f, Scale_1_1);
test.run();
}
TEST_P(DistanceAndOverlap, Scaled_Data_KCF)
{
TrackerTest test( TrackerKCF::create(), dataset, 20, .4f, Scale_1_1, 5);
TrackerTest<Tracker, Rect> test(TrackerKCF::create(), dataset, 20, .4f, Scale_1_1, 5);
test.run();
}
TEST_P(DistanceAndOverlap, Scaled_Data_TLD)
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Scaled_Data_KCF_legacy)
{
TrackerTest test( TrackerTLD::create(), dataset, 30, .45f, Scale_1_1);
TrackerTest<legacy::Tracker> test(legacy::TrackerKCF::create(), dataset, 20, .4f, Scale_1_1, 5);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, DISABLED_GOTURN)
TEST_P(DistanceAndOverlap, Scaled_Data_TLD)
{
TrackerTest test(TrackerGOTURN::create(), dataset, 18, .5f, NoTransform);
TrackerTest<legacy::Tracker> test(legacy::TrackerTLD::create(), dataset, 30, .45f, Scale_1_1);
test.run();
}
TEST_P(DistanceAndOverlap, Scaled_Data_MOSSE)
{
TrackerTest test( TrackerMOSSE::create(), dataset, 22, 0.69f, Scale_1_1, 1);
TrackerTest<legacy::Tracker> test(legacy::TrackerMOSSE::create(), dataset, 22, 0.69f, Scale_1_1, 1);
test.run();
}
TEST_P(DistanceAndOverlap, Scaled_Data_CSRT)
{
TrackerTest test( TrackerCSRT::create(), dataset, 22, 0.69f, Scale_1_1, 1);
TrackerTest<Tracker, Rect> test(TrackerCSRT::create(), dataset, 22, 0.69f, Scale_1_1, 1);
test.run();
}
#ifdef TEST_LEGACY
TEST_P(DistanceAndOverlap, Scaled_Data_CSRT_legacy)
{
TrackerTest<Tracker, Rect> test(TrackerCSRT::create(), dataset, 22, 0.69f, Scale_1_1, 1);
test.run();
}
#endif
TEST_P(DistanceAndOverlap, GOTURN)
{
std::string model = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.prototxt");
std::string weights = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.caffemodel", false);
cv::TrackerGOTURN::Params params;
params.modelTxt = model;
params.modelBin = weights;
TrackerTest<Tracker, Rect> test(TrackerGOTURN::create(params), dataset, 35, .35f, NoTransform);
test.run();
}
INSTANTIATE_TEST_CASE_P(Tracking, DistanceAndOverlap, TESTSET_NAMES);
TEST(GOTURN, memory_usage)
{
cv::Rect2d roi(145, 70, 85, 85);
cv::Mat frame;
cv::Rect roi(145, 70, 85, 85);
std::string model = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.prototxt");
std::string weights = cvtest::findDataFile("dnn/gsoc2016-goturn/goturn.caffemodel", false);
cv::TrackerGOTURN::Params params;
params.modelTxt = model;
params.modelBin = weights;
cv::Ptr<cv::Tracker> tracker = cv::TrackerGOTURN::create(params);
cv::Ptr<Tracker> tracker = TrackerGOTURN::create(params);
string inputVideo = cvtest::findDataFile("tracking/david/data/david.webm");
cv::VideoCapture video(inputVideo);
ASSERT_TRUE(video.isOpened()) << inputVideo;
cv::Mat frame;
video >> frame;
ASSERT_FALSE(frame.empty()) << inputVideo;
tracker->init(frame, roi);
string ground_truth_bb;
for (int nframes = 0; nframes < 15; ++nframes)
{
std::cout << "Frame: " << nframes << std::endl;
video >> frame;
tracker->update(frame, roi);
bool res = tracker->update(frame, roi);
ASSERT_TRUE(res);
std::cout << "Predicted ROI: " << roi << std::endl;
}
}
INSTANTIATE_TEST_CASE_P( Tracking, DistanceAndOverlap, TESTSET_NAMES);
}} // namespace
/* End of file. */

@ -43,7 +43,7 @@
#include "opencv2/tracking/kalman_filters.hpp"
namespace opencv_test { namespace {
using namespace cv::tracking;
using namespace cv::detail;
// In this two tests Unscented Kalman Filter are applied to the dynamic system from example "The reentry problem" from
// "A New Extension of the Kalman Filter to Nonlinear Systems" by Simon J. Julier and Jeffrey K. Uhlmann.

@ -38,11 +38,11 @@ Explanation
You can add all tracked objects at once to the MultiTracker as shown in the code.
In this case, all objects will be tracked using same tracking algorithm as specified in decaration of MultiTracker object.
If you want to use different tracker algorithms for each tracked object,
You should add the tracked objects one by one and specify their tracking algorithm using the variant of @ref cv::MultiTracker::add.
@sa cv::MultiTracker::add( const String& trackerType, const Mat& image, const Rect2d& boundingBox )
You should add the tracked objects one by one and specify their tracking algorithm using the variant of @ref cv::legacy::MultiTracker::add.
@sa cv::legacy::MultiTracker::add( const String& trackerType, const Mat& image, const Rect2d& boundingBox )
-# **Obtaining the result**
@snippet tracking/samples/tutorial_multitracker.cpp result
You can access the result from the public variable @ref cv::MultiTracker::objects provided by the MultiTracker class as shown in the code.
You can access the result from the public variable @ref cv::legacy::MultiTracker::objects provided by the MultiTracker class as shown in the code.

Loading…
Cancel
Save