@ -1,84 +1,4 @@
/*
Tracker based on Kernelized Correlation Filter ( KCF ) [ 1 ] and Circulant Structure with Kernels ( CSK ) [ 2 ] .
CSK is implemented by using raw gray level features , since it is a single - channel filter .
KCF is implemented by using HOG features ( the default ) , since it extends CSK to multiple channels .
[ 1 ] J . F . Henriques , R . Caseiro , P . Martins , J . Batista ,
" High-Speed Tracking with Kernelized Correlation Filters " , TPAMI 2015.
[ 2 ] J . F . Henriques , R . Caseiro , P . Martins , J . Batista ,
" Exploiting the Circulant Structure of Tracking-by-detection with Kernels " , ECCV 2012.
Authors : Joao Faro , Christian Bailer , Joao F . Henriques
Contacts : joaopfaro @ gmail . com , Christian . Bailer @ dfki . de , henriques @ isr . uc . pt
Institute of Systems and Robotics - University of Coimbra / Department Augmented Vision DFKI
Constructor parameters , all boolean :
hog : use HOG features ( default ) , otherwise use raw pixels
fixed_window : fix window size ( default ) , otherwise use ROI size ( slower but more accurate )
multiscale : use multi - scale tracking ( default ; cannot be used with fixed_window = true )
Default values are set for all properties of the tracker depending on the above choices .
Their values can be customized further before calling init ( ) :
interp_factor : linear interpolation factor for adaptation
sigma : gaussian kernel bandwidth
lambda : regularization
cell_size : HOG cell size
padding : area surrounding the target , relative to its size
output_sigma_factor : bandwidth of gaussian target
template_size : template size in pixels , 0 to use ROI size
scale_step : scale step for multi - scale estimation , 1 to disable it
scale_weight : to downweight detection scores of other scales for added stability
For speed , the value ( template_size / cell_size ) should be a power of 2 or a product of small prime numbers .
Inputs to init ( ) :
image is the initial frame .
roi is a cv : : Rect with the target positions in the initial frame
Inputs to update ( ) :
image is the current frame .
Outputs of update ( ) :
cv : : Rect with target positions for the current frame
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
( 3 - clause BSD License )
Redistribution and use in source and binary forms , with or without modification ,
are permitted provided that the following conditions are met :
* Redistributions of source code must retain the above copyright notice ,
this list of conditions and the following disclaimer .
* Redistributions 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 .
* Neither the names of the copyright holders nor the names of the contributors
may 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 copyright holders 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 .
*/
# include <iostream>
# ifndef _KCFTRACKER_HEADERS
# include "kcftracker.hpp"
@ -88,75 +8,74 @@ the use of this software, even if advised of the possibility of such damage.
# include "labdata.hpp"
# endif
// Constructor
// KCFTracker类的构造函数, 用于初始化KCF跟踪器的参数
KCFTracker : : KCFTracker ( bool hog , bool fixed_window , bool multiscale , bool lab )
{
// 所有情况下参数都相同
lambda = 0.0001 ; // 权重参数
padding = 2.5 ; // 边界填充参数
output_sigma_factor = 0.125 ; // 输出高斯函数的标准差缩放因子
// Parameters equal in all cases
lambda = 0.0001 ;
padding = 2.5 ;
//output_sigma_factor = 0.1;
output_sigma_factor = 0.125 ;
if ( hog ) { // HOG
// 根据是否使用HOG特征来设置参数
if ( hog ) { // 如果使用HOG特征
// VOT
interp_factor = 0.012 ;
sigma = 0.6 ;
// TPAMI
//interp_factor = 0.02;
//sigma = 0.5;
cell_size = 4 ;
_hogfeatures = true ;
interp_factor = 0.012 ; // 插值因子
sigma = 0.6 ; // 高斯核的标准差
cell_size = 4 ; // 大小
_hogfeatures = true ; // 设置HOG特征标志为真
// 如果使用LAB特征
if ( lab ) {
interp_factor = 0.005 ;
sigma = 0.4 ;
interp_factor = 0.005 ; // 插值因子
sigma = 0.4 ; // 高斯核的标准差
//output_sigma_factor = 0.025;
output_sigma_factor = 0.1 ;
output_sigma_factor = 0.1 ; // 输出高斯函数的标准差缩放因子
_labfeatures = true ;
_labCentroids = cv : : Mat ( nClusters , 3 , CV_32FC1 , & data ) ;
cell_sizeQ = cell_size * cell_size ;
_labfeatures = true ; // 设置LAB特征标志为真
_labCentroids = cv : : Mat ( nClusters , 3 , CV_32FC1 , & data ) ; // 初始化LAB特征的聚类中心
cell_sizeQ = cell_size * cell_size ; // 计算细胞大小的平方
}
else {
_labfeatures = false ;
else {
_labfeatures = false ; // 设置LAB特征标志为假
}
}
else { // RAW
interp_factor = 0.075 ;
sigma = 0.2 ;
cell_size = 1 ;
_hogfeatures = false ;
else { // 如果使用原始特征
interp_factor = 0.075 ; // 插值因子
sigma = 0.2 ; // 高斯核的标准差
cell_size = 1 ; // 细胞大小
_hogfeatures = false ; // 设置HOG特征标志为假
// 如果尝试使用LAB特征, 则打印错误信息
if ( lab ) {
printf ( " Lab features are only used with HOG features. \n " ) ;
_labfeatures = false ;
_labfeatures = false ; // 设置LAB特征标志为假
}
}
if ( multiscale ) { // multiscale
template_size = 96 ;
// 根据是否使用多尺度来设置参数
if ( multiscale ) { // 如果使用多尺度
template_size = 96 ; // 模板大小
//template_size = 100;
scale_step = 1.05 ;
scale_weight = 0.95 ;
if ( ! fixed_window ) {
scale_step = 1.05 ; // 缩放步长
scale_weight = 0.95 ; // 缩放权重
if ( ! fixed_window ) { // 如果不是固定窗口
//printf("Multiscale does not support non-fixed window.\n");
fixed_window = true ;
fixed_window = true ; // 设置固定窗口标志为真
}
}
else if ( fixed_window ) { // fit correction without multiscale
template_size = 96 ;
else if ( fixed_window ) { // 如果使用固定窗口
template_size = 96 ; // 模板大小
//template_size = 100;
scale_step = 1 ;
scale_step = 1 ; // 缩放步长
}
else {
template_size = 1 ;
scale_step = 1 ;
else { // 如果都不使用
template_size = 1 ; // 模板大小
scale_step = 1 ; // 缩放步长
}
}
// Initialize tracker
void KCFTracker : : init ( const cv : : Rect & roi , cv : : Mat image )
{
@ -172,51 +91,51 @@ void KCFTracker::init(const cv::Rect &roi, cv::Mat image)
// Update position based on the new frame
cv : : Rect KCFTracker : : update ( cv : : Mat image )
{
if ( _roi . x + _roi . width < = 0 ) _roi . x = - _roi . width + 1 ;
if ( _roi . y + _roi . height < = 0 ) _roi . y = - _roi . height + 1 ;
if ( _roi . x > = image . cols - 1 ) _roi . x = image . cols - 2 ;
if ( _roi . y > = image . rows - 1 ) _roi . y = image . rows - 2 ;
float cx = _roi . x + _roi . width / 2.0f ;
float cy = _roi . y + _roi . height / 2.0f ;
if ( _roi . x + _roi . width < = 0 ) _roi . x = - _roi . width + 1 ; // 如果ROI的x坐标加上宽度小于0, 则调整x坐标
if ( _roi . y + _roi . height < = 0 ) _roi . y = - _roi . height + 1 ; // 如果ROI的y坐标加上高度小于0, 则调整y坐标
if ( _roi . x > = image . cols - 1 ) _roi . x = image . cols - 2 ; // 如果ROI的x坐标加上宽度大于图像宽度, 则调整x坐标
if ( _roi . y > = image . rows - 1 ) _roi . y = image . rows - 2 ; // 如果ROI的y坐标加上高度大于图像高度, 则调整y坐标
float cx = _roi . x + _roi . width / 2.0f ; // 计算ROI的中心x坐标
float cy = _roi . y + _roi . height / 2.0f ; // 计算ROI的中心y坐标
float peak_value ;
cv : : Point2f res = detect ( _tmpl , getFeatures ( image , 0 , 1.0f ) , peak_value ) ;
float peak_value ; // 峰值值
cv : : Point2f res = detect ( _tmpl , getFeatures ( image , 0 , 1.0f ) , peak_value ) ; // 使用检测函数和模板进行检测
if ( scale_step ! = 1 ) {
// Test at a smaller _scale
if ( scale_step ! = 1 ) { // 如果缩放步长不是1, 则尝试在更小的缩放级别上进行检测
// 在更小的缩放级别上进行测试
float new_peak_value ;
cv : : Point2f new_res = detect ( _tmpl , getFeatures ( image , 0 , 1.0f / scale_step ) , new_peak_value ) ;
if ( scale_weight * new_peak_value > peak_value ) {
if ( scale_weight * new_peak_value > peak_value ) { // 如果新峰值值更大,则更新结果
res = new_res ;
peak_value = new_peak_value ;
_scale / = scale_step ;
_roi . width / = scale_step ;
_roi . height / = scale_step ;
_scale / = scale_step ; // 更新缩放级别
_roi . width / = scale_step ; // 更新ROI的宽度
_roi . height / = scale_step ; // 更新ROI的高度
}
// Test at a bigger _scale
// 在更大的缩放级别上进行测试
new_res = detect ( _tmpl , getFeatures ( image , 0 , scale_step ) , new_peak_value ) ;
if ( scale_weight * new_peak_value > peak_value ) {
if ( scale_weight * new_peak_value > peak_value ) { // 如果新峰值值更大,则更新结果
res = new_res ;
peak_value = new_peak_value ;
_scale * = scale_step ;
_roi . width * = scale_step ;
_roi . height * = scale_step ;
_scale * = scale_step ; // 更新缩放级别
_roi . width * = scale_step ; // 更新ROI的宽度
_roi . height * = scale_step ; // 更新ROI的高度
}
}
// Adjust by cell size and _scale
_roi . x = cx - _roi . width / 2.0f + ( ( float ) res . x * cell_size * _scale ) ;
_roi . y = cy - _roi . height / 2.0f + ( ( float ) res . y * cell_size * _scale ) ;
// 根据细胞大小和缩放级别调整ROI
_roi . x = cx - _roi . width / 2.0f + ( ( float ) res . x * cell_size * _scale ) ; // 调整ROI的x坐标
_roi . y = cy - _roi . height / 2.0f + ( ( float ) res . y * cell_size * _scale ) ; // 调整ROI的y坐标
if ( _roi . x > = image . cols - 1 ) _roi . x = image . cols - 1 ; // 确保ROI的x坐标不超过图像宽度
if ( _roi . y > = image . rows - 1 ) _roi . y = image . rows - 1 ; // 确保ROI的y坐标不超过图像高度
if ( _roi . x + _roi . width < = 0 ) _roi . x = - _roi . width + 2 ; // 确保ROI的x坐标加上宽度大于0
if ( _roi . y + _roi . height < = 0 ) _roi . y = - _roi . height + 2 ; // 确保ROI的y坐标加上高度大于0
if ( _roi . x > = image . cols - 1 ) _roi . x = image . cols - 1 ;
if ( _roi . y > = image . rows - 1 ) _roi . y = image . rows - 1 ;
if ( _roi . x + _roi . width < = 0 ) _roi . x = - _roi . width + 2 ;
if ( _roi . y + _roi . height < = 0 ) _roi . y = - _roi . height + 2 ;
assert ( _roi . width > = 0 & & _roi . height > = 0 ) ;
cv : : Mat x = getFeatures ( image , 0 ) ;
@ -261,30 +180,20 @@ cv::Point2f KCFTracker::detect(cv::Mat z, cv::Mat x, float &peak_value)
return p ;
}
// train tracker with a single image
// 使用单个图像训练跟踪器
void KCFTracker : : train ( cv : : Mat x , float train_interp_factor )
{
using namespace FFTTools ;
cv : : Mat k = gaussianCorrelation ( x , x ) ;
cv : : Mat alphaf = complexDivision ( _prob , ( fftd ( k ) + lambda ) ) ;
_tmpl = ( 1 - train_interp_factor ) * _tmpl + ( train_interp_factor ) * x ;
_alphaf = ( 1 - train_interp_factor ) * _alphaf + ( train_interp_factor ) * alphaf ;
using namespace FFTTools ; // 引入FFTTools命名空间, 可能包含相关函数和变量
/*cv::Mat kf = fftd(gaussianCorrelation(x, x));
cv : : Mat num = complexMultiplication ( kf , _prob ) ;
cv : : Mat den = complexMultiplication ( kf , kf + lambda ) ;
_tmpl = ( 1 - train_interp_factor ) * _tmpl + ( train_interp_factor ) * x ;
_num = ( 1 - train_interp_factor ) * _num + ( train_interp_factor ) * num ;
_den = ( 1 - train_interp_factor ) * _den + ( train_interp_factor ) * den ;
cv : : Mat k = gaussianCorrelation ( x , x ) ; // 计算x和x之间的高斯相关性
cv : : Mat alphaf = complexDivision ( _prob , ( fftd ( k ) + lambda ) ) ; // 计算高斯核的傅里叶变换,并除以(核变换 + lambda)
_alphaf = complexDivision ( _num , _den ) ; */
_tmpl = ( 1 - train_interp_factor ) * _tmpl + ( train_interp_factor ) * x ; // 更新模板
_alphaf = ( 1 - train_interp_factor ) * _alphaf + ( train_interp_factor ) * alphaf ; // 更新高斯核的傅里叶变换
}
// Evaluates a Gaussian kernel with bandwidth SIGMA for all relative shifts between input images X and Y, which must both be MxN. They must also be periodic (ie., pre-processed with a cosine window).
cv : : Mat KCFTracker : : gaussianCorrelation ( cv : : Mat x1 , cv : : Mat x2 )
{
@ -321,27 +230,28 @@ cv::Mat KCFTracker::gaussianCorrelation(cv::Mat x1, cv::Mat x2)
return k ;
}
// Create Gaussian Peak. Function called only in the first frame.
// 在第一帧中创建高斯峰值
cv : : Mat KCFTracker : : createGaussianPeak ( int sizey , int sizex )
{
cv : : Mat_ < float > res ( sizey , sizex ) ;
cv : : Mat_ < float > res ( sizey , sizex ) ; // 创建一个浮点数矩阵, 大小为sizey x sizex
int syh = ( sizey ) / 2 ;
int sxh = ( sizex ) / 2 ;
int syh = ( sizey ) / 2 ; // 计算y方向的高斯峰值中心
int sxh = ( sizex ) / 2 ; // 计算x方向的高斯峰值中心
float output_sigma = std : : sqrt ( ( float ) sizex * sizey ) / padding * output_sigma_factor ;
float mult = - 0.5 / ( output_sigma * output_sigma ) ;
float output_sigma = std : : sqrt ( ( float ) sizex * sizey ) / padding * output_sigma_factor ; // 计算输出高斯核的标准差
float mult = - 0.5 / ( output_sigma * output_sigma ) ; // 计算高斯核的缩放因子
for ( int i = 0 ; i < sizey ; i + + )
for ( int j = 0 ; j < sizex ; j + + )
for ( int i = 0 ; i < sizey ; i + + ) // 遍历矩阵的每一行
for ( int j = 0 ; j < sizex ; j + + ) // 遍历矩阵的每一列
{
int ih = i - syh ;
int jh = j - sxh ;
res ( i , j ) = std : : exp ( mult * ( float ) ( ih * ih + jh * jh ) ) ;
int ih = i - syh ; // 计算当前点与y方向高斯峰值中心的距离
int jh = j - sxh ; // 计算当前点与x方向高斯峰值中心的距离
res ( i , j ) = std : : exp ( mult * ( float ) ( ih * ih + jh * jh ) ) ; // 计算高斯函数的值
}
return FFTTools : : fftd ( res ) ;
return FFTTools : : fftd ( res ) ; // 返回高斯峰值的傅里叶变换
}
// Obtain sub-window from image, with replication-padding and extract features
cv : : Mat KCFTracker : : getFeatures ( const cv : : Mat & image , bool inithann , float scale_adjust )
{
@ -486,22 +396,25 @@ cv::Mat KCFTracker::getFeatures(const cv::Mat & image, bool inithann, float scal
return FeaturesMap ;
}
// Initialize Hanning window. Function called only in the first frame.
// 初始化汉明窗口。该函数仅在第一帧调用。
void KCFTracker : : createHanningMats ( )
{
{
cv : : Mat hann1t = cv : : Mat ( cv : : Size ( size_patch [ 1 ] , 1 ) , CV_32F , cv : : Scalar ( 0 ) ) ;
cv : : Mat hann2t = cv : : Mat ( cv : : Size ( 1 , size_patch [ 0 ] ) , CV_32F , cv : : Scalar ( 0 ) ) ;
cv : : Mat hann2t = cv : : Mat ( cv : : Size ( 1 , size_patch [ 0 ] ) , CV_32F , cv : : Scalar ( 0 ) ) ;
// 创建汉明窗口的一维版本
for ( int i = 0 ; i < hann1t . cols ; i + + )
hann1t . at < float > ( 0 , i ) = 0.5 * ( 1 - std : : cos ( 2 * 3.14159265358979323846 * i / ( hann1t . cols - 1 ) ) ) ;
hann1t . at < float > ( 0 , i ) = 0.5 * ( 1 - std : : cos ( 2 * 3.14159265358979323846 * i / ( hann1t . cols - 1 ) ) ) ;
for ( int i = 0 ; i < hann2t . rows ; i + + )
hann2t . at < float > ( i , 0 ) = 0.5 * ( 1 - std : : cos ( 2 * 3.14159265358979323846 * i / ( hann2t . rows - 1 ) ) ) ;
hann2t . at < float > ( i , 0 ) = 0.5 * ( 1 - std : : cos ( 2 * 3.14159265358979323846 * i / ( hann2t . rows - 1 ) ) ) ;
// 将一维汉明窗口组合成二维汉明窗口
cv : : Mat hann2d = hann2t * hann1t ;
// HOG features
// HOG特征
if ( _hogfeatures ) {
cv : : Mat hann1d = hann2d . reshape ( 1 , 1 ) ; // Procedure do deal with cv::Mat multichannel bug
cv : : Mat hann1d = hann2d . reshape ( 1 , 1 ) ; // 解决cv::Mat多通道bug的步骤
hann = cv : : Mat ( cv : : Size ( size_patch [ 0 ] * size_patch [ 1 ] , size_patch [ 2 ] ) , CV_32F , cv : : Scalar ( 0 ) ) ;
for ( int i = 0 ; i < size_patch [ 2 ] ; i + + ) {
for ( int j = 0 ; j < size_patch [ 0 ] * size_patch [ 1 ] ; j + + ) {
@ -509,15 +422,15 @@ void KCFTracker::createHanningMats()
}
}
}
// Gray features
// 灰度特征
else {
hann = hann2d ;
}
}
// Calculate sub-pixel peak for one dimension
// 为单维度计算亚像素峰值
float KCFTracker : : subPixelPeak ( float left , float center , float right )
{
{
float divisor = 2 * center - right - left ;
if ( divisor = = 0 )