Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
PaddlePaddle
PaddleDetection
提交
531bca9d
P
PaddleDetection
项目概览
PaddlePaddle
/
PaddleDetection
大约 2 年 前同步成功
通知
708
Star
11112
Fork
2696
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
184
列表
看板
标记
里程碑
合并请求
40
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
P
PaddleDetection
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
184
Issue
184
列表
看板
标记
里程碑
合并请求
40
合并请求
40
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
未验证
提交
531bca9d
编写于
11月 08, 2021
作者:
W
wangguanzhong
提交者:
GitHub
11月 08, 2021
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
[MOT] add cpplint & refine format in pptracking (#4501)
上级
305928b8
变更
22
展开全部
显示空白变更内容
内联
并排
Showing
22 changed file
with
1680 addition
and
1636 deletion
+1680
-1636
.pre-commit-config.yaml
.pre-commit-config.yaml
+17
-0
.travis/codestyle/clang_format.hook
.travis/codestyle/clang_format.hook
+15
-0
.travis/codestyle/cpplint_pre_commit.hook
.travis/codestyle/cpplint_pre_commit.hook
+27
-0
deploy/pptracking/include/config_parser.h
deploy/pptracking/include/config_parser.h
+3
-5
deploy/pptracking/include/jde_predictor.h
deploy/pptracking/include/jde_predictor.h
+22
-25
deploy/pptracking/include/lapjv.h
deploy/pptracking/include/lapjv.h
+24
-12
deploy/pptracking/include/pipeline.h
deploy/pptracking/include/pipeline.h
+37
-28
deploy/pptracking/include/postprocess.h
deploy/pptracking/include/postprocess.h
+15
-11
deploy/pptracking/include/preprocess_op.h
deploy/pptracking/include/preprocess_op.h
+12
-13
deploy/pptracking/include/sde_predictor.h
deploy/pptracking/include/sde_predictor.h
+23
-26
deploy/pptracking/include/tracker.h
deploy/pptracking/include/tracker.h
+39
-30
deploy/pptracking/include/trajectory.h
deploy/pptracking/include/trajectory.h
+181
-153
deploy/pptracking/include/utils.h
deploy/pptracking/include/utils.h
+14
-16
deploy/pptracking/src/jde_predictor.cc
deploy/pptracking/src/jde_predictor.cc
+44
-45
deploy/pptracking/src/lapjv.cpp
deploy/pptracking/src/lapjv.cpp
+325
-321
deploy/pptracking/src/main.cc
deploy/pptracking/src/main.cc
+49
-26
deploy/pptracking/src/pipeline.cc
deploy/pptracking/src/pipeline.cc
+72
-46
deploy/pptracking/src/postprocess.cc
deploy/pptracking/src/postprocess.cc
+34
-30
deploy/pptracking/src/preprocess_op.cc
deploy/pptracking/src/preprocess_op.cc
+42
-64
deploy/pptracking/src/sde_predictor.cc
deploy/pptracking/src/sde_predictor.cc
+9
-13
deploy/pptracking/src/tracker.cc
deploy/pptracking/src/tracker.cc
+254
-283
deploy/pptracking/src/trajectory.cc
deploy/pptracking/src/trajectory.cc
+422
-489
未找到文件。
.pre-commit-config.yaml
浏览文件 @
531bca9d
...
@@ -25,3 +25,20 @@
...
@@ -25,3 +25,20 @@
files
:
\.(md|yml)$
files
:
\.(md|yml)$
-
id
:
remove-tabs
-
id
:
remove-tabs
files
:
\.(md|yml)$
files
:
\.(md|yml)$
-
repo
:
local
hooks
:
-
id
:
clang-format-with-version-check
name
:
clang-format
description
:
Format files with ClangFormat.
entry
:
bash ./.travis/codestyle/clang_format.hook -i
language
:
system
files
:
\.(c|cc|cxx|cpp|cu|h|hpp|hxx|proto)$
-
repo
:
local
hooks
:
-
id
:
cpplint-cpp-source
name
:
cpplint
description
:
Check C++ code style using cpplint.py.
entry
:
bash ./.travis/codestyle/cpplint_pre_commit.hook
language
:
system
files
:
\.(c|cc|cxx|cpp|cu|h|hpp|hxx)$
.travis/codestyle/clang_format.hook
0 → 100644
浏览文件 @
531bca9d
#!/bin/bash
set
-e
readonly
VERSION
=
"3.8"
version
=
$(
clang-format
-version
)
if
!
[[
$version
==
*
"
$VERSION
"
*
]]
;
then
echo
"clang-format version check failed."
echo
"a version contains '
$VERSION
' is needed, but get '
$version
'"
echo
"you can install the right version, and make an soft-link to '
\$
PATH' env"
exit
-1
fi
clang-format
$@
.travis/codestyle/cpplint_pre_commit.hook
0 → 100644
浏览文件 @
531bca9d
#!/bin/bash
TOTAL_ERRORS
=
0
if
[[
!
$TRAVIS_BRANCH
]]
;
then
# install cpplint on local machine.
if
[[
!
$(
which cpplint
)
]]
;
then
pip
install
cpplint
fi
# diff files on local machine.
files
=
$(
git diff
--cached
--name-status
|
awk
'$1 != "D" {print $2}'
)
else
# diff files between PR and latest commit on Travis CI.
branch_ref
=
$(
git rev-parse
"
$TRAVIS_BRANCH
"
)
head_ref
=
$(
git rev-parse HEAD
)
files
=
$(
git diff
--name-status
$branch_ref
$head_ref
|
awk
'$1 != "D" {print $2}'
)
fi
# The trick to remove deleted files: https://stackoverflow.com/a/2413151
for
file
in
$files
;
do
if
[[
$file
=
~ ^
(
patches/.
*
)
]]
;
then
continue
;
else
cpplint
--filter
=
-readability
/fn_size,-build/include_what_you_use,-build/c++11
$file
;
TOTAL_ERRORS
=
$(
expr
$TOTAL_ERRORS
+
$?
)
;
fi
done
exit
$TOTAL_ERRORS
deploy/pptracking/include/config_parser.h
浏览文件 @
531bca9d
...
@@ -15,9 +15,9 @@
...
@@ -15,9 +15,9 @@
#pragma once
#pragma once
#include <iostream>
#include <iostream>
#include <vector>
#include <string>
#include <map>
#include <map>
#include <string>
#include <vector>
#include "yaml-cpp/yaml.h"
#include "yaml-cpp/yaml.h"
...
@@ -47,8 +47,7 @@ class ConfigPaser {
...
@@ -47,8 +47,7 @@ class ConfigPaser {
mode_
=
config
[
"mode"
].
as
<
std
::
string
>
();
mode_
=
config
[
"mode"
].
as
<
std
::
string
>
();
}
else
{
}
else
{
std
::
cerr
<<
"Please set mode, "
std
::
cerr
<<
"Please set mode, "
<<
"support value : fluid/trt_fp16/trt_fp32."
<<
"support value : fluid/trt_fp16/trt_fp32."
<<
std
::
endl
;
<<
std
::
endl
;
return
false
;
return
false
;
}
}
...
@@ -136,4 +135,3 @@ class ConfigPaser {
...
@@ -136,4 +135,3 @@ class ConfigPaser {
};
};
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/include/jde_predictor.h
浏览文件 @
531bca9d
...
@@ -14,37 +14,37 @@
...
@@ -14,37 +14,37 @@
#pragma once
#pragma once
#include <string>
#include <ctime>
#include <vector>
#include <memory>
#include <memory>
#include <string>
#include <utility>
#include <utility>
#include <
ctime
>
#include <
vector
>
#include <opencv2/core/core.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "paddle_inference_api.h" // NOLINT
#include "paddle_inference_api.h" // NOLINT
#include "include/preprocess_op.h"
#include "include/config_parser.h"
#include "include/config_parser.h"
#include "include/preprocess_op.h"
#include "include/utils.h"
#include "include/utils.h"
using
namespace
paddle_infer
;
using
namespace
paddle_infer
;
// NOLINT
namespace
PaddleDetection
{
namespace
PaddleDetection
{
class
JDEPredictor
{
class
JDEPredictor
{
public:
public:
explicit
JDEPredictor
(
const
std
::
string
&
device
=
"CPU"
,
explicit
JDEPredictor
(
const
std
::
string
&
device
=
"CPU"
,
const
std
::
string
&
model_dir
=
""
,
const
std
::
string
&
model_dir
=
""
,
const
double
threshold
=
-
1.
,
const
double
threshold
=
-
1.
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
int
gpu_id
=
0
,
const
int
gpu_id
=
0
,
const
bool
use_mkldnn
=
false
,
const
bool
use_mkldnn
=
false
,
const
int
cpu_threads
=
1
,
const
int
cpu_threads
=
1
,
bool
trt_calib_mode
=
false
,
bool
trt_calib_mode
=
false
,
const
int
min_box_area
=
200
)
{
const
int
min_box_area
=
200
)
{
this
->
device_
=
device
;
this
->
device_
=
device
;
this
->
gpu_id_
=
gpu_id
;
this
->
gpu_id_
=
gpu_id
;
this
->
use_mkldnn_
=
use_mkldnn
;
this
->
use_mkldnn_
=
use_mkldnn
;
...
@@ -60,8 +60,7 @@ class JDEPredictor {
...
@@ -60,8 +60,7 @@ class JDEPredictor {
}
}
// Load Paddle inference model
// Load Paddle inference model
void
LoadModel
(
void
LoadModel
(
const
std
::
string
&
model_dir
,
const
std
::
string
&
model_dir
,
const
std
::
string
&
run_mode
=
"fluid"
);
const
std
::
string
&
run_mode
=
"fluid"
);
// Run predictor
// Run predictor
...
@@ -82,9 +81,7 @@ class JDEPredictor {
...
@@ -82,9 +81,7 @@ class JDEPredictor {
// Preprocess image and copy data to input buffer
// Preprocess image and copy data to input buffer
void
Preprocess
(
const
cv
::
Mat
&
image_mat
);
void
Preprocess
(
const
cv
::
Mat
&
image_mat
);
// Postprocess result
// Postprocess result
void
Postprocess
(
void
Postprocess
(
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
MOTResult
*
result
);
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
MOTResult
*
result
);
std
::
shared_ptr
<
Predictor
>
predictor_
;
std
::
shared_ptr
<
Predictor
>
predictor_
;
Preprocessor
preprocessor_
;
Preprocessor
preprocessor_
;
...
...
deploy/pptracking/include/lapjv.h
浏览文件 @
531bca9d
...
@@ -17,9 +17,8 @@
...
@@ -17,9 +17,8 @@
// Ths copyright of gatagat/lap is as follows:
// Ths copyright of gatagat/lap is as follows:
// MIT License
// MIT License
#ifndef LAPJV_H
#ifndef DEPLOY_PPTRACKING_INCLUDE_LAPJV_H_
#define LAPJV_H
#define DEPLOY_PPTRACKING_INCLUDE_LAPJV_H_
#define LARGE 1000000
#define LARGE 1000000
#if !defined TRUE
#if !defined TRUE
...
@@ -29,9 +28,21 @@
...
@@ -29,9 +28,21 @@
#define FALSE 0
#define FALSE 0
#endif
#endif
#define NEW(x, t, n) if ((x = (t *)malloc(sizeof(t) * (n))) == 0) {return -1;}
#define NEW(x, t, n) \
#define FREE(x) if (x != 0) { free(x); x = 0; }
if ((x = reinterpret_cast<t *>(malloc(sizeof(t) * (n)))) == 0) { \
#define SWAP_INDICES(a, b) { int_t _temp_index = a; a = b; b = _temp_index; }
return -1; \
}
#define FREE(x) \
if (x != 0) { \
free(x); \
x = 0; \
}
#define SWAP_INDICES(a, b) \
{ \
int_t _temp_index = a; \
a = b; \
b = _temp_index; \
}
#include <opencv2/opencv.hpp>
#include <opencv2/opencv.hpp>
namespace
PaddleDetection
{
namespace
PaddleDetection
{
...
@@ -42,11 +53,12 @@ typedef double cost_t;
...
@@ -42,11 +53,12 @@ typedef double cost_t;
typedef
char
boolean
;
typedef
char
boolean
;
typedef
enum
fp_t
{
FP_1
=
1
,
FP_2
=
2
,
FP_DYNAMIC
=
3
}
fp_t
;
typedef
enum
fp_t
{
FP_1
=
1
,
FP_2
=
2
,
FP_DYNAMIC
=
3
}
fp_t
;
int
lapjv_internal
(
int
lapjv_internal
(
const
cv
::
Mat
&
cost
,
const
cv
::
Mat
&
cost
,
const
bool
extend_cost
,
const
float
cost_limit
,
const
bool
extend_cost
,
int
*
x
,
int
*
y
);
const
float
cost_limit
,
int
*
x
,
int
*
y
);
}
// namespace PaddleDetection
}
// namespace PaddleDetection
#endif // LAPJV_H
#endif // DEPLOY_PPTRACKING_INCLUDE_LAPJV_H_
deploy/pptracking/include/pipeline.h
浏览文件 @
531bca9d
...
@@ -12,16 +12,18 @@
...
@@ -12,16 +12,18 @@
// See the License for the specific language governing permissions and
// See the License for the specific language governing permissions and
// limitations under the License.
// limitations under the License.
#ifndef DEPLOY_PPTRACKING_INCLUDE_PIPELINE_H_
#define DEPLOY_PPTRACKING_INCLUDE_PIPELINE_H_
#include <glog/logging.h>
#include <glog/logging.h>
#include <math.h>
#include <sys/types.h>
#include <algorithm>
#include <iostream>
#include <iostream>
#include <numeric>
#include <string>
#include <string>
#include <vector>
#include <vector>
#include <numeric>
#include <sys/types.h>
#include <sys/stat.h>
#include <math.h>
#include <algorithm>
#ifdef _WIN32
#ifdef _WIN32
#include <direct.h>
#include <direct.h>
...
@@ -41,16 +43,16 @@ class Pipeline {
...
@@ -41,16 +43,16 @@ class Pipeline {
explicit
Pipeline
(
const
std
::
string
&
device
,
explicit
Pipeline
(
const
std
::
string
&
device
,
const
double
threshold
,
const
double
threshold
,
const
std
::
string
&
output_dir
,
const
std
::
string
&
output_dir
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
int
gpu_id
=
0
,
const
int
gpu_id
=
0
,
const
bool
use_mkldnn
=
false
,
const
bool
use_mkldnn
=
false
,
const
int
cpu_threads
=
1
,
const
int
cpu_threads
=
1
,
const
bool
trt_calib_mode
=
false
,
const
bool
trt_calib_mode
=
false
,
const
bool
count
=
false
,
const
bool
count
=
false
,
const
bool
save_result
=
false
,
const
bool
save_result
=
false
,
const
std
::
string
&
scene
=
"pedestrian"
,
const
std
::
string
&
scene
=
"pedestrian"
,
const
bool
tiny_obj
=
false
,
const
bool
tiny_obj
=
false
,
const
bool
is_mtmct
=
false
)
{
const
bool
is_mtmct
=
false
)
{
std
::
vector
<
std
::
string
>
input
;
std
::
vector
<
std
::
string
>
input
;
this
->
input_
=
input
;
this
->
input_
=
input
;
this
->
device_
=
device
;
this
->
device_
=
device
;
...
@@ -67,10 +69,8 @@ class Pipeline {
...
@@ -67,10 +69,8 @@ class Pipeline {
InitPredictor
();
InitPredictor
();
}
}
// Set input, it must execute before Run()
// Set input, it must execute before Run()
void
SetInput
(
std
::
string
&
input_video
);
void
SetInput
(
const
std
::
string
&
input_video
);
void
ClearInput
();
void
ClearInput
();
// Run pipeline in video
// Run pipeline in video
...
@@ -79,16 +79,23 @@ class Pipeline {
...
@@ -79,16 +79,23 @@ class Pipeline {
void
PredictMTMCT
(
const
std
::
vector
<
std
::
string
>
video_inputs
);
void
PredictMTMCT
(
const
std
::
vector
<
std
::
string
>
video_inputs
);
// Run pipeline in stream
// Run pipeline in stream
void
RunMOTStream
(
const
cv
::
Mat
img
,
const
int
frame_id
,
cv
::
Mat
&
out_img
,
std
::
vector
<
std
::
string
>&
records
,
std
::
vector
<
int
>&
count_list
,
std
::
vector
<
int
>&
in_count_list
,
std
::
vector
<
int
>&
out_count_list
);
void
RunMOTStream
(
const
cv
::
Mat
img
,
void
RunMTMCTStream
(
const
std
::
vector
<
cv
::
Mat
>
imgs
,
std
::
vector
<
std
::
string
>&
records
);
const
int
frame_id
,
cv
::
Mat
out_img
,
void
PrintBenchmarkLog
(
std
::
vector
<
double
>
det_time
,
int
img_num
);
std
::
vector
<
std
::
string
>*
records
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
out_count_list
);
void
RunMTMCTStream
(
const
std
::
vector
<
cv
::
Mat
>
imgs
,
std
::
vector
<
std
::
string
>*
records
);
void
PrintBenchmarkLog
(
const
std
::
vector
<
double
>
det_time
,
const
int
img_num
);
private:
private:
// Select model according to scenes, it must execute before Run()
// Select model according to scenes, it must execute before Run()
void
SelectModel
(
const
std
::
string
&
scene
=
"pedestrian"
,
void
SelectModel
(
const
std
::
string
&
scene
=
"pedestrian"
,
const
bool
tiny_obj
=
false
,
const
bool
tiny_obj
=
false
,
const
bool
is_mtmct
=
false
);
const
bool
is_mtmct
=
false
);
void
InitPredictor
();
void
InitPredictor
();
std
::
shared_ptr
<
PaddleDetection
::
JDEPredictor
>
jde_sct_
;
std
::
shared_ptr
<
PaddleDetection
::
JDEPredictor
>
jde_sct_
;
...
@@ -112,3 +119,5 @@ class Pipeline {
...
@@ -112,3 +119,5 @@ class Pipeline {
};
};
}
// namespace PaddleDetection
}
// namespace PaddleDetection
#endif // DEPLOY_PPTRACKING_INCLUDE_PIPELINE_H_
deploy/pptracking/include/postprocess.h
浏览文件 @
531bca9d
...
@@ -14,15 +14,15 @@
...
@@ -14,15 +14,15 @@
#pragma once
#pragma once
#include <string>
#include <ctime>
#include <vector>
#include <memory>
#include <memory>
#include <string>
#include <utility>
#include <utility>
#include <
ctime
>
#include <
vector
>
#include <opencv2/core/core.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "include/utils.h"
#include "include/utils.h"
...
@@ -34,15 +34,19 @@ cv::Scalar GetColor(int idx);
...
@@ -34,15 +34,19 @@ cv::Scalar GetColor(int idx);
// Visualize Tracking Results
// Visualize Tracking Results
cv
::
Mat
VisualizeTrackResult
(
const
cv
::
Mat
&
img
,
cv
::
Mat
VisualizeTrackResult
(
const
cv
::
Mat
&
img
,
const
MOTResult
&
results
,
const
MOTResult
&
results
,
const
float
fps
,
const
int
frame_id
);
const
float
fps
,
const
int
frame_id
);
// Pedestrian/Vehicle Counting
// Pedestrian/Vehicle Counting
void
FlowStatistic
(
const
MOTResult
&
results
,
const
int
frame_id
,
void
FlowStatistic
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
out_count_list
);
std
::
vector
<
int
>*
out_count_list
);
// Save Tracking Results
// Save Tracking Results
void
SaveMOTResult
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
std
::
string
>&
records
);
void
SaveMOTResult
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
std
::
string
>*
records
);
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/include/preprocess_op.h
浏览文件 @
531bca9d
...
@@ -17,16 +17,16 @@
...
@@ -17,16 +17,16 @@
#include <glog/logging.h>
#include <glog/logging.h>
#include <yaml-cpp/yaml.h>
#include <yaml-cpp/yaml.h>
#include <vector>
#include <iostream>
#include <string>
#include <utility>
#include <memory>
#include <memory>
#include <string>
#include <unordered_map>
#include <unordered_map>
#include <iostream>
#include <utility>
#include <vector>
#include <opencv2/core/core.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
namespace
PaddleDetection
{
namespace
PaddleDetection
{
...
@@ -40,7 +40,7 @@ class ImageBlob {
...
@@ -40,7 +40,7 @@ class ImageBlob {
// in net data shape(after pad)
// in net data shape(after pad)
std
::
vector
<
float
>
in_net_shape_
;
std
::
vector
<
float
>
in_net_shape_
;
// Evaluation image width and height
// Evaluation image width and height
//std::vector<float> eval_im_size_f_;
//
std::vector<float> eval_im_size_f_;
// Scale factor for image size to origin image size
// Scale factor for image size to origin image size
std
::
vector
<
float
>
scale_factor_
;
std
::
vector
<
float
>
scale_factor_
;
};
};
...
@@ -52,7 +52,7 @@ class PreprocessOp {
...
@@ -52,7 +52,7 @@ class PreprocessOp {
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
=
0
;
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
=
0
;
};
};
class
InitInfo
:
public
PreprocessOp
{
class
InitInfo
:
public
PreprocessOp
{
public:
public:
virtual
void
Init
(
const
YAML
::
Node
&
item
)
{}
virtual
void
Init
(
const
YAML
::
Node
&
item
)
{}
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
);
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
);
...
@@ -79,7 +79,6 @@ class Permute : public PreprocessOp {
...
@@ -79,7 +79,6 @@ class Permute : public PreprocessOp {
public:
public:
virtual
void
Init
(
const
YAML
::
Node
&
item
)
{}
virtual
void
Init
(
const
YAML
::
Node
&
item
)
{}
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
);
virtual
void
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
);
};
};
class
Resize
:
public
PreprocessOp
{
class
Resize
:
public
PreprocessOp
{
...
@@ -155,7 +154,8 @@ class Preprocessor {
...
@@ -155,7 +154,8 @@ class Preprocessor {
// use PadStride instead of PadBatch
// use PadStride instead of PadBatch
return
std
::
make_shared
<
PadStride
>
();
return
std
::
make_shared
<
PadStride
>
();
}
}
std
::
cerr
<<
"can not find function of OP: "
<<
name
<<
" and return: nullptr"
<<
std
::
endl
;
std
::
cerr
<<
"can not find function of OP: "
<<
name
<<
" and return: nullptr"
<<
std
::
endl
;
return
nullptr
;
return
nullptr
;
}
}
...
@@ -169,4 +169,3 @@ class Preprocessor {
...
@@ -169,4 +169,3 @@ class Preprocessor {
};
};
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/include/sde_predictor.h
浏览文件 @
531bca9d
...
@@ -14,38 +14,38 @@
...
@@ -14,38 +14,38 @@
#pragma once
#pragma once
#include <string>
#include <ctime>
#include <vector>
#include <memory>
#include <memory>
#include <string>
#include <utility>
#include <utility>
#include <
ctime
>
#include <
vector
>
#include <opencv2/core/core.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "paddle_inference_api.h" // NOLINT
#include "paddle_inference_api.h" // NOLINT
#include "include/preprocess_op.h"
#include "include/config_parser.h"
#include "include/config_parser.h"
#include "include/preprocess_op.h"
#include "include/utils.h"
#include "include/utils.h"
using
namespace
paddle_infer
;
using
namespace
paddle_infer
;
// NOLINT
namespace
PaddleDetection
{
namespace
PaddleDetection
{
class
SDEPredictor
{
class
SDEPredictor
{
public:
public:
explicit
SDEPredictor
(
const
std
::
string
&
device
,
explicit
SDEPredictor
(
const
std
::
string
&
device
,
const
std
::
string
&
det_model_dir
=
""
,
const
std
::
string
&
det_model_dir
=
""
,
const
std
::
string
&
reid_model_dir
=
""
,
const
std
::
string
&
reid_model_dir
=
""
,
const
double
threshold
=
-
1.
,
const
double
threshold
=
-
1.
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
std
::
string
&
run_mode
=
"fluid"
,
const
int
gpu_id
=
0
,
const
int
gpu_id
=
0
,
const
bool
use_mkldnn
=
false
,
const
bool
use_mkldnn
=
false
,
const
int
cpu_threads
=
1
,
const
int
cpu_threads
=
1
,
bool
trt_calib_mode
=
false
,
bool
trt_calib_mode
=
false
,
const
int
min_box_area
=
200
)
{
const
int
min_box_area
=
200
)
{
this
->
device_
=
device
;
this
->
device_
=
device
;
this
->
gpu_id_
=
gpu_id
;
this
->
gpu_id_
=
gpu_id
;
this
->
use_mkldnn_
=
use_mkldnn
;
this
->
use_mkldnn_
=
use_mkldnn
;
...
@@ -65,8 +65,7 @@ class SDEPredictor {
...
@@ -65,8 +65,7 @@ class SDEPredictor {
}
}
// Load Paddle inference model
// Load Paddle inference model
void
LoadModel
(
void
LoadModel
(
const
std
::
string
&
det_model_dir
,
const
std
::
string
&
det_model_dir
,
const
std
::
string
&
reid_model_dir
,
const
std
::
string
&
reid_model_dir
,
const
std
::
string
&
run_mode
=
"fluid"
);
const
std
::
string
&
run_mode
=
"fluid"
);
...
@@ -88,9 +87,7 @@ class SDEPredictor {
...
@@ -88,9 +87,7 @@ class SDEPredictor {
// Preprocess image and copy data to input buffer
// Preprocess image and copy data to input buffer
void
Preprocess
(
const
cv
::
Mat
&
image_mat
);
void
Preprocess
(
const
cv
::
Mat
&
image_mat
);
// Postprocess result
// Postprocess result
void
Postprocess
(
void
Postprocess
(
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
MOTResult
*
result
);
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
MOTResult
*
result
);
std
::
shared_ptr
<
Predictor
>
det_predictor_
;
std
::
shared_ptr
<
Predictor
>
det_predictor_
;
std
::
shared_ptr
<
Predictor
>
reid_predictor_
;
std
::
shared_ptr
<
Predictor
>
reid_predictor_
;
...
...
deploy/pptracking/include/tracker.h
浏览文件 @
531bca9d
...
@@ -21,35 +21,44 @@
...
@@ -21,35 +21,44 @@
#include <map>
#include <map>
#include <vector>
#include <vector>
#include <opencv2/opencv.hpp>
#include "trajectory.h"
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "include/trajectory.h"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
typedef
std
::
map
<
int
,
int
>
Match
;
typedef
std
::
map
<
int
,
int
>
Match
;
typedef
std
::
map
<
int
,
int
>::
iterator
MatchIterator
;
typedef
std
::
map
<
int
,
int
>::
iterator
MatchIterator
;
struct
Track
struct
Track
{
{
int
id
;
int
id
;
float
score
;
float
score
;
cv
::
Vec4f
ltrb
;
cv
::
Vec4f
ltrb
;
};
};
class
JDETracker
class
JDETracker
{
{
public:
public:
static
JDETracker
*
instance
(
void
);
static
JDETracker
*
instance
(
void
);
virtual
bool
update
(
const
cv
::
Mat
&
dets
,
const
cv
::
Mat
&
emb
,
std
::
vector
<
Track
>
&
tracks
);
virtual
bool
update
(
const
cv
::
Mat
&
dets
,
private:
const
cv
::
Mat
&
emb
,
std
::
vector
<
Track
>
*
tracks
);
private:
JDETracker
(
void
);
JDETracker
(
void
);
virtual
~
JDETracker
(
void
)
{}
virtual
~
JDETracker
(
void
)
{}
cv
::
Mat
motion_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
cv
::
Mat
motion_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
void
linear_assignment
(
const
cv
::
Mat
&
cost
,
float
cost_limit
,
Match
&
matches
,
void
linear_assignment
(
const
cv
::
Mat
&
cost
,
std
::
vector
<
int
>
&
mismatch_row
,
std
::
vector
<
int
>
&
mismatch_col
);
float
cost_limit
,
void
remove_duplicate_trajectory
(
TrajectoryPool
&
a
,
TrajectoryPool
&
b
,
float
iou_thresh
=
0.15
f
);
Match
*
matches
,
private:
std
::
vector
<
int
>
*
mismatch_row
,
std
::
vector
<
int
>
*
mismatch_col
);
void
remove_duplicate_trajectory
(
TrajectoryPool
*
a
,
TrajectoryPool
*
b
,
float
iou_thresh
=
0.15
f
);
private:
static
JDETracker
*
me
;
static
JDETracker
*
me
;
int
timestamp
;
int
timestamp
;
TrajectoryPool
tracked_trajectories
;
TrajectoryPool
tracked_trajectories
;
...
...
deploy/pptracking/include/trajectory.h
浏览文件 @
531bca9d
...
@@ -20,88 +20,104 @@
...
@@ -20,88 +20,104 @@
#pragma once
#pragma once
#include <vector>
#include <vector>
#include <opencv2/opencv.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "opencv2/video/tracking.hpp"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
typedef
enum
typedef
enum
{
New
=
0
,
Tracked
=
1
,
Lost
=
2
,
Removed
=
3
}
TrajectoryState
;
{
New
=
0
,
Tracked
=
1
,
Lost
=
2
,
Removed
=
3
}
TrajectoryState
;
class
Trajectory
;
class
Trajectory
;
typedef
std
::
vector
<
Trajectory
>
TrajectoryPool
;
typedef
std
::
vector
<
Trajectory
>
TrajectoryPool
;
typedef
std
::
vector
<
Trajectory
>::
iterator
TrajectoryPoolIterator
;
typedef
std
::
vector
<
Trajectory
>::
iterator
TrajectoryPoolIterator
;
typedef
std
::
vector
<
Trajectory
*>
TrajectoryPtrPool
;
typedef
std
::
vector
<
Trajectory
*>
TrajectoryPtrPool
;
typedef
std
::
vector
<
Trajectory
*>::
iterator
TrajectoryPtrPoolIterator
;
typedef
std
::
vector
<
Trajectory
*>::
iterator
TrajectoryPtrPoolIterator
;
class
TKalmanFilter
:
public
cv
::
KalmanFilter
class
TKalmanFilter
:
public
cv
::
KalmanFilter
{
{
public:
public:
TKalmanFilter
(
void
);
TKalmanFilter
(
void
);
virtual
~
TKalmanFilter
(
void
)
{}
virtual
~
TKalmanFilter
(
void
)
{}
virtual
void
init
(
const
cv
::
Mat
&
measurement
);
virtual
void
init
(
const
cv
::
Mat
&
measurement
);
virtual
const
cv
::
Mat
&
predict
();
virtual
const
cv
::
Mat
&
predict
();
virtual
const
cv
::
Mat
&
correct
(
const
cv
::
Mat
&
measurement
);
virtual
const
cv
::
Mat
&
correct
(
const
cv
::
Mat
&
measurement
);
virtual
void
project
(
cv
::
Mat
&
mean
,
cv
::
Mat
&
covariance
)
const
;
virtual
void
project
(
cv
::
Mat
*
mean
,
cv
::
Mat
*
covariance
)
const
;
private:
private:
float
std_weight_position
;
float
std_weight_position
;
float
std_weight_velocity
;
float
std_weight_velocity
;
};
};
inline
TKalmanFilter
::
TKalmanFilter
(
void
)
:
cv
::
KalmanFilter
(
8
,
4
)
inline
TKalmanFilter
::
TKalmanFilter
(
void
)
:
cv
::
KalmanFilter
(
8
,
4
)
{
{
cv
::
KalmanFilter
::
transitionMatrix
=
cv
::
Mat
::
eye
(
8
,
8
,
CV_32F
);
cv
::
KalmanFilter
::
transitionMatrix
=
cv
::
Mat
::
eye
(
8
,
8
,
CV_32F
);
for
(
int
i
=
0
;
i
<
4
;
++
i
)
for
(
int
i
=
0
;
i
<
4
;
++
i
)
cv
::
KalmanFilter
::
transitionMatrix
.
at
<
float
>
(
i
,
i
+
4
)
=
1
;
cv
::
KalmanFilter
::
transitionMatrix
.
at
<
float
>
(
i
,
i
+
4
)
=
1
;
cv
::
KalmanFilter
::
measurementMatrix
=
cv
::
Mat
::
eye
(
4
,
8
,
CV_32F
);
cv
::
KalmanFilter
::
measurementMatrix
=
cv
::
Mat
::
eye
(
4
,
8
,
CV_32F
);
std_weight_position
=
1
/
20.
f
;
std_weight_position
=
1
/
20.
f
;
std_weight_velocity
=
1
/
160.
f
;
std_weight_velocity
=
1
/
160.
f
;
}
}
class
Trajectory
:
public
TKalmanFilter
class
Trajectory
:
public
TKalmanFilter
{
{
public:
public:
Trajectory
();
Trajectory
();
Trajectory
(
cv
::
Vec4f
&
ltrb
,
float
score
,
const
cv
::
Mat
&
embedding
);
Trajectory
(
const
cv
::
Vec4f
&
ltrb
,
float
score
,
const
cv
::
Mat
&
embedding
);
Trajectory
(
const
Trajectory
&
other
);
Trajectory
(
const
Trajectory
&
other
);
Trajectory
&
operator
=
(
const
Trajectory
&
rhs
);
Trajectory
&
operator
=
(
const
Trajectory
&
rhs
);
virtual
~
Trajectory
(
void
)
{};
virtual
~
Trajectory
(
void
)
{}
static
int
next_id
();
static
int
next_id
();
virtual
const
cv
::
Mat
&
predict
(
void
);
virtual
const
cv
::
Mat
&
predict
(
void
);
virtual
void
update
(
Trajectory
&
traj
,
int
timestamp
,
bool
update_embedding
=
true
);
virtual
void
update
(
Trajectory
*
traj
,
int
timestamp
,
bool
update_embedding
=
true
);
virtual
void
activate
(
int
timestamp
);
virtual
void
activate
(
int
timestamp
);
virtual
void
reactivate
(
Trajectory
&
traj
,
int
timestamp
,
bool
newid
=
false
);
virtual
void
reactivate
(
Trajectory
*
traj
,
int
timestamp
,
bool
newid
=
false
);
virtual
void
mark_lost
(
void
);
virtual
void
mark_lost
(
void
);
virtual
void
mark_removed
(
void
);
virtual
void
mark_removed
(
void
);
friend
TrajectoryPool
operator
+
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
TrajectoryPool
operator
+
(
const
TrajectoryPool
&
a
,
friend
TrajectoryPool
operator
+
(
const
TrajectoryPool
&
a
,
const
TrajectoryPtrPool
&
b
);
const
TrajectoryPool
&
b
);
friend
TrajectoryPool
&
operator
+=
(
TrajectoryPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPool
operator
+
(
const
TrajectoryPool
&
a
,
friend
TrajectoryPool
operator
-
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPool
&
operator
-=
(
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
TrajectoryPool
&
operator
+=
(
TrajectoryPool
&
a
,
// NOLINT
friend
TrajectoryPtrPool
operator
+
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPtrPool
operator
+
(
const
TrajectoryPtrPool
&
a
,
TrajectoryPool
&
b
);
friend
TrajectoryPool
operator
-
(
const
TrajectoryPool
&
a
,
friend
TrajectoryPtrPool
operator
-
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
const
TrajectoryPool
&
b
);
friend
TrajectoryPool
&
operator
-=
(
TrajectoryPool
&
a
,
// NOLINT
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPtrPool
operator
+
(
const
TrajectoryPtrPool
&
a
,
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPtrPool
operator
+
(
const
TrajectoryPtrPool
&
a
,
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
TrajectoryPool
*
b
);
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
TrajectoryPtrPool
operator
-
(
const
TrajectoryPtrPool
&
a
,
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
const
TrajectoryPtrPool
&
b
);
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
cv
::
Mat
embedding_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
cv
::
Mat
mahalanobis_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPool
&
a
,
const
TrajectoryPool
&
b
);
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPtrPool
&
b
);
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPtrPool
&
a
,
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
const
TrajectoryPtrPool
&
b
);
private:
friend
cv
::
Mat
iou_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
);
private:
void
update_embedding
(
const
cv
::
Mat
&
embedding
);
void
update_embedding
(
const
cv
::
Mat
&
embedding
);
public:
public:
TrajectoryState
state
;
TrajectoryState
state
;
cv
::
Vec4f
ltrb
;
cv
::
Vec4f
ltrb
;
cv
::
Mat
smooth_embedding
;
cv
::
Mat
smooth_embedding
;
...
@@ -110,7 +126,8 @@ public:
...
@@ -110,7 +126,8 @@ public:
int
timestamp
;
int
timestamp
;
int
starttime
;
int
starttime
;
float
score
;
float
score
;
private:
private:
static
int
count
;
static
int
count
;
cv
::
Vec4f
xyah
;
cv
::
Vec4f
xyah
;
cv
::
Mat
current_embedding
;
cv
::
Mat
current_embedding
;
...
@@ -118,8 +135,7 @@ private:
...
@@ -118,8 +135,7 @@ private:
int
length
;
int
length
;
};
};
inline
cv
::
Vec4f
ltrb2xyah
(
cv
::
Vec4f
&
ltrb
)
inline
cv
::
Vec4f
ltrb2xyah
(
const
cv
::
Vec4f
&
ltrb
)
{
{
cv
::
Vec4f
xyah
;
cv
::
Vec4f
xyah
;
xyah
[
0
]
=
(
ltrb
[
0
]
+
ltrb
[
2
])
*
0.5
f
;
xyah
[
0
]
=
(
ltrb
[
0
]
+
ltrb
[
2
])
*
0.5
f
;
xyah
[
1
]
=
(
ltrb
[
1
]
+
ltrb
[
3
])
*
0.5
f
;
xyah
[
1
]
=
(
ltrb
[
1
]
+
ltrb
[
3
])
*
0.5
f
;
...
@@ -128,25 +144,46 @@ inline cv::Vec4f ltrb2xyah(cv::Vec4f <rb)
...
@@ -128,25 +144,46 @@ inline cv::Vec4f ltrb2xyah(cv::Vec4f <rb)
return
xyah
;
return
xyah
;
}
}
inline
Trajectory
::
Trajectory
()
:
inline
Trajectory
::
Trajectory
()
state
(
New
),
ltrb
(
cv
::
Vec4f
()),
smooth_embedding
(
cv
::
Mat
()),
id
(
0
),
:
state
(
New
),
is_activated
(
false
),
timestamp
(
0
),
starttime
(
0
),
score
(
0
),
eta
(
0.9
),
length
(
0
)
ltrb
(
cv
::
Vec4f
()),
{
smooth_embedding
(
cv
::
Mat
()),
}
id
(
0
),
is_activated
(
false
),
inline
Trajectory
::
Trajectory
(
cv
::
Vec4f
&
ltrb_
,
float
score_
,
const
cv
::
Mat
&
embedding
)
:
timestamp
(
0
),
state
(
New
),
ltrb
(
ltrb_
),
smooth_embedding
(
cv
::
Mat
()),
id
(
0
),
starttime
(
0
),
is_activated
(
false
),
timestamp
(
0
),
starttime
(
0
),
score
(
score_
),
eta
(
0.9
),
length
(
0
)
score
(
0
),
{
eta
(
0.9
),
length
(
0
)
{}
inline
Trajectory
::
Trajectory
(
const
cv
::
Vec4f
&
ltrb_
,
float
score_
,
const
cv
::
Mat
&
embedding
)
:
state
(
New
),
ltrb
(
ltrb_
),
smooth_embedding
(
cv
::
Mat
()),
id
(
0
),
is_activated
(
false
),
timestamp
(
0
),
starttime
(
0
),
score
(
score_
),
eta
(
0.9
),
length
(
0
)
{
xyah
=
ltrb2xyah
(
ltrb
);
xyah
=
ltrb2xyah
(
ltrb
);
update_embedding
(
embedding
);
update_embedding
(
embedding
);
}
}
inline
Trajectory
::
Trajectory
(
const
Trajectory
&
other
)
:
inline
Trajectory
::
Trajectory
(
const
Trajectory
&
other
)
state
(
other
.
state
),
ltrb
(
other
.
ltrb
),
id
(
other
.
id
),
is_activated
(
other
.
is_activated
),
:
state
(
other
.
state
),
timestamp
(
other
.
timestamp
),
starttime
(
other
.
starttime
),
xyah
(
other
.
xyah
),
ltrb
(
other
.
ltrb
),
score
(
other
.
score
),
eta
(
other
.
eta
),
length
(
other
.
length
)
id
(
other
.
id
),
{
is_activated
(
other
.
is_activated
),
timestamp
(
other
.
timestamp
),
starttime
(
other
.
starttime
),
xyah
(
other
.
xyah
),
score
(
other
.
score
),
eta
(
other
.
eta
),
length
(
other
.
length
)
{
other
.
smooth_embedding
.
copyTo
(
smooth_embedding
);
other
.
smooth_embedding
.
copyTo
(
smooth_embedding
);
other
.
current_embedding
.
copyTo
(
current_embedding
);
other
.
current_embedding
.
copyTo
(
current_embedding
);
// copy state in KalmanFilter
// copy state in KalmanFilter
...
@@ -155,11 +192,9 @@ inline Trajectory::Trajectory(const Trajectory &other):
...
@@ -155,11 +192,9 @@ inline Trajectory::Trajectory(const Trajectory &other):
other
.
statePost
.
copyTo
(
cv
::
KalmanFilter
::
statePost
);
other
.
statePost
.
copyTo
(
cv
::
KalmanFilter
::
statePost
);
other
.
errorCovPre
.
copyTo
(
cv
::
KalmanFilter
::
errorCovPre
);
other
.
errorCovPre
.
copyTo
(
cv
::
KalmanFilter
::
errorCovPre
);
other
.
errorCovPost
.
copyTo
(
cv
::
KalmanFilter
::
errorCovPost
);
other
.
errorCovPost
.
copyTo
(
cv
::
KalmanFilter
::
errorCovPost
);
}
}
inline
Trajectory
&
Trajectory
::
operator
=
(
const
Trajectory
&
rhs
)
inline
Trajectory
&
Trajectory
::
operator
=
(
const
Trajectory
&
rhs
)
{
{
this
->
state
=
rhs
.
state
;
this
->
state
=
rhs
.
state
;
this
->
ltrb
=
rhs
.
ltrb
;
this
->
ltrb
=
rhs
.
ltrb
;
rhs
.
smooth_embedding
.
copyTo
(
this
->
smooth_embedding
);
rhs
.
smooth_embedding
.
copyTo
(
this
->
smooth_embedding
);
...
@@ -183,20 +218,13 @@ inline Trajectory &Trajectory::operator=(const Trajectory &rhs)
...
@@ -183,20 +218,13 @@ inline Trajectory &Trajectory::operator=(const Trajectory &rhs)
return
*
this
;
return
*
this
;
}
}
inline
int
Trajectory
::
next_id
()
inline
int
Trajectory
::
next_id
()
{
{
++
count
;
++
count
;
return
count
;
return
count
;
}
}
inline
void
Trajectory
::
mark_lost
(
void
)
inline
void
Trajectory
::
mark_lost
(
void
)
{
state
=
Lost
;
}
{
state
=
Lost
;
}
inline
void
Trajectory
::
mark_removed
(
void
)
inline
void
Trajectory
::
mark_removed
(
void
)
{
state
=
Removed
;
}
{
state
=
Removed
;
}
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/include/utils.h
浏览文件 @
531bca9d
...
@@ -14,27 +14,25 @@
...
@@ -14,27 +14,25 @@
#pragma once
#pragma once
#include <string>
#include <algorithm>
#include <vector>
#include <utility>
#include <ctime>
#include <ctime>
#include <numeric>
#include <numeric>
#include <algorithm>
#include <string>
#include <utility>
#include <vector>
#include "include/tracker.h"
#include "include/tracker.h"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
struct
Rect
struct
Rect
{
{
float
left
;
float
left
;
float
top
;
float
top
;
float
right
;
float
right
;
float
bottom
;
float
bottom
;
};
};
struct
MOTTrack
struct
MOTTrack
{
{
int
ids
;
int
ids
;
float
score
;
float
score
;
Rect
rects
;
Rect
rects
;
...
...
deploy/pptracking/src/jde_predictor.cc
浏览文件 @
531bca9d
...
@@ -13,12 +13,11 @@
...
@@ -13,12 +13,11 @@
// limitations under the License.
// limitations under the License.
#include <sstream>
#include <sstream>
// for setprecision
// for setprecision
#include <iomanip>
#include <chrono>
#include <chrono>
#include <iomanip>
#include "include/jde_predictor.h"
#include "include/jde_predictor.h"
using
namespace
paddle_infer
;
// NOLINT
using
namespace
paddle_infer
;
namespace
PaddleDetection
{
namespace
PaddleDetection
{
...
@@ -37,26 +36,24 @@ void JDEPredictor::LoadModel(const std::string& model_dir,
...
@@ -37,26 +36,24 @@ void JDEPredictor::LoadModel(const std::string& model_dir,
auto
precision
=
paddle_infer
::
Config
::
Precision
::
kFloat32
;
auto
precision
=
paddle_infer
::
Config
::
Precision
::
kFloat32
;
if
(
run_mode
==
"trt_fp32"
)
{
if
(
run_mode
==
"trt_fp32"
)
{
precision
=
paddle_infer
::
Config
::
Precision
::
kFloat32
;
precision
=
paddle_infer
::
Config
::
Precision
::
kFloat32
;
}
}
else
if
(
run_mode
==
"trt_fp16"
)
{
else
if
(
run_mode
==
"trt_fp16"
)
{
precision
=
paddle_infer
::
Config
::
Precision
::
kHalf
;
precision
=
paddle_infer
::
Config
::
Precision
::
kHalf
;
}
}
else
if
(
run_mode
==
"trt_int8"
)
{
else
if
(
run_mode
==
"trt_int8"
)
{
precision
=
paddle_infer
::
Config
::
Precision
::
kInt8
;
precision
=
paddle_infer
::
Config
::
Precision
::
kInt8
;
}
else
{
}
else
{
printf
(
"run_mode should be 'fluid', 'trt_fp32', 'trt_fp16' or 'trt_int8'"
);
printf
(
"run_mode should be 'fluid', 'trt_fp32', 'trt_fp16' or 'trt_int8'"
);
}
}
// set tensorrt
// set tensorrt
config
.
EnableTensorRtEngine
(
config
.
EnableTensorRtEngine
(
1
<<
30
,
1
<<
30
,
1
,
1
,
this
->
min_subgraph_size_
,
this
->
min_subgraph_size_
,
precision
,
precision
,
false
,
false
,
this
->
trt_calib_mode_
);
this
->
trt_calib_mode_
);
}
}
}
else
if
(
this
->
device_
==
"XPU"
){
}
else
if
(
this
->
device_
==
"XPU"
)
{
config
.
EnableXpu
(
10
*
1024
*
1024
);
config
.
EnableXpu
(
10
*
1024
*
1024
);
}
else
{
}
else
{
config
.
DisableGpu
();
config
.
DisableGpu
();
if
(
this
->
use_mkldnn_
)
{
if
(
this
->
use_mkldnn_
)
{
...
@@ -74,7 +71,9 @@ void JDEPredictor::LoadModel(const std::string& model_dir,
...
@@ -74,7 +71,9 @@ void JDEPredictor::LoadModel(const std::string& model_dir,
predictor_
=
std
::
move
(
CreatePredictor
(
config
));
predictor_
=
std
::
move
(
CreatePredictor
(
config
));
}
}
void
FilterDets
(
const
float
conf_thresh
,
const
cv
::
Mat
dets
,
std
::
vector
<
int
>*
index
)
{
void
FilterDets
(
const
float
conf_thresh
,
const
cv
::
Mat
dets
,
std
::
vector
<
int
>*
index
)
{
for
(
int
i
=
0
;
i
<
dets
.
rows
;
++
i
)
{
for
(
int
i
=
0
;
i
<
dets
.
rows
;
++
i
)
{
float
score
=
*
dets
.
ptr
<
float
>
(
i
,
4
);
float
score
=
*
dets
.
ptr
<
float
>
(
i
,
4
);
if
(
score
>
conf_thresh
)
{
if
(
score
>
conf_thresh
)
{
...
@@ -89,8 +88,8 @@ void JDEPredictor::Preprocess(const cv::Mat& ori_im) {
...
@@ -89,8 +88,8 @@ void JDEPredictor::Preprocess(const cv::Mat& ori_im) {
preprocessor_
.
Run
(
&
im
,
&
inputs_
);
preprocessor_
.
Run
(
&
im
,
&
inputs_
);
}
}
void
JDEPredictor
::
Postprocess
(
void
JDEPredictor
::
Postprocess
(
const
cv
::
Mat
dets
,
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
const
cv
::
Mat
emb
,
MOTResult
*
result
)
{
MOTResult
*
result
)
{
result
->
clear
();
result
->
clear
();
std
::
vector
<
Track
>
tracks
;
std
::
vector
<
Track
>
tracks
;
...
@@ -101,7 +100,7 @@ void JDEPredictor::Postprocess(
...
@@ -101,7 +100,7 @@ void JDEPredictor::Postprocess(
new_dets
.
push_back
(
dets
.
row
(
valid
[
i
]));
new_dets
.
push_back
(
dets
.
row
(
valid
[
i
]));
new_emb
.
push_back
(
emb
.
row
(
valid
[
i
]));
new_emb
.
push_back
(
emb
.
row
(
valid
[
i
]));
}
}
JDETracker
::
instance
()
->
update
(
new_dets
,
new_emb
,
tracks
);
JDETracker
::
instance
()
->
update
(
new_dets
,
new_emb
,
&
tracks
);
if
(
tracks
.
size
()
==
0
)
{
if
(
tracks
.
size
()
==
0
)
{
MOTTrack
mot_track
;
MOTTrack
mot_track
;
Rect
ret
=
{
*
dets
.
ptr
<
float
>
(
0
,
0
),
Rect
ret
=
{
*
dets
.
ptr
<
float
>
(
0
,
0
),
...
@@ -124,10 +123,8 @@ void JDEPredictor::Postprocess(
...
@@ -124,10 +123,8 @@ void JDEPredictor::Postprocess(
float
area
=
w
*
h
;
float
area
=
w
*
h
;
if
(
area
>
min_box_area_
&&
!
vertical
)
{
if
(
area
>
min_box_area_
&&
!
vertical
)
{
MOTTrack
mot_track
;
MOTTrack
mot_track
;
Rect
ret
=
{
titer
->
ltrb
[
0
],
Rect
ret
=
{
titer
->
ltrb
[
1
],
titer
->
ltrb
[
0
],
titer
->
ltrb
[
1
],
titer
->
ltrb
[
2
],
titer
->
ltrb
[
3
]};
titer
->
ltrb
[
2
],
titer
->
ltrb
[
3
]};
mot_track
.
rects
=
ret
;
mot_track
.
rects
=
ret
;
mot_track
.
score
=
titer
->
score
;
mot_track
.
score
=
titer
->
score
;
mot_track
.
ids
=
titer
->
id
;
mot_track
.
ids
=
titer
->
id
;
...
@@ -160,8 +157,8 @@ void JDEPredictor::Predict(const std::vector<cv::Mat> imgs,
...
@@ -160,8 +157,8 @@ void JDEPredictor::Predict(const std::vector<cv::Mat> imgs,
scale_factor_all
[
bs_idx
*
2
]
=
inputs_
.
scale_factor_
[
0
];
scale_factor_all
[
bs_idx
*
2
]
=
inputs_
.
scale_factor_
[
0
];
scale_factor_all
[
bs_idx
*
2
+
1
]
=
inputs_
.
scale_factor_
[
1
];
scale_factor_all
[
bs_idx
*
2
+
1
]
=
inputs_
.
scale_factor_
[
1
];
// TODO: reduce cost time
in_data_all
.
insert
(
in_data_all
.
insert
(
in_data_all
.
end
(),
inputs_
.
im_data_
.
begin
(),
inputs_
.
im_data_
.
end
());
in_data_all
.
end
(),
inputs_
.
im_data_
.
begin
(),
inputs_
.
im_data_
.
end
());
}
}
// Prepare input tensor
// Prepare input tensor
...
@@ -224,12 +221,14 @@ void JDEPredictor::Predict(const std::vector<cv::Mat> imgs,
...
@@ -224,12 +221,14 @@ void JDEPredictor::Predict(const std::vector<cv::Mat> imgs,
auto
postprocess_end
=
std
::
chrono
::
steady_clock
::
now
();
auto
postprocess_end
=
std
::
chrono
::
steady_clock
::
now
();
std
::
chrono
::
duration
<
float
>
preprocess_diff
=
preprocess_end
-
preprocess_start
;
std
::
chrono
::
duration
<
float
>
preprocess_diff
=
(
*
times
)[
0
]
+=
double
(
preprocess_diff
.
count
()
*
1000
);
preprocess_end
-
preprocess_start
;
(
*
times
)[
0
]
+=
static_cast
<
double
>
(
preprocess_diff
.
count
()
*
1000
);
std
::
chrono
::
duration
<
float
>
inference_diff
=
inference_end
-
inference_start
;
std
::
chrono
::
duration
<
float
>
inference_diff
=
inference_end
-
inference_start
;
(
*
times
)[
1
]
+=
double
(
inference_diff
.
count
()
*
1000
);
(
*
times
)[
1
]
+=
static_cast
<
double
>
(
inference_diff
.
count
()
*
1000
);
std
::
chrono
::
duration
<
float
>
postprocess_diff
=
postprocess_end
-
postprocess_start
;
std
::
chrono
::
duration
<
float
>
postprocess_diff
=
(
*
times
)[
2
]
+=
double
(
postprocess_diff
.
count
()
*
1000
);
postprocess_end
-
postprocess_start
;
(
*
times
)[
2
]
+=
static_cast
<
double
>
(
postprocess_diff
.
count
()
*
1000
);
}
}
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/src/lapjv.cpp
浏览文件 @
531bca9d
...
@@ -27,9 +27,8 @@ namespace PaddleDetection {
...
@@ -27,9 +27,8 @@ namespace PaddleDetection {
/** Column-reduction and reduction transfer for a dense cost matrix.
/** Column-reduction and reduction transfer for a dense cost matrix.
*/
*/
int
_ccrrt_dense
(
const
int
n
,
float
*
cost
[],
int
_ccrrt_dense
(
int
*
free_rows
,
int
*
x
,
int
*
y
,
float
*
v
)
const
int
n
,
float
*
cost
[],
int
*
free_rows
,
int
*
x
,
int
*
y
,
float
*
v
)
{
{
int
n_free_rows
;
int
n_free_rows
;
bool
*
unique
;
bool
*
unique
;
...
@@ -70,7 +69,7 @@ int _ccrrt_dense(const int n, float *cost[],
...
@@ -70,7 +69,7 @@ int _ccrrt_dense(const int n, float *cost[],
const
int
j
=
x
[
i
];
const
int
j
=
x
[
i
];
float
min
=
LARGE
;
float
min
=
LARGE
;
for
(
int
j2
=
0
;
j2
<
n
;
j2
++
)
{
for
(
int
j2
=
0
;
j2
<
n
;
j2
++
)
{
if
(
j2
==
(
int
)
j
)
{
if
(
j2
==
static_cast
<
int
>
(
j
)
)
{
continue
;
continue
;
}
}
const
float
c
=
cost
[
i
][
j2
]
-
v
[
j2
];
const
float
c
=
cost
[
i
][
j2
]
-
v
[
j2
];
...
@@ -85,14 +84,15 @@ int _ccrrt_dense(const int n, float *cost[],
...
@@ -85,14 +84,15 @@ int _ccrrt_dense(const int n, float *cost[],
return
n_free_rows
;
return
n_free_rows
;
}
}
/** Augmenting row reduction for a dense cost matrix.
/** Augmenting row reduction for a dense cost matrix.
*/
*/
int
_carr_dense
(
int
_carr_dense
(
const
int
n
,
const
int
n
,
float
*
cost
[],
float
*
cost
[],
const
int
n_free_rows
,
const
int
n_free_rows
,
int
*
free_rows
,
int
*
x
,
int
*
y
,
float
*
v
)
int
*
free_rows
,
{
int
*
x
,
int
*
y
,
float
*
v
)
{
int
current
=
0
;
int
current
=
0
;
int
new_free_rows
=
0
;
int
new_free_rows
=
0
;
int
rr_cnt
=
0
;
int
rr_cnt
=
0
;
...
@@ -150,11 +150,9 @@ int _carr_dense(
...
@@ -150,11 +150,9 @@ int _carr_dense(
return
new_free_rows
;
return
new_free_rows
;
}
}
/** Find columns with minimum d[j] and put them on the SCAN list.
/** Find columns with minimum d[j] and put them on the SCAN list.
*/
*/
int
_find_dense
(
const
int
n
,
int
lo
,
float
*
d
,
int
*
cols
,
int
*
y
)
int
_find_dense
(
const
int
n
,
int
lo
,
float
*
d
,
int
*
cols
,
int
*
y
)
{
{
int
hi
=
lo
+
1
;
int
hi
=
lo
+
1
;
float
mind
=
d
[
cols
[
lo
]];
float
mind
=
d
[
cols
[
lo
]];
for
(
int
k
=
hi
;
k
<
n
;
k
++
)
{
for
(
int
k
=
hi
;
k
<
n
;
k
++
)
{
...
@@ -171,14 +169,17 @@ int _find_dense(const int n, int lo, float *d, int *cols, int *y)
...
@@ -171,14 +169,17 @@ int _find_dense(const int n, int lo, float *d, int *cols, int *y)
return
hi
;
return
hi
;
}
}
// Scan all columns in TODO starting from arbitrary column in SCAN
// Scan all columns in TODO starting from arbitrary column in SCAN
// and try to decrease d of the TODO columns using the SCAN column.
// and try to decrease d of the TODO columns using the SCAN column.
int
_scan_dense
(
const
int
n
,
float
*
cost
[],
int
_scan_dense
(
const
int
n
,
int
*
plo
,
int
*
phi
,
float
*
cost
[],
float
*
d
,
int
*
cols
,
int
*
pred
,
int
*
plo
,
int
*
y
,
float
*
v
)
int
*
phi
,
{
float
*
d
,
int
*
cols
,
int
*
pred
,
int
*
y
,
float
*
v
)
{
int
lo
=
*
plo
;
int
lo
=
*
plo
;
int
hi
=
*
phi
;
int
hi
=
*
phi
;
float
h
,
cred_ij
;
float
h
,
cred_ij
;
...
@@ -210,19 +211,19 @@ int _scan_dense(const int n, float *cost[],
...
@@ -210,19 +211,19 @@ int _scan_dense(const int n, float *cost[],
return
-
1
;
return
-
1
;
}
}
/** Single iteration of modified Dijkstra shortest path algorithm as explained
/** Single iteration of modified Dijkstra shortest path algorithm as explained
in the JV paper.
*
in the JV paper.
*
*
* This is a dense matrix version.
* This is a dense matrix version.
*
*
* \return The closest free column index.
* \return The closest free column index.
*/
*/
int
find_path_dense
(
int
find_path_dense
(
const
int
n
,
const
int
n
,
float
*
cost
[],
float
*
cost
[],
const
int
start_i
,
const
int
start_i
,
int
*
y
,
float
*
v
,
int
*
y
,
int
*
pred
)
float
*
v
,
{
int
*
pred
)
{
int
lo
=
0
,
hi
=
0
;
int
lo
=
0
,
hi
=
0
;
int
final_j
=
-
1
;
int
final_j
=
-
1
;
int
n_ready
=
0
;
int
n_ready
=
0
;
...
@@ -250,8 +251,7 @@ int find_path_dense(
...
@@ -250,8 +251,7 @@ int find_path_dense(
}
}
}
}
if
(
final_j
==
-
1
)
{
if
(
final_j
==
-
1
)
{
final_j
=
_scan_dense
(
final_j
=
_scan_dense
(
n
,
cost
,
&
lo
,
&
hi
,
d
,
cols
,
pred
,
y
,
v
);
n
,
cost
,
&
lo
,
&
hi
,
d
,
cols
,
pred
,
y
,
v
);
}
}
}
}
...
@@ -269,14 +269,15 @@ int find_path_dense(
...
@@ -269,14 +269,15 @@ int find_path_dense(
return
final_j
;
return
final_j
;
}
}
/** Augment for a dense cost matrix.
/** Augment for a dense cost matrix.
*/
*/
int
_ca_dense
(
int
_ca_dense
(
const
int
n
,
const
int
n
,
float
*
cost
[],
float
*
cost
[],
const
int
n_free_rows
,
const
int
n_free_rows
,
int
*
free_rows
,
int
*
x
,
int
*
y
,
float
*
v
)
int
*
free_rows
,
{
int
*
x
,
int
*
y
,
float
*
v
)
{
int
*
pred
;
int
*
pred
;
NEW
(
pred
,
int
,
n
);
NEW
(
pred
,
int
,
n
);
...
@@ -297,19 +298,22 @@ int _ca_dense(
...
@@ -297,19 +298,22 @@ int _ca_dense(
return
0
;
return
0
;
}
}
/** Solve dense sparse LAP.
/** Solve dense sparse LAP.
*/
*/
int
lapjv_internal
(
int
lapjv_internal
(
const
cv
::
Mat
&
cost
,
const
cv
::
Mat
&
cost
,
const
bool
extend_cost
,
const
float
cost_limit
,
const
bool
extend_cost
,
int
*
x
,
int
*
y
)
{
const
float
cost_limit
,
int
*
x
,
int
*
y
)
{
int
n_rows
=
cost
.
rows
;
int
n_rows
=
cost
.
rows
;
int
n_cols
=
cost
.
cols
;
int
n_cols
=
cost
.
cols
;
int
n
;
int
n
;
if
(
n_rows
==
n_cols
)
{
if
(
n_rows
==
n_cols
)
{
n
=
n_rows
;
n
=
n_rows
;
}
else
if
(
!
extend_cost
)
{
}
else
if
(
!
extend_cost
)
{
throw
std
::
invalid_argument
(
"Square cost array expected. If cost is intentionally non-square, pass extend_cost=True."
);
throw
std
::
invalid_argument
(
"Square cost array expected. If cost is intentionally non-square, pass "
"extend_cost=True."
);
}
}
// Get extend cost
// Get extend cost
...
@@ -323,7 +327,7 @@ int lapjv_internal(
...
@@ -323,7 +327,7 @@ int lapjv_internal(
}
else
{
}
else
{
double
max_v
;
double
max_v
;
minMaxLoc
(
cost
,
nullptr
,
&
max_v
);
minMaxLoc
(
cost
,
nullptr
,
&
max_v
);
expand_value
=
(
float
)
max_v
+
1
;
expand_value
=
static_cast
<
float
>
(
max_v
)
+
1.
;
}
}
for
(
int
i
=
0
;
i
<
n
;
++
i
)
{
for
(
int
i
=
0
;
i
<
n
;
++
i
)
{
...
@@ -376,7 +380,7 @@ int lapjv_internal(
...
@@ -376,7 +380,7 @@ int lapjv_internal(
}
}
FREE
(
cost_ptr
);
FREE
(
cost_ptr
);
if
(
ret
!=
0
)
{
if
(
ret
!=
0
)
{
if
(
ret
==
-
1
)
{
if
(
ret
==
-
1
)
{
throw
"Out of memory."
;
throw
"Out of memory."
;
}
}
throw
"Unknown error (lapjv_internal)"
;
throw
"Unknown error (lapjv_internal)"
;
...
...
deploy/pptracking/src/main.cc
浏览文件 @
531bca9d
...
@@ -14,44 +14,55 @@
...
@@ -14,44 +14,55 @@
#include <glog/logging.h>
#include <glog/logging.h>
#include <math.h>
#include <sys/types.h>
#include <algorithm>
#include <iostream>
#include <iostream>
#include <numeric>
#include <string>
#include <string>
#include <vector>
#include <vector>
#include <numeric>
#include <sys/types.h>
#include <sys/stat.h>
#include <math.h>
#include <algorithm>
#ifdef _WIN32
#ifdef _WIN32
#include <direct.h>
#include <direct.h>
#include <io.h>
#include <io.h>
#el
if LINUX
#el
se
#include <stdarg.h>
#include <stdarg.h>
#include <sys/stat.h>
#include <sys/stat.h>
#endif
#endif
#include "include/pipeline.h"
#include <gflags/gflags.h>
#include <gflags/gflags.h>
#include "include/pipeline.h"
DEFINE_string
(
video_file
,
""
,
"Path of input video."
);
DEFINE_string
(
video_file
,
""
,
"Path of input video."
);
DEFINE_string
(
video_other_file
,
""
,
"Path of other input video used for MTMCT."
);
DEFINE_string
(
video_other_file
,
DEFINE_string
(
device
,
"CPU"
,
"Choose the device you want to run, it can be: CPU/GPU/XPU, default is CPU."
);
""
,
"Path of other input video used for MTMCT."
);
DEFINE_string
(
device
,
"CPU"
,
"Choose the device you want to run, it can be: CPU/GPU/XPU, "
"default is CPU."
);
DEFINE_double
(
threshold
,
0.5
,
"Threshold of score."
);
DEFINE_double
(
threshold
,
0.5
,
"Threshold of score."
);
DEFINE_string
(
output_dir
,
"output"
,
"Directory of output visualization files."
);
DEFINE_string
(
output_dir
,
"output"
,
"Directory of output visualization files."
);
DEFINE_string
(
run_mode
,
"fluid"
,
"Mode of running(fluid/trt_fp32/trt_fp16/trt_int8)"
);
DEFINE_string
(
run_mode
,
"fluid"
,
"Mode of running(fluid/trt_fp32/trt_fp16/trt_int8)"
);
DEFINE_int32
(
gpu_id
,
0
,
"Device id of GPU to execute"
);
DEFINE_int32
(
gpu_id
,
0
,
"Device id of GPU to execute"
);
DEFINE_bool
(
use_mkldnn
,
false
,
"Whether use mkldnn with CPU"
);
DEFINE_bool
(
use_mkldnn
,
false
,
"Whether use mkldnn with CPU"
);
DEFINE_int32
(
cpu_threads
,
1
,
"Num of threads with CPU"
);
DEFINE_int32
(
cpu_threads
,
1
,
"Num of threads with CPU"
);
DEFINE_bool
(
trt_calib_mode
,
false
,
"If the model is produced by TRT offline quantitative calibration, trt_calib_mode need to set True"
);
DEFINE_bool
(
trt_calib_mode
,
false
,
"If the model is produced by TRT offline quantitative calibration, "
"trt_calib_mode need to set True"
);
DEFINE_bool
(
tiny_obj
,
false
,
"Whether tracking tiny object"
);
DEFINE_bool
(
tiny_obj
,
false
,
"Whether tracking tiny object"
);
DEFINE_bool
(
count
,
false
,
"Whether counting after tracking"
);
DEFINE_bool
(
count
,
false
,
"Whether counting after tracking"
);
DEFINE_bool
(
save_result
,
false
,
"Whether saving result after tracking"
);
DEFINE_bool
(
save_result
,
false
,
"Whether saving result after tracking"
);
DEFINE_string
(
scene
,
""
,
"scene of tracking system, it can be : pedestrian/vehicle/multiclass"
);
DEFINE_string
(
scene
,
""
,
"scene of tracking system, it can be : pedestrian/vehicle/multiclass"
);
DEFINE_bool
(
is_mtmct
,
false
,
"Whether use multi-target multi-camera tracking"
);
DEFINE_bool
(
is_mtmct
,
false
,
"Whether use multi-target multi-camera tracking"
);
static
std
::
string
DirName
(
const
std
::
string
&
filepath
)
{
static
std
::
string
DirName
(
const
std
::
string
&
filepath
)
{
auto
pos
=
filepath
.
rfind
(
OS_PATH_SEP
);
auto
pos
=
filepath
.
rfind
(
OS_PATH_SEP
);
if
(
pos
==
std
::
string
::
npos
)
{
if
(
pos
==
std
::
string
::
npos
)
{
return
""
;
return
""
;
...
@@ -59,7 +70,7 @@ static std::string DirName(const std::string &filepath) {
...
@@ -59,7 +70,7 @@ static std::string DirName(const std::string &filepath) {
return
filepath
.
substr
(
0
,
pos
);
return
filepath
.
substr
(
0
,
pos
);
}
}
static
bool
PathExists
(
const
std
::
string
&
path
){
static
bool
PathExists
(
const
std
::
string
&
path
)
{
#ifdef _WIN32
#ifdef _WIN32
struct
_stat
buffer
;
struct
_stat
buffer
;
return
(
_stat
(
path
.
c_str
(),
&
buffer
)
==
0
);
return
(
_stat
(
path
.
c_str
(),
&
buffer
)
==
0
);
...
@@ -101,13 +112,18 @@ int main(int argc, char** argv) {
...
@@ -101,13 +112,18 @@ int main(int argc, char** argv) {
<<
"-scene=pedestrian/vehicle/multiclass"
<<
std
::
endl
;
<<
"-scene=pedestrian/vehicle/multiclass"
<<
std
::
endl
;
return
-
1
;
return
-
1
;
}
}
if
(
!
(
FLAGS_run_mode
==
"fluid"
||
FLAGS_run_mode
==
"trt_fp32"
if
(
!
(
FLAGS_run_mode
==
"fluid"
||
FLAGS_run_mode
==
"trt_fp32"
||
||
FLAGS_run_mode
==
"trt_fp16"
||
FLAGS_run_mode
==
"trt_int8"
))
{
FLAGS_run_mode
==
"trt_fp16"
||
FLAGS_run_mode
==
"trt_int8"
))
{
std
::
cout
<<
"run_mode should be 'fluid', 'trt_fp32', 'trt_fp16' or 'trt_int8'."
;
std
::
cout
<<
"run_mode should be 'fluid', 'trt_fp32', 'trt_fp16' or 'trt_int8'."
;
return
-
1
;
return
-
1
;
}
}
transform
(
FLAGS_device
.
begin
(),
FLAGS_device
.
end
(),
FLAGS_device
.
begin
(),
::
toupper
);
transform
(
FLAGS_device
.
begin
(),
if
(
!
(
FLAGS_device
==
"CPU"
||
FLAGS_device
==
"GPU"
||
FLAGS_device
==
"XPU"
))
{
FLAGS_device
.
end
(),
FLAGS_device
.
begin
(),
::
toupper
);
if
(
!
(
FLAGS_device
==
"CPU"
||
FLAGS_device
==
"GPU"
||
FLAGS_device
==
"XPU"
))
{
std
::
cout
<<
"device should be 'CPU', 'GPU' or 'XPU'."
;
std
::
cout
<<
"device should be 'CPU', 'GPU' or 'XPU'."
;
return
-
1
;
return
-
1
;
}
}
...
@@ -116,11 +132,18 @@ int main(int argc, char** argv) {
...
@@ -116,11 +132,18 @@ int main(int argc, char** argv) {
MkDirs
(
FLAGS_output_dir
);
MkDirs
(
FLAGS_output_dir
);
}
}
PaddleDetection
::
Pipeline
pipeline
(
PaddleDetection
::
Pipeline
pipeline
(
FLAGS_device
,
FLAGS_device
,
FLAGS_threshold
,
FLAGS_threshold
,
FLAGS_output_dir
,
FLAGS_run_mode
,
FLAGS_gpu_id
,
FLAGS_output_dir
,
FLAGS_use_mkldnn
,
FLAGS_cpu_threads
,
FLAGS_trt_calib_mode
,
FLAGS_run_mode
,
FLAGS_count
,
FLAGS_save_result
,
FLAGS_scene
,
FLAGS_tiny_obj
,
FLAGS_gpu_id
,
FLAGS_use_mkldnn
,
FLAGS_cpu_threads
,
FLAGS_trt_calib_mode
,
FLAGS_count
,
FLAGS_save_result
,
FLAGS_scene
,
FLAGS_tiny_obj
,
FLAGS_is_mtmct
);
FLAGS_is_mtmct
);
pipeline
.
SetInput
(
FLAGS_video_file
);
pipeline
.
SetInput
(
FLAGS_video_file
);
...
...
deploy/pptracking/src/pipeline.cc
浏览文件 @
531bca9d
...
@@ -14,18 +14,17 @@
...
@@ -14,18 +14,17 @@
#include <sstream>
#include <sstream>
// for setprecision
// for setprecision
#include <chrono>
#include <iomanip>
#include <iostream>
#include <iostream>
#include <string>
#include <string>
#include <iomanip>
#include <chrono>
#include "include/pipeline.h"
#include "include/pipeline.h"
#include "include/postprocess.h"
#include "include/postprocess.h"
#include "include/predictor.h"
#include "include/predictor.h"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
void
Pipeline
::
SetInput
(
const
std
::
string
&
input_video
)
{
void
Pipeline
::
SetInput
(
std
::
string
&
input_video
)
{
input_
.
push_back
(
input_video
);
input_
.
push_back
(
input_video
);
}
}
...
@@ -76,16 +75,29 @@ void Pipeline::InitPredictor() {
...
@@ -76,16 +75,29 @@ void Pipeline::InitPredictor() {
}
}
if
(
!
track_model_dir_
.
empty
())
{
if
(
!
track_model_dir_
.
empty
())
{
jde_sct_
=
std
::
make_shared
<
PaddleDetection
::
JDEPredictor
>
(
device_
,
track_model_dir_
,
threshold_
,
run_mode_
,
gpu_id_
,
use_mkldnn_
,
cpu_threads_
,
trt_calib_mode_
);
jde_sct_
=
std
::
make_shared
<
PaddleDetection
::
JDEPredictor
>
(
device_
,
track_model_dir_
,
threshold_
,
run_mode_
,
gpu_id_
,
use_mkldnn_
,
cpu_threads_
,
trt_calib_mode_
);
}
}
if
(
!
det_model_dir_
.
empty
())
{
if
(
!
det_model_dir_
.
empty
())
{
sde_sct_
=
std
::
make_shared
<
PaddleDetection
::
SDEPredictor
>
(
device_
,
det_model_dir_
,
reid_model_dir_
,
threshold_
,
run_mode_
,
gpu_id_
,
use_mkldnn_
,
cpu_threads_
,
trt_calib_mode_
);
sde_sct_
=
std
::
make_shared
<
PaddleDetection
::
SDEPredictor
>
(
device_
,
det_model_dir_
,
reid_model_dir_
,
threshold_
,
run_mode_
,
gpu_id_
,
use_mkldnn_
,
cpu_threads_
,
trt_calib_mode_
);
}
}
}
}
void
Pipeline
::
Run
()
{
void
Pipeline
::
Run
()
{
if
(
track_model_dir_
.
empty
()
&&
det_model_dir_
.
empty
())
{
if
(
track_model_dir_
.
empty
()
&&
det_model_dir_
.
empty
())
{
std
::
cout
<<
"Pipeline must use SelectModel before Run"
;
std
::
cout
<<
"Pipeline must use SelectModel before Run"
;
return
;
return
;
...
@@ -98,21 +110,21 @@ void Pipeline::Run() {
...
@@ -98,21 +110,21 @@ void Pipeline::Run() {
if
(
!
track_model_dir_
.
empty
())
{
if
(
!
track_model_dir_
.
empty
())
{
// single camera
// single camera
if
(
input_
.
size
()
>
1
)
{
if
(
input_
.
size
()
>
1
)
{
throw
"Single camera tracking except single video, but received %d"
,
input_
.
size
();
throw
"Single camera tracking except single video, but received %d"
,
input_
.
size
();
}
}
PredictMOT
(
input_
[
0
]);
PredictMOT
(
input_
[
0
]);
}
else
{
}
else
{
// multi cameras
// multi cameras
if
(
input_
.
size
()
!=
2
)
{
if
(
input_
.
size
()
!=
2
)
{
throw
"Multi camera tracking except two videos, but received %d"
,
input_
.
size
();
throw
"Multi camera tracking except two videos, but received %d"
,
input_
.
size
();
}
}
PredictMTMCT
(
input_
);
PredictMTMCT
(
input_
);
}
}
}
}
void
Pipeline
::
PredictMOT
(
const
std
::
string
&
video_path
)
{
void
Pipeline
::
PredictMOT
(
const
std
::
string
&
video_path
)
{
// Open video
// Open video
cv
::
VideoCapture
capture
;
cv
::
VideoCapture
capture
;
capture
.
open
(
video_path
.
c_str
());
capture
.
open
(
video_path
.
c_str
());
...
@@ -134,9 +146,9 @@ void Pipeline::PredictMOT(const std::string& video_path) {
...
@@ -134,9 +146,9 @@ void Pipeline::PredictMOT(const std::string& video_path) {
// Create VideoWriter for output
// Create VideoWriter for output
cv
::
VideoWriter
video_out
;
cv
::
VideoWriter
video_out
;
std
::
string
video_out_path
=
output_dir_
+
OS_PATH_SEP
+
"mot_output.mp4"
;
std
::
string
video_out_path
=
output_dir_
+
OS_PATH_SEP
+
"mot_output.mp4"
;
int
fcc
=
cv
::
VideoWriter
::
fourcc
(
'm'
,
'p'
,
'4'
,
'v'
);
int
fcc
=
cv
::
VideoWriter
::
fourcc
(
'm'
,
'p'
,
'4'
,
'v'
);
video_out
.
open
(
video_out_path
.
c_str
(),
video_out
.
open
(
video_out_path
.
c_str
(),
fcc
,
//
0x00000021,
fcc
,
//
0x00000021,
video_fps
,
video_fps
,
cv
::
Size
(
video_width
,
video_height
),
cv
::
Size
(
video_width
,
video_height
),
true
);
true
);
...
@@ -172,18 +184,19 @@ void Pipeline::PredictMOT(const std::string& video_path) {
...
@@ -172,18 +184,19 @@ void Pipeline::PredictMOT(const std::string& video_path) {
times
=
total_time
/
frame_id
;
times
=
total_time
/
frame_id
;
LOG
(
INFO
)
<<
"frame_id: "
<<
frame_id
LOG
(
INFO
)
<<
"frame_id: "
<<
frame_id
<<
" predict time(s): "
<<
total_time
/
1000
;
<<
" predict time(s): "
<<
total_time
/
1000
;
cv
::
Mat
out_img
=
PaddleDetection
::
VisualizeTrackResult
(
cv
::
Mat
out_img
=
PaddleDetection
::
VisualizeTrackResult
(
frame
,
result
,
1000.
/
times
,
frame_id
);
frame
,
result
,
1000.
/
times
,
frame_id
);
if
(
count_
)
{
if
(
count_
)
{
// Count total number
// Count total number
// Count in & out number
// Count in & out number
PaddleDetection
::
FlowStatistic
(
result
,
frame_id
,
&
count_list
,
&
in_count_list
,
&
out_count_list
);
PaddleDetection
::
FlowStatistic
(
result
,
frame_id
,
&
count_list
,
&
in_count_list
,
&
out_count_list
);
}
}
if
(
save_result_
)
{
if
(
save_result_
)
{
PaddleDetection
::
SaveMOTResult
(
result
,
frame_id
,
records
);
PaddleDetection
::
SaveMOTResult
(
result
,
frame_id
,
&
records
);
}
}
video_out
.
write
(
out_img
);
video_out
.
write
(
out_img
);
}
}
...
@@ -194,10 +207,11 @@ void Pipeline::PredictMOT(const std::string& video_path) {
...
@@ -194,10 +207,11 @@ void Pipeline::PredictMOT(const std::string& video_path) {
LOG
(
INFO
)
<<
"Total frame: "
<<
frame_id
;
LOG
(
INFO
)
<<
"Total frame: "
<<
frame_id
;
LOG
(
INFO
)
<<
"Visualized output saved as "
<<
video_out_path
.
c_str
();
LOG
(
INFO
)
<<
"Visualized output saved as "
<<
video_out_path
.
c_str
();
if
(
save_result_
)
{
if
(
save_result_
)
{
FILE
*
fp
;
FILE
*
fp
;
std
::
string
result_output_path
=
output_dir_
+
OS_PATH_SEP
+
"mot_output.txt"
;
std
::
string
result_output_path
=
if
((
fp
=
fopen
(
result_output_path
.
c_str
(),
"w+"
))
==
NULL
)
{
output_dir_
+
OS_PATH_SEP
+
"mot_output.txt"
;
if
((
fp
=
fopen
(
result_output_path
.
c_str
(),
"w+"
))
==
NULL
)
{
printf
(
"Open %s error.
\n
"
,
result_output_path
.
c_str
());
printf
(
"Open %s error.
\n
"
,
result_output_path
.
c_str
());
return
;
return
;
}
}
...
@@ -214,7 +228,13 @@ void Pipeline::PredictMTMCT(const std::vector<std::string> video_path) {
...
@@ -214,7 +228,13 @@ void Pipeline::PredictMTMCT(const std::vector<std::string> video_path) {
throw
"Not Implement!"
;
throw
"Not Implement!"
;
}
}
void
Pipeline
::
RunMOTStream
(
const
cv
::
Mat
img
,
const
int
frame_id
,
cv
::
Mat
&
out_img
,
std
::
vector
<
std
::
string
>&
records
,
std
::
vector
<
int
>&
count_list
,
std
::
vector
<
int
>&
in_count_list
,
std
::
vector
<
int
>&
out_count_list
)
{
void
Pipeline
::
RunMOTStream
(
const
cv
::
Mat
img
,
const
int
frame_id
,
cv
::
Mat
out_img
,
std
::
vector
<
std
::
string
>*
records
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
out_count_list
)
{
PaddleDetection
::
MOTResult
result
;
PaddleDetection
::
MOTResult
result
;
std
::
vector
<
double
>
det_times
(
3
);
std
::
vector
<
double
>
det_times
(
3
);
double
times
;
double
times
;
...
@@ -228,15 +248,16 @@ void Pipeline::RunMOTStream(const cv::Mat img, const int frame_id, cv::Mat& out_
...
@@ -228,15 +248,16 @@ void Pipeline::RunMOTStream(const cv::Mat img, const int frame_id, cv::Mat& out_
times
=
total_time
/
frame_id
;
times
=
total_time
/
frame_id
;
LOG
(
INFO
)
<<
"frame_id: "
<<
frame_id
LOG
(
INFO
)
<<
"frame_id: "
<<
frame_id
<<
" predict time(s): "
<<
total_time
/
1000
;
<<
" predict time(s): "
<<
total_time
/
1000
;
out_img
=
PaddleDetection
::
VisualizeTrackResult
(
out_img
=
PaddleDetection
::
VisualizeTrackResult
(
img
,
result
,
1000.
/
times
,
frame_id
);
img
,
result
,
1000.
/
times
,
frame_id
);
if
(
count_
)
{
if
(
count_
)
{
// Count total number
// Count total number
// Count in & out number
// Count in & out number
PaddleDetection
::
FlowStatistic
(
result
,
frame_id
,
&
count_list
,
&
in_count_list
,
&
out_count_list
);
PaddleDetection
::
FlowStatistic
(
result
,
frame_id
,
count_list
,
in_count_list
,
out_count_list
);
}
}
PrintBenchmarkLog
(
det_times
,
frame_id
);
PrintBenchmarkLog
(
det_times
,
frame_id
);
...
@@ -245,23 +266,30 @@ void Pipeline::RunMOTStream(const cv::Mat img, const int frame_id, cv::Mat& out_
...
@@ -245,23 +266,30 @@ void Pipeline::RunMOTStream(const cv::Mat img, const int frame_id, cv::Mat& out_
}
}
}
}
void
Pipeline
::
RunMTMCTStream
(
const
std
::
vector
<
cv
::
Mat
>
imgs
,
std
::
vector
<
std
::
string
>&
records
)
{
void
Pipeline
::
RunMTMCTStream
(
const
std
::
vector
<
cv
::
Mat
>
imgs
,
std
::
vector
<
std
::
string
>*
records
)
{
throw
"Not Implement!"
;
throw
"Not Implement!"
;
}
}
void
Pipeline
::
PrintBenchmarkLog
(
std
::
vector
<
double
>
det_time
,
int
img_num
){
void
Pipeline
::
PrintBenchmarkLog
(
const
std
::
vector
<
double
>
det_time
,
const
int
img_num
)
{
LOG
(
INFO
)
<<
"----------------------- Config info -----------------------"
;
LOG
(
INFO
)
<<
"----------------------- Config info -----------------------"
;
LOG
(
INFO
)
<<
"runtime_device: "
<<
device_
;
LOG
(
INFO
)
<<
"runtime_device: "
<<
device_
;
LOG
(
INFO
)
<<
"ir_optim: "
<<
"True"
;
LOG
(
INFO
)
<<
"ir_optim: "
LOG
(
INFO
)
<<
"enable_memory_optim: "
<<
"True"
;
<<
"True"
;
LOG
(
INFO
)
<<
"enable_memory_optim: "
<<
"True"
;
int
has_trt
=
run_mode_
.
find
(
"trt"
);
int
has_trt
=
run_mode_
.
find
(
"trt"
);
if
(
has_trt
>=
0
)
{
if
(
has_trt
>=
0
)
{
LOG
(
INFO
)
<<
"enable_tensorrt: "
<<
"True"
;
LOG
(
INFO
)
<<
"enable_tensorrt: "
<<
"True"
;
std
::
string
precision
=
run_mode_
.
substr
(
4
,
8
);
std
::
string
precision
=
run_mode_
.
substr
(
4
,
8
);
LOG
(
INFO
)
<<
"precision: "
<<
precision
;
LOG
(
INFO
)
<<
"precision: "
<<
precision
;
}
else
{
}
else
{
LOG
(
INFO
)
<<
"enable_tensorrt: "
<<
"False"
;
LOG
(
INFO
)
<<
"enable_tensorrt: "
LOG
(
INFO
)
<<
"precision: "
<<
"fp32"
;
<<
"False"
;
LOG
(
INFO
)
<<
"precision: "
<<
"fp32"
;
}
}
LOG
(
INFO
)
<<
"enable_mkldnn: "
<<
(
use_mkldnn_
?
"True"
:
"False"
);
LOG
(
INFO
)
<<
"enable_mkldnn: "
<<
(
use_mkldnn_
?
"True"
:
"False"
);
LOG
(
INFO
)
<<
"cpu_math_library_num_threads: "
<<
cpu_threads_
;
LOG
(
INFO
)
<<
"cpu_math_library_num_threads: "
<<
cpu_threads_
;
...
@@ -269,12 +297,10 @@ void Pipeline::PrintBenchmarkLog(std::vector<double> det_time, int img_num){
...
@@ -269,12 +297,10 @@ void Pipeline::PrintBenchmarkLog(std::vector<double> det_time, int img_num){
LOG
(
INFO
)
<<
"Total number of predicted data: "
<<
img_num
LOG
(
INFO
)
<<
"Total number of predicted data: "
<<
img_num
<<
" and total time spent(s): "
<<
" and total time spent(s): "
<<
std
::
accumulate
(
det_time
.
begin
(),
det_time
.
end
(),
0.
)
/
1000
;
<<
std
::
accumulate
(
det_time
.
begin
(),
det_time
.
end
(),
0.
)
/
1000
;
i
mg_
num
=
std
::
max
(
1
,
img_num
);
i
nt
num
=
std
::
max
(
1
,
img_num
);
LOG
(
INFO
)
<<
"preproce_time(ms): "
<<
det_time
[
0
]
/
img_
num
LOG
(
INFO
)
<<
"preproce_time(ms): "
<<
det_time
[
0
]
/
num
<<
", inference_time(ms): "
<<
det_time
[
1
]
/
img_
num
<<
", inference_time(ms): "
<<
det_time
[
1
]
/
num
<<
", postprocess_time(ms): "
<<
det_time
[
2
]
/
img_
num
;
<<
", postprocess_time(ms): "
<<
det_time
[
2
]
/
num
;
}
}
}
// namespace PaddleDetection
}
// namespace PaddleDetection
deploy/pptracking/src/postprocess.cc
浏览文件 @
531bca9d
...
@@ -14,46 +14,47 @@
...
@@ -14,46 +14,47 @@
#include <sstream>
#include <sstream>
// for setprecision
// for setprecision
#include <iomanip>
#include <chrono>
#include <chrono>
#include <iomanip>
#include "include/postprocess.h"
#include "include/postprocess.h"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
cv
::
Scalar
GetColor
(
int
idx
)
{
cv
::
Scalar
GetColor
(
int
idx
)
{
idx
=
idx
*
3
;
idx
=
idx
*
3
;
cv
::
Scalar
color
=
cv
::
Scalar
((
37
*
idx
)
%
255
,
cv
::
Scalar
color
=
(
17
*
idx
)
%
255
,
cv
::
Scalar
((
37
*
idx
)
%
255
,
(
17
*
idx
)
%
255
,
(
29
*
idx
)
%
255
);
(
29
*
idx
)
%
255
);
return
color
;
return
color
;
}
}
cv
::
Mat
VisualizeTrackResult
(
const
cv
::
Mat
&
img
,
cv
::
Mat
VisualizeTrackResult
(
const
cv
::
Mat
&
img
,
const
MOTResult
&
results
,
const
MOTResult
&
results
,
const
float
fps
,
const
int
frame_id
)
{
const
float
fps
,
const
int
frame_id
)
{
cv
::
Mat
vis_img
=
img
.
clone
();
cv
::
Mat
vis_img
=
img
.
clone
();
int
im_h
=
img
.
rows
;
int
im_h
=
img
.
rows
;
int
im_w
=
img
.
cols
;
int
im_w
=
img
.
cols
;
float
text_scale
=
std
::
max
(
1
,
int
(
im_w
/
1600.
));
float
text_scale
=
std
::
max
(
1
,
static_cast
<
int
>
(
im_w
/
1600.
));
float
text_thickness
=
2.
;
float
text_thickness
=
2.
;
float
line_thickness
=
std
::
max
(
1
,
int
(
im_w
/
500.
));
float
line_thickness
=
std
::
max
(
1
,
static_cast
<
int
>
(
im_w
/
500.
));
std
::
ostringstream
oss
;
std
::
ostringstream
oss
;
oss
<<
std
::
setiosflags
(
std
::
ios
::
fixed
)
<<
std
::
setprecision
(
4
);
oss
<<
std
::
setiosflags
(
std
::
ios
::
fixed
)
<<
std
::
setprecision
(
4
);
oss
<<
"frame: "
<<
frame_id
<<
" "
;
oss
<<
"frame: "
<<
frame_id
<<
" "
;
oss
<<
"fps: "
<<
fps
<<
" "
;
oss
<<
"fps: "
<<
fps
<<
" "
;
oss
<<
"num: "
<<
results
.
size
();
oss
<<
"num: "
<<
results
.
size
();
std
::
string
text
=
oss
.
str
();
std
::
string
text
=
oss
.
str
();
cv
::
Point
origin
;
cv
::
Point
origin
;
origin
.
x
=
0
;
origin
.
x
=
0
;
origin
.
y
=
int
(
15
*
text_scale
);
origin
.
y
=
static_cast
<
int
>
(
15
*
text_scale
);
cv
::
putText
(
cv
::
putText
(
vis_img
,
vis_img
,
text
,
text
,
origin
,
origin
,
cv
::
FONT_HERSHEY_PLAIN
,
cv
::
FONT_HERSHEY_PLAIN
,
text_scale
,
(
0
,
0
,
255
),
2
);
text_scale
,
(
0
,
0
,
255
),
2
);
for
(
int
i
=
0
;
i
<
results
.
size
();
++
i
)
{
for
(
int
i
=
0
;
i
<
results
.
size
();
++
i
)
{
const
int
obj_id
=
results
[
i
].
ids
;
const
int
obj_id
=
results
[
i
].
ids
;
...
@@ -63,8 +64,10 @@ cv::Mat VisualizeTrackResult(const cv::Mat& img,
...
@@ -63,8 +64,10 @@ cv::Mat VisualizeTrackResult(const cv::Mat& img,
cv
::
Point
pt1
=
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
);
cv
::
Point
pt1
=
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
);
cv
::
Point
pt2
=
cv
::
Point
(
results
[
i
].
rects
.
right
,
results
[
i
].
rects
.
bottom
);
cv
::
Point
pt2
=
cv
::
Point
(
results
[
i
].
rects
.
right
,
results
[
i
].
rects
.
bottom
);
cv
::
Point
id_pt
=
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
+
10
);
cv
::
Point
id_pt
=
cv
::
Point
score_pt
=
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
-
10
);
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
+
10
);
cv
::
Point
score_pt
=
cv
::
Point
(
results
[
i
].
rects
.
left
,
results
[
i
].
rects
.
top
-
10
);
cv
::
rectangle
(
vis_img
,
pt1
,
pt2
,
color
,
line_thickness
);
cv
::
rectangle
(
vis_img
,
pt1
,
pt2
,
color
,
line_thickness
);
std
::
ostringstream
idoss
;
std
::
ostringstream
idoss
;
...
@@ -92,19 +95,21 @@ cv::Mat VisualizeTrackResult(const cv::Mat& img,
...
@@ -92,19 +95,21 @@ cv::Mat VisualizeTrackResult(const cv::Mat& img,
text_scale
,
text_scale
,
cv
::
Scalar
(
0
,
255
,
255
),
cv
::
Scalar
(
0
,
255
,
255
),
text_thickness
);
text_thickness
);
}
}
return
vis_img
;
return
vis_img
;
}
}
void
FlowStatistic
(
const
MOTResult
&
results
,
const
int
frame_id
,
void
FlowStatistic
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
in_count_list
,
std
::
vector
<
int
>*
out_count_list
)
{
std
::
vector
<
int
>*
out_count_list
)
{
throw
"Not Implement"
;
throw
"Not Implement"
;
}
}
void
SaveMOTResult
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
std
::
string
>&
records
)
{
void
SaveMOTResult
(
const
MOTResult
&
results
,
const
int
frame_id
,
std
::
vector
<
std
::
string
>*
records
)
{
// result format: frame_id, track_id, x1, y1, w, h
// result format: frame_id, track_id, x1, y1, w, h
std
::
string
record
;
std
::
string
record
;
for
(
int
i
=
0
;
i
<
results
.
size
();
++
i
)
{
for
(
int
i
=
0
;
i
<
results
.
size
();
++
i
)
{
...
@@ -122,11 +127,10 @@ void SaveMOTResult(const MOTResult& results, const int frame_id, std::vector<std
...
@@ -122,11 +127,10 @@ void SaveMOTResult(const MOTResult& results, const int frame_id, std::vector<std
continue
;
continue
;
}
}
std
::
ostringstream
os
;
std
::
ostringstream
os
;
os
<<
frame_id
<<
" "
<<
ids
<<
""
os
<<
frame_id
<<
" "
<<
ids
<<
""
<<
x1
<<
" "
<<
y1
<<
" "
<<
w
<<
" "
<<
x1
<<
" "
<<
y1
<<
" "
<<
h
<<
"
\n
"
;
<<
w
<<
" "
<<
h
<<
"
\n
"
;
record
=
os
.
str
();
record
=
os
.
str
();
records
.
push_back
(
record
);
records
->
push_back
(
record
);
}
}
}
}
...
...
deploy/pptracking/src/preprocess_op.cc
浏览文件 @
531bca9d
...
@@ -12,24 +12,20 @@
...
@@ -12,24 +12,20 @@
// See the License for the specific language governing permissions and
// See the License for the specific language governing permissions and
// limitations under the License.
// limitations under the License.
#include <vector>
#include <string>
#include <string>
#include <thread>
#include <thread>
#include <vector>
#include "include/preprocess_op.h"
#include "include/preprocess_op.h"
namespace
PaddleDetection
{
namespace
PaddleDetection
{
void
InitInfo
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
void
InitInfo
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
data
->
im_shape_
=
{
data
->
im_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
)};
static_cast
<
float
>
(
im
->
cols
)
};
data
->
scale_factor_
=
{
1.
,
1.
};
data
->
scale_factor_
=
{
1.
,
1.
};
data
->
in_net_shape_
=
{
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
)};
static_cast
<
float
>
(
im
->
cols
)
};
}
}
void
NormalizeImage
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
void
NormalizeImage
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
...
@@ -41,11 +37,11 @@ void NormalizeImage::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -41,11 +37,11 @@ void NormalizeImage::Run(cv::Mat* im, ImageBlob* data) {
for
(
int
h
=
0
;
h
<
im
->
rows
;
h
++
)
{
for
(
int
h
=
0
;
h
<
im
->
rows
;
h
++
)
{
for
(
int
w
=
0
;
w
<
im
->
cols
;
w
++
)
{
for
(
int
w
=
0
;
w
<
im
->
cols
;
w
++
)
{
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
0
]
=
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
0
]
=
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
0
]
-
mean_
[
0
]
)
/
scale_
[
0
];
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
0
]
-
mean_
[
0
])
/
scale_
[
0
];
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
1
]
=
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
1
]
=
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
1
]
-
mean_
[
1
]
)
/
scale_
[
1
];
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
1
]
-
mean_
[
1
])
/
scale_
[
1
];
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
2
]
=
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
2
]
=
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
2
]
-
mean_
[
2
]
)
/
scale_
[
2
];
(
im
->
at
<
cv
::
Vec3f
>
(
h
,
w
)[
2
]
-
mean_
[
2
])
/
scale_
[
2
];
}
}
}
}
}
}
...
@@ -64,27 +60,20 @@ void Permute::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -64,27 +60,20 @@ void Permute::Run(cv::Mat* im, ImageBlob* data) {
void
Resize
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
void
Resize
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
auto
resize_scale
=
GenerateScale
(
*
im
);
auto
resize_scale
=
GenerateScale
(
*
im
);
data
->
im_shape_
=
{
data
->
im_shape_
=
{
static_cast
<
float
>
(
im
->
cols
*
resize_scale
.
first
),
static_cast
<
float
>
(
im
->
cols
*
resize_scale
.
first
),
static_cast
<
float
>
(
im
->
rows
*
resize_scale
.
second
)};
static_cast
<
float
>
(
im
->
rows
*
resize_scale
.
second
)
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
cols
*
resize_scale
.
first
),
};
static_cast
<
float
>
(
im
->
rows
*
resize_scale
.
second
)};
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
cols
*
resize_scale
.
first
),
static_cast
<
float
>
(
im
->
rows
*
resize_scale
.
second
)
};
cv
::
resize
(
cv
::
resize
(
*
im
,
*
im
,
cv
::
Size
(),
resize_scale
.
first
,
resize_scale
.
second
,
interp_
);
*
im
,
*
im
,
cv
::
Size
(),
resize_scale
.
first
,
resize_scale
.
second
,
interp_
);
data
->
im_shape_
=
{
data
->
im_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
),
static_cast
<
float
>
(
im
->
cols
),
};
};
data
->
scale_factor_
=
{
data
->
scale_factor_
=
{
resize_scale
.
second
,
resize_scale
.
second
,
resize_scale
.
first
,
resize_scale
.
first
,
};
};
}
}
std
::
pair
<
float
,
float
>
Resize
::
GenerateScale
(
const
cv
::
Mat
&
im
)
{
std
::
pair
<
float
,
float
>
Resize
::
GenerateScale
(
const
cv
::
Mat
&
im
)
{
std
::
pair
<
float
,
float
>
resize_scale
;
std
::
pair
<
float
,
float
>
resize_scale
;
int
origin_w
=
im
.
cols
;
int
origin_w
=
im
.
cols
;
...
@@ -93,8 +82,10 @@ std::pair<float, float> Resize::GenerateScale(const cv::Mat& im) {
...
@@ -93,8 +82,10 @@ std::pair<float, float> Resize::GenerateScale(const cv::Mat& im) {
if
(
keep_ratio_
)
{
if
(
keep_ratio_
)
{
int
im_size_max
=
std
::
max
(
origin_w
,
origin_h
);
int
im_size_max
=
std
::
max
(
origin_w
,
origin_h
);
int
im_size_min
=
std
::
min
(
origin_w
,
origin_h
);
int
im_size_min
=
std
::
min
(
origin_w
,
origin_h
);
int
target_size_max
=
*
std
::
max_element
(
target_size_
.
begin
(),
target_size_
.
end
());
int
target_size_max
=
int
target_size_min
=
*
std
::
min_element
(
target_size_
.
begin
(),
target_size_
.
end
());
*
std
::
max_element
(
target_size_
.
begin
(),
target_size_
.
end
());
int
target_size_min
=
*
std
::
min_element
(
target_size_
.
begin
(),
target_size_
.
end
());
float
scale_min
=
float
scale_min
=
static_cast
<
float
>
(
target_size_min
)
/
static_cast
<
float
>
(
im_size_min
);
static_cast
<
float
>
(
target_size_min
)
/
static_cast
<
float
>
(
im_size_min
);
float
scale_max
=
float
scale_max
=
...
@@ -114,10 +105,8 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -114,10 +105,8 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
float
resize_scale
=
GenerateScale
(
*
im
);
float
resize_scale
=
GenerateScale
(
*
im
);
int
new_shape_w
=
std
::
round
(
im
->
cols
*
resize_scale
);
int
new_shape_w
=
std
::
round
(
im
->
cols
*
resize_scale
);
int
new_shape_h
=
std
::
round
(
im
->
rows
*
resize_scale
);
int
new_shape_h
=
std
::
round
(
im
->
rows
*
resize_scale
);
data
->
im_shape_
=
{
data
->
im_shape_
=
{
static_cast
<
float
>
(
new_shape_h
),
static_cast
<
float
>
(
new_shape_h
),
static_cast
<
float
>
(
new_shape_w
)};
static_cast
<
float
>
(
new_shape_w
)
};
float
padw
=
(
target_size_
[
1
]
-
new_shape_w
)
/
2.
;
float
padw
=
(
target_size_
[
1
]
-
new_shape_w
)
/
2.
;
float
padh
=
(
target_size_
[
0
]
-
new_shape_h
)
/
2.
;
float
padh
=
(
target_size_
[
0
]
-
new_shape_h
)
/
2.
;
...
@@ -130,11 +119,9 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -130,11 +119,9 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
*
im
,
*
im
,
cv
::
Size
(
new_shape_w
,
new_shape_h
),
0
,
0
,
cv
::
INTER_AREA
);
*
im
,
*
im
,
cv
::
Size
(
new_shape_w
,
new_shape_h
),
0
,
0
,
cv
::
INTER_AREA
);
data
->
in_net_shape_
=
{
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
),
static_cast
<
float
>
(
im
->
cols
),
};
};
cv
::
copyMakeBorder
(
cv
::
copyMakeBorder
(
*
im
,
*
im
,
*
im
,
*
im
,
top
,
top
,
bottom
,
bottom
,
...
@@ -144,16 +131,12 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -144,16 +131,12 @@ void LetterBoxResize::Run(cv::Mat* im, ImageBlob* data) {
cv
::
Scalar
(
127.5
));
cv
::
Scalar
(
127.5
));
data
->
in_net_shape_
=
{
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
),
static_cast
<
float
>
(
im
->
cols
),
};
};
data
->
scale_factor_
=
{
data
->
scale_factor_
=
{
resize_scale
,
resize_scale
,
resize_scale
,
resize_scale
,
};
};
}
}
float
LetterBoxResize
::
GenerateScale
(
const
cv
::
Mat
&
im
)
{
float
LetterBoxResize
::
GenerateScale
(
const
cv
::
Mat
&
im
)
{
...
@@ -179,24 +162,19 @@ void PadStride::Run(cv::Mat* im, ImageBlob* data) {
...
@@ -179,24 +162,19 @@ void PadStride::Run(cv::Mat* im, ImageBlob* data) {
int
nh
=
(
rh
/
stride_
)
*
stride_
+
(
rh
%
stride_
!=
0
)
*
stride_
;
int
nh
=
(
rh
/
stride_
)
*
stride_
+
(
rh
%
stride_
!=
0
)
*
stride_
;
int
nw
=
(
rw
/
stride_
)
*
stride_
+
(
rw
%
stride_
!=
0
)
*
stride_
;
int
nw
=
(
rw
/
stride_
)
*
stride_
+
(
rw
%
stride_
!=
0
)
*
stride_
;
cv
::
copyMakeBorder
(
cv
::
copyMakeBorder
(
*
im
,
*
im
,
*
im
,
0
,
nh
-
rh
,
0
,
nw
-
rw
,
cv
::
BORDER_CONSTANT
,
cv
::
Scalar
(
0
));
*
im
,
0
,
nh
-
rh
,
0
,
nw
-
rw
,
cv
::
BORDER_CONSTANT
,
cv
::
Scalar
(
0
));
data
->
in_net_shape_
=
{
data
->
in_net_shape_
=
{
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
rows
),
static_cast
<
float
>
(
im
->
cols
),
static_cast
<
float
>
(
im
->
cols
),
};
};
}
}
// Preprocessor op running order
// Preprocessor op running order
const
std
::
vector
<
std
::
string
>
Preprocessor
::
RUN_ORDER
=
{
const
std
::
vector
<
std
::
string
>
Preprocessor
::
RUN_ORDER
=
{
"InitInfo"
,
"InitInfo"
,
"Resize"
,
"LetterBoxResize"
,
"NormalizeImage"
,
"PadStride"
,
"Permute"
"Resize"
,
};
"LetterBoxResize"
,
"NormalizeImage"
,
"PadStride"
,
"Permute"
};
void
Preprocessor
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
void
Preprocessor
::
Run
(
cv
::
Mat
*
im
,
ImageBlob
*
data
)
{
for
(
const
auto
&
name
:
RUN_ORDER
)
{
for
(
const
auto
&
name
:
RUN_ORDER
)
{
...
...
deploy/pptracking/src/sde_predictor.cc
浏览文件 @
531bca9d
...
@@ -13,12 +13,11 @@
...
@@ -13,12 +13,11 @@
// limitations under the License.
// limitations under the License.
#include <sstream>
#include <sstream>
// for setprecision
// for setprecision
#include <iomanip>
#include <chrono>
#include <chrono>
#include <iomanip>
#include "include/sde_predictor.h"
#include "include/sde_predictor.h"
using
namespace
paddle_infer
;
// NOLINT
using
namespace
paddle_infer
;
namespace
PaddleDetection
{
namespace
PaddleDetection
{
...
@@ -29,13 +28,10 @@ void SDEPredictor::LoadModel(const std::string& det_model_dir,
...
@@ -29,13 +28,10 @@ void SDEPredictor::LoadModel(const std::string& det_model_dir,
throw
"Not Implement"
;
throw
"Not Implement"
;
}
}
void
SDEPredictor
::
Preprocess
(
const
cv
::
Mat
&
ori_im
)
{
throw
"Not Implement"
;
}
void
SDEPredictor
::
Preprocess
(
const
cv
::
Mat
&
ori_im
)
{
void
SDEPredictor
::
Postprocess
(
const
cv
::
Mat
dets
,
throw
"Not Implement"
;
const
cv
::
Mat
emb
,
}
void
SDEPredictor
::
Postprocess
(
const
cv
::
Mat
dets
,
const
cv
::
Mat
emb
,
MOTResult
*
result
)
{
MOTResult
*
result
)
{
throw
"Not Implement"
;
throw
"Not Implement"
;
}
}
...
...
deploy/pptracking/src/tracker.cc
浏览文件 @
531bca9d
...
@@ -17,20 +17,23 @@
...
@@ -17,20 +17,23 @@
// Ths copyright of CnybTseng/JDE is as follows:
// Ths copyright of CnybTseng/JDE is as follows:
// MIT License
// MIT License
#include <map>
#include <stdio.h>
#include <limits.h>
#include <limits.h>
#include <stdio.h>
#include <algorithm>
#include <algorithm>
#include <map>
#include "include/lapjv.h"
#include "include/lapjv.h"
#include "include/tracker.h"
#include "include/tracker.h"
#define mat2vec4f(m) cv::Vec4f(*m.ptr<float>(0,0), *m.ptr<float>(0,1), *m.ptr<float>(0,2), *m.ptr<float>(0,3))
#define mat2vec4f(m) \
cv::Vec4f(*m.ptr<float>(0, 0), \
*m.ptr<float>(0, 1), \
*m.ptr<float>(0, 2), \
*m.ptr<float>(0, 3))
namespace
PaddleDetection
{
namespace
PaddleDetection
{
static
std
::
map
<
int
,
float
>
chi2inv95
=
{
static
std
::
map
<
int
,
float
>
chi2inv95
=
{{
1
,
3.841459
f
},
{
1
,
3.841459
f
},
{
2
,
5.991465
f
},
{
2
,
5.991465
f
},
{
3
,
7.814728
f
},
{
3
,
7.814728
f
},
{
4
,
9.487729
f
},
{
4
,
9.487729
f
},
...
@@ -38,26 +41,21 @@ static std::map<int, float> chi2inv95 = {
...
@@ -38,26 +41,21 @@ static std::map<int, float> chi2inv95 = {
{
6
,
12.591587
f
},
{
6
,
12.591587
f
},
{
7
,
14.067140
f
},
{
7
,
14.067140
f
},
{
8
,
15.507313
f
},
{
8
,
15.507313
f
},
{
9
,
16.918978
f
}
{
9
,
16.918978
f
}};
};
JDETracker
*
JDETracker
::
me
=
new
JDETracker
;
JDETracker
*
JDETracker
::
me
=
new
JDETracker
;
JDETracker
*
JDETracker
::
instance
(
void
)
JDETracker
*
JDETracker
::
instance
(
void
)
{
return
me
;
}
{
return
me
;
}
JDETracker
::
JDETracker
(
void
)
:
timestamp
(
0
),
max_lost_time
(
30
),
lambda
(
0.98
f
),
det_thresh
(
0.3
f
)
JDETracker
::
JDETracker
(
void
)
{
:
timestamp
(
0
),
max_lost_time
(
30
),
lambda
(
0.98
f
),
det_thresh
(
0.3
f
)
{}
}
bool
JDETracker
::
update
(
const
cv
::
Mat
&
dets
,
const
cv
::
Mat
&
emb
,
std
::
vector
<
Track
>
&
tracks
)
bool
JDETracker
::
update
(
const
cv
::
Mat
&
dets
,
{
const
cv
::
Mat
&
emb
,
std
::
vector
<
Track
>
*
tracks
)
{
++
timestamp
;
++
timestamp
;
TrajectoryPool
candidates
(
dets
.
rows
);
TrajectoryPool
candidates
(
dets
.
rows
);
for
(
int
i
=
0
;
i
<
dets
.
rows
;
++
i
)
for
(
int
i
=
0
;
i
<
dets
.
rows
;
++
i
)
{
{
float
score
=
*
dets
.
ptr
<
float
>
(
i
,
4
);
float
score
=
*
dets
.
ptr
<
float
>
(
i
,
4
);
const
cv
::
Mat
&
ltrb_
=
dets
(
cv
::
Rect
(
0
,
i
,
4
,
1
));
const
cv
::
Mat
&
ltrb_
=
dets
(
cv
::
Rect
(
0
,
i
,
4
,
1
));
cv
::
Vec4f
ltrb
=
mat2vec4f
(
ltrb_
);
cv
::
Vec4f
ltrb
=
mat2vec4f
(
ltrb_
);
...
@@ -65,19 +63,17 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
...
@@ -65,19 +63,17 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
candidates
[
i
]
=
Trajectory
(
ltrb
,
score
,
embedding
);
candidates
[
i
]
=
Trajectory
(
ltrb
,
score
,
embedding
);
}
}
TrajectoryPtrPool
tracked_trajectories
;
TrajectoryPtrPool
tracked_trajectories
;
TrajectoryPtrPool
unconfirmed_trajectories
;
TrajectoryPtrPool
unconfirmed_trajectories
;
for
(
size_t
i
=
0
;
i
<
this
->
tracked_trajectories
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
this
->
tracked_trajectories
.
size
();
++
i
)
{
{
if
(
this
->
tracked_trajectories
[
i
].
is_activated
)
if
(
this
->
tracked_trajectories
[
i
].
is_activated
)
tracked_trajectories
.
push_back
(
&
this
->
tracked_trajectories
[
i
]);
tracked_trajectories
.
push_back
(
&
this
->
tracked_trajectories
[
i
]);
else
else
unconfirmed_trajectories
.
push_back
(
&
this
->
tracked_trajectories
[
i
]);
unconfirmed_trajectories
.
push_back
(
&
this
->
tracked_trajectories
[
i
]);
}
}
TrajectoryPtrPool
trajectory_pool
=
TrajectoryPtrPool
trajectory_pool
=
tracked_trajectories
+
this
->
lost_trajectories
;
tracked_trajectories
+
&
(
this
->
lost_trajectories
)
;
for
(
size_t
i
=
0
;
i
<
trajectory_pool
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
trajectory_pool
.
size
();
++
i
)
trajectory_pool
[
i
]
->
predict
();
trajectory_pool
[
i
]
->
predict
();
...
@@ -87,25 +83,20 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
...
@@ -87,25 +83,20 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
std
::
vector
<
int
>
mismatch_col
;
std
::
vector
<
int
>
mismatch_col
;
cv
::
Mat
cost
=
motion_distance
(
trajectory_pool
,
candidates
);
cv
::
Mat
cost
=
motion_distance
(
trajectory_pool
,
candidates
);
linear_assignment
(
cost
,
0.7
f
,
matches
,
mismatch_row
,
mismatch_col
);
linear_assignment
(
cost
,
0.7
f
,
&
matches
,
&
mismatch_row
,
&
mismatch_col
);
MatchIterator
miter
;
MatchIterator
miter
;
TrajectoryPtrPool
activated_trajectories
;
TrajectoryPtrPool
activated_trajectories
;
TrajectoryPtrPool
retrieved_trajectories
;
TrajectoryPtrPool
retrieved_trajectories
;
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
{
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
{
Trajectory
*
pt
=
trajectory_pool
[
miter
->
first
];
Trajectory
*
pt
=
trajectory_pool
[
miter
->
first
];
Trajectory
&
ct
=
candidates
[
miter
->
second
];
Trajectory
&
ct
=
candidates
[
miter
->
second
];
if
(
pt
->
state
==
Tracked
)
if
(
pt
->
state
==
Tracked
)
{
{
pt
->
update
(
&
ct
,
timestamp
);
pt
->
update
(
ct
,
timestamp
);
activated_trajectories
.
push_back
(
pt
);
activated_trajectories
.
push_back
(
pt
);
}
}
else
{
else
pt
->
reactivate
(
&
ct
,
timestamp
);
{
pt
->
reactivate
(
ct
,
timestamp
);
retrieved_trajectories
.
push_back
(
pt
);
retrieved_trajectories
.
push_back
(
pt
);
}
}
}
}
...
@@ -115,38 +106,31 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
...
@@ -115,38 +106,31 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
next_candidates
[
i
]
=
&
candidates
[
mismatch_col
[
i
]];
next_candidates
[
i
]
=
&
candidates
[
mismatch_col
[
i
]];
TrajectoryPtrPool
next_trajectory_pool
;
TrajectoryPtrPool
next_trajectory_pool
;
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
{
{
int
j
=
mismatch_row
[
i
];
int
j
=
mismatch_row
[
i
];
if
(
trajectory_pool
[
j
]
->
state
==
Tracked
)
if
(
trajectory_pool
[
j
]
->
state
==
Tracked
)
next_trajectory_pool
.
push_back
(
trajectory_pool
[
j
]);
next_trajectory_pool
.
push_back
(
trajectory_pool
[
j
]);
}
}
cost
=
iou_distance
(
next_trajectory_pool
,
next_candidates
);
cost
=
iou_distance
(
next_trajectory_pool
,
next_candidates
);
linear_assignment
(
cost
,
0.5
f
,
matches
,
mismatch_row
,
mismatch_col
);
linear_assignment
(
cost
,
0.5
f
,
&
matches
,
&
mismatch_row
,
&
mismatch_col
);
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
{
{
Trajectory
*
pt
=
next_trajectory_pool
[
miter
->
first
];
Trajectory
*
pt
=
next_trajectory_pool
[
miter
->
first
];
Trajectory
*
ct
=
next_candidates
[
miter
->
second
];
Trajectory
*
ct
=
next_candidates
[
miter
->
second
];
if
(
pt
->
state
==
Tracked
)
if
(
pt
->
state
==
Tracked
)
{
{
pt
->
update
(
ct
,
timestamp
);
pt
->
update
(
*
ct
,
timestamp
);
activated_trajectories
.
push_back
(
pt
);
activated_trajectories
.
push_back
(
pt
);
}
}
else
{
else
pt
->
reactivate
(
ct
,
timestamp
);
{
pt
->
reactivate
(
*
ct
,
timestamp
);
retrieved_trajectories
.
push_back
(
pt
);
retrieved_trajectories
.
push_back
(
pt
);
}
}
}
}
TrajectoryPtrPool
lost_trajectories
;
TrajectoryPtrPool
lost_trajectories
;
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
{
{
Trajectory
*
pt
=
next_trajectory_pool
[
mismatch_row
[
i
]];
Trajectory
*
pt
=
next_trajectory_pool
[
mismatch_row
[
i
]];
if
(
pt
->
state
!=
Lost
)
if
(
pt
->
state
!=
Lost
)
{
{
pt
->
mark_lost
();
pt
->
mark_lost
();
lost_trajectories
.
push_back
(
pt
);
lost_trajectories
.
push_back
(
pt
);
}
}
...
@@ -156,42 +140,38 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
...
@@ -156,42 +140,38 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
for
(
size_t
i
=
0
;
i
<
mismatch_col
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
mismatch_col
.
size
();
++
i
)
nnext_candidates
[
i
]
=
next_candidates
[
mismatch_col
[
i
]];
nnext_candidates
[
i
]
=
next_candidates
[
mismatch_col
[
i
]];
cost
=
iou_distance
(
unconfirmed_trajectories
,
nnext_candidates
);
cost
=
iou_distance
(
unconfirmed_trajectories
,
nnext_candidates
);
linear_assignment
(
cost
,
0.7
f
,
matches
,
mismatch_row
,
mismatch_col
);
linear_assignment
(
cost
,
0.7
f
,
&
matches
,
&
mismatch_row
,
&
mismatch_col
);
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
for
(
miter
=
matches
.
begin
();
miter
!=
matches
.
end
();
miter
++
)
{
{
unconfirmed_trajectories
[
miter
->
first
]
->
update
(
unconfirmed_trajectories
[
miter
->
first
]
->
update
(
*
nnext_candidates
[
miter
->
second
],
timestamp
);
nnext_candidates
[
miter
->
second
],
timestamp
);
activated_trajectories
.
push_back
(
unconfirmed_trajectories
[
miter
->
first
]);
activated_trajectories
.
push_back
(
unconfirmed_trajectories
[
miter
->
first
]);
}
}
TrajectoryPtrPool
removed_trajectories
;
TrajectoryPtrPool
removed_trajectories
;
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
mismatch_row
.
size
();
++
i
)
{
{
unconfirmed_trajectories
[
mismatch_row
[
i
]]
->
mark_removed
();
unconfirmed_trajectories
[
mismatch_row
[
i
]]
->
mark_removed
();
removed_trajectories
.
push_back
(
unconfirmed_trajectories
[
mismatch_row
[
i
]]);
removed_trajectories
.
push_back
(
unconfirmed_trajectories
[
mismatch_row
[
i
]]);
}
}
for
(
size_t
i
=
0
;
i
<
mismatch_col
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
mismatch_col
.
size
();
++
i
)
{
{
if
(
nnext_candidates
[
mismatch_col
[
i
]]
->
score
<
det_thresh
)
continue
;
if
(
nnext_candidates
[
mismatch_col
[
i
]]
->
score
<
det_thresh
)
continue
;
nnext_candidates
[
mismatch_col
[
i
]]
->
activate
(
timestamp
);
nnext_candidates
[
mismatch_col
[
i
]]
->
activate
(
timestamp
);
activated_trajectories
.
push_back
(
nnext_candidates
[
mismatch_col
[
i
]]);
activated_trajectories
.
push_back
(
nnext_candidates
[
mismatch_col
[
i
]]);
}
}
for
(
size_t
i
=
0
;
i
<
this
->
lost_trajectories
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
this
->
lost_trajectories
.
size
();
++
i
)
{
{
Trajectory
&
lt
=
this
->
lost_trajectories
[
i
];
Trajectory
&
lt
=
this
->
lost_trajectories
[
i
];
if
(
timestamp
-
lt
.
timestamp
>
max_lost_time
)
if
(
timestamp
-
lt
.
timestamp
>
max_lost_time
)
{
{
lt
.
mark_removed
();
lt
.
mark_removed
();
removed_trajectories
.
push_back
(
&
lt
);
removed_trajectories
.
push_back
(
&
lt
);
}
}
}
}
TrajectoryPoolIterator
piter
;
TrajectoryPoolIterator
piter
;
for
(
piter
=
this
->
tracked_trajectories
.
begin
();
piter
!=
this
->
tracked_trajectories
.
end
();
)
for
(
piter
=
this
->
tracked_trajectories
.
begin
();
{
piter
!=
this
->
tracked_trajectories
.
end
();)
{
if
(
piter
->
state
!=
Tracked
)
if
(
piter
->
state
!=
Tracked
)
piter
=
this
->
tracked_trajectories
.
erase
(
piter
);
piter
=
this
->
tracked_trajectories
.
erase
(
piter
);
else
else
...
@@ -205,26 +185,23 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
...
@@ -205,26 +185,23 @@ bool JDETracker::update(const cv::Mat &dets, const cv::Mat &emb, std::vector<Tra
this
->
lost_trajectories
+=
lost_trajectories
;
this
->
lost_trajectories
+=
lost_trajectories
;
this
->
lost_trajectories
-=
this
->
removed_trajectories
;
this
->
lost_trajectories
-=
this
->
removed_trajectories
;
this
->
removed_trajectories
+=
removed_trajectories
;
this
->
removed_trajectories
+=
removed_trajectories
;
remove_duplicate_trajectory
(
this
->
tracked_trajectories
,
this
->
lost_trajectories
);
remove_duplicate_trajectory
(
&
this
->
tracked_trajectories
,
&
this
->
lost_trajectories
);
tracks
.
clear
();
tracks
->
clear
();
for
(
size_t
i
=
0
;
i
<
this
->
tracked_trajectories
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
this
->
tracked_trajectories
.
size
();
++
i
)
{
{
if
(
this
->
tracked_trajectories
[
i
].
is_activated
)
{
if
(
this
->
tracked_trajectories
[
i
].
is_activated
)
Track
track
=
{.
id
=
this
->
tracked_trajectories
[
i
].
id
,
{
Track
track
=
{
.
id
=
this
->
tracked_trajectories
[
i
].
id
,
.
score
=
this
->
tracked_trajectories
[
i
].
score
,
.
score
=
this
->
tracked_trajectories
[
i
].
score
,
.
ltrb
=
this
->
tracked_trajectories
[
i
].
ltrb
};
.
ltrb
=
this
->
tracked_trajectories
[
i
].
ltrb
};
tracks
.
push_back
(
track
);
tracks
->
push_back
(
track
);
}
}
}
}
return
0
;
return
0
;
}
}
cv
::
Mat
JDETracker
::
motion_distance
(
const
TrajectoryPtrPool
&
a
,
cv
::
Mat
JDETracker
::
motion_distance
(
const
TrajectoryPtrPool
&
a
,
const
TrajectoryPool
&
b
)
const
TrajectoryPool
&
b
)
{
{
if
(
0
==
a
.
size
()
||
0
==
b
.
size
())
if
(
0
==
a
.
size
()
||
0
==
b
.
size
())
return
cv
::
Mat
(
a
.
size
(),
b
.
size
(),
CV_32F
);
return
cv
::
Mat
(
a
.
size
(),
b
.
size
(),
CV_32F
);
...
@@ -233,10 +210,8 @@ cv::Mat JDETracker::motion_distance(const TrajectoryPtrPool &a, const Trajectory
...
@@ -233,10 +210,8 @@ cv::Mat JDETracker::motion_distance(const TrajectoryPtrPool &a, const Trajectory
cv
::
Mat
fdists
=
lambda
*
edists
+
(
1
-
lambda
)
*
mdists
;
cv
::
Mat
fdists
=
lambda
*
edists
+
(
1
-
lambda
)
*
mdists
;
const
float
gate_thresh
=
chi2inv95
[
4
];
const
float
gate_thresh
=
chi2inv95
[
4
];
for
(
int
i
=
0
;
i
<
fdists
.
rows
;
++
i
)
for
(
int
i
=
0
;
i
<
fdists
.
rows
;
++
i
)
{
{
for
(
int
j
=
0
;
j
<
fdists
.
cols
;
++
j
)
{
for
(
int
j
=
0
;
j
<
fdists
.
cols
;
++
j
)
{
if
(
*
mdists
.
ptr
<
float
>
(
i
,
j
)
>
gate_thresh
)
if
(
*
mdists
.
ptr
<
float
>
(
i
,
j
)
>
gate_thresh
)
*
fdists
.
ptr
<
float
>
(
i
,
j
)
=
FLT_MAX
;
*
fdists
.
ptr
<
float
>
(
i
,
j
)
=
FLT_MAX
;
}
}
...
@@ -245,18 +220,17 @@ cv::Mat JDETracker::motion_distance(const TrajectoryPtrPool &a, const Trajectory
...
@@ -245,18 +220,17 @@ cv::Mat JDETracker::motion_distance(const TrajectoryPtrPool &a, const Trajectory
return
fdists
;
return
fdists
;
}
}
void
JDETracker
::
linear_assignment
(
const
cv
::
Mat
&
cost
,
float
cost_limit
,
Match
&
matches
,
void
JDETracker
::
linear_assignment
(
const
cv
::
Mat
&
cost
,
std
::
vector
<
int
>
&
mismatch_row
,
std
::
vector
<
int
>
&
mismatch_col
)
float
cost_limit
,
{
Match
*
matches
,
matches
.
clear
();
std
::
vector
<
int
>
*
mismatch_row
,
mismatch_row
.
clear
();
std
::
vector
<
int
>
*
mismatch_col
)
{
mismatch_col
.
clear
();
matches
->
clear
();
if
(
cost
.
empty
())
mismatch_row
->
clear
();
{
mismatch_col
->
clear
();
for
(
int
i
=
0
;
i
<
cost
.
rows
;
++
i
)
if
(
cost
.
empty
())
{
mismatch_row
.
push_back
(
i
);
for
(
int
i
=
0
;
i
<
cost
.
rows
;
++
i
)
mismatch_row
->
push_back
(
i
);
for
(
int
i
=
0
;
i
<
cost
.
cols
;
++
i
)
for
(
int
i
=
0
;
i
<
cost
.
cols
;
++
i
)
mismatch_col
->
push_back
(
i
);
mismatch_col
.
push_back
(
i
);
return
;
return
;
}
}
...
@@ -264,44 +238,43 @@ void JDETracker::linear_assignment(const cv::Mat &cost, float cost_limit, Match
...
@@ -264,44 +238,43 @@ void JDETracker::linear_assignment(const cv::Mat &cost, float cost_limit, Match
cv
::
Mat
x
(
cost
.
rows
,
1
,
CV_32S
);
cv
::
Mat
x
(
cost
.
rows
,
1
,
CV_32S
);
cv
::
Mat
y
(
cost
.
cols
,
1
,
CV_32S
);
cv
::
Mat
y
(
cost
.
cols
,
1
,
CV_32S
);
lapjv_internal
(
cost
,
true
,
cost_limit
,
lapjv_internal
(
cost
,
(
int
*
)
x
.
data
,
(
int
*
)
y
.
data
);
true
,
cost_limit
,
reinterpret_cast
<
int
*>
(
x
.
data
),
reinterpret_cast
<
int
*>
(
y
.
data
));
for
(
int
i
=
0
;
i
<
x
.
rows
;
++
i
)
for
(
int
i
=
0
;
i
<
x
.
rows
;
++
i
)
{
{
int
j
=
*
x
.
ptr
<
int
>
(
i
);
int
j
=
*
x
.
ptr
<
int
>
(
i
);
if
(
j
>=
0
)
if
(
j
>=
0
)
matches
.
insert
({
i
,
j
});
matches
->
insert
({
i
,
j
});
else
else
mismatch_row
.
push_back
(
i
);
mismatch_row
->
push_back
(
i
);
}
}
for
(
int
i
=
0
;
i
<
y
.
rows
;
++
i
)
for
(
int
i
=
0
;
i
<
y
.
rows
;
++
i
)
{
{
int
j
=
*
y
.
ptr
<
int
>
(
i
);
int
j
=
*
y
.
ptr
<
int
>
(
i
);
if
(
j
<
0
)
if
(
j
<
0
)
mismatch_col
->
push_back
(
i
);
mismatch_col
.
push_back
(
i
);
}
}
return
;
return
;
}
}
void
JDETracker
::
remove_duplicate_trajectory
(
TrajectoryPool
&
a
,
TrajectoryPool
&
b
,
float
iou_thresh
)
void
JDETracker
::
remove_duplicate_trajectory
(
TrajectoryPool
*
a
,
{
TrajectoryPool
*
b
,
if
(
0
==
a
.
size
()
||
0
==
b
.
size
())
float
iou_thresh
)
{
return
;
if
(
a
->
size
()
==
0
||
b
->
size
()
==
0
)
return
;
cv
::
Mat
dist
=
iou_distance
(
a
,
b
);
cv
::
Mat
dist
=
iou_distance
(
*
a
,
*
b
);
cv
::
Mat
mask
=
dist
<
iou_thresh
;
cv
::
Mat
mask
=
dist
<
iou_thresh
;
std
::
vector
<
cv
::
Point
>
idx
;
std
::
vector
<
cv
::
Point
>
idx
;
cv
::
findNonZero
(
mask
,
idx
);
cv
::
findNonZero
(
mask
,
idx
);
std
::
vector
<
int
>
da
;
std
::
vector
<
int
>
da
;
std
::
vector
<
int
>
db
;
std
::
vector
<
int
>
db
;
for
(
size_t
i
=
0
;
i
<
idx
.
size
();
++
i
)
for
(
size_t
i
=
0
;
i
<
idx
.
size
();
++
i
)
{
{
int
ta
=
(
*
a
)[
idx
[
i
].
y
].
timestamp
-
(
*
a
)[
idx
[
i
].
y
].
starttime
;
int
ta
=
a
[
idx
[
i
].
y
].
timestamp
-
a
[
idx
[
i
].
y
].
starttime
;
int
tb
=
(
*
b
)[
idx
[
i
].
x
].
timestamp
-
(
*
b
)[
idx
[
i
].
x
].
starttime
;
int
tb
=
b
[
idx
[
i
].
x
].
timestamp
-
b
[
idx
[
i
].
x
].
starttime
;
if
(
ta
>
tb
)
if
(
ta
>
tb
)
db
.
push_back
(
idx
[
i
].
x
);
db
.
push_back
(
idx
[
i
].
x
);
else
else
...
@@ -310,21 +283,19 @@ void JDETracker::remove_duplicate_trajectory(TrajectoryPool &a, TrajectoryPool &
...
@@ -310,21 +283,19 @@ void JDETracker::remove_duplicate_trajectory(TrajectoryPool &a, TrajectoryPool &
int
id
=
0
;
int
id
=
0
;
TrajectoryPoolIterator
piter
;
TrajectoryPoolIterator
piter
;
for
(
piter
=
a
.
begin
();
piter
!=
a
.
end
();
)
for
(
piter
=
a
->
begin
();
piter
!=
a
->
end
();)
{
{
std
::
vector
<
int
>::
iterator
iter
=
find
(
da
.
begin
(),
da
.
end
(),
id
++
);
std
::
vector
<
int
>::
iterator
iter
=
find
(
da
.
begin
(),
da
.
end
(),
id
++
);
if
(
iter
!=
da
.
end
())
if
(
iter
!=
da
.
end
())
piter
=
a
.
erase
(
piter
);
piter
=
a
->
erase
(
piter
);
else
else
++
piter
;
++
piter
;
}
}
id
=
0
;
id
=
0
;
for
(
piter
=
b
.
begin
();
piter
!=
b
.
end
();
)
for
(
piter
=
b
->
begin
();
piter
!=
b
->
end
();)
{
{
std
::
vector
<
int
>::
iterator
iter
=
find
(
db
.
begin
(),
db
.
end
(),
id
++
);
std
::
vector
<
int
>::
iterator
iter
=
find
(
db
.
begin
(),
db
.
end
(),
id
++
);
if
(
iter
!=
db
.
end
())
if
(
iter
!=
db
.
end
())
piter
=
b
.
erase
(
piter
);
piter
=
b
->
erase
(
piter
);
else
else
++
piter
;
++
piter
;
}
}
...
...
deploy/pptracking/src/trajectory.cc
浏览文件 @
531bca9d
此差异已折叠。
点击以展开。
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录