[Model] add pptracking model (#357)

* add override mark

* delete some

* recovery

* recovery

* add tracking

* add tracking py_bind and example

* add pptracking

* add pptracking

* iomanip head file

* add opencv_video lib

* add python libs package

Signed-off-by: ChaoII <849453582@qq.com>

* complete comments

Signed-off-by: ChaoII <849453582@qq.com>

* add jdeTracker_ member variable

Signed-off-by: ChaoII <849453582@qq.com>

* add 'FASTDEPLOY_DECL' macro

Signed-off-by: ChaoII <849453582@qq.com>

* remove kwargs params

Signed-off-by: ChaoII <849453582@qq.com>

* [Doc]update pptracking docs

* delete 'ENABLE_PADDLE_FRONTEND' switch

* add pptracking unit test

* update pptracking unit test

Signed-off-by: ChaoII <849453582@qq.com>

* modify test video file path and remove trt test

* update unit test model url

* remove 'FASTDEPLOY_DECL' macro

Signed-off-by: ChaoII <849453582@qq.com>

* fix build python packages about pptracking on win32

Signed-off-by: ChaoII <849453582@qq.com>

Signed-off-by: ChaoII <849453582@qq.com>
Co-authored-by: Jason <jiangjiajun@baidu.com>
This commit is contained in:
ChaoII
2022-10-26 14:27:55 +08:00
committed by GitHub
parent da7247aa41
commit ba501fd963
38 changed files with 2959 additions and 16 deletions

View File

@@ -0,0 +1,413 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/gatagat/lap/blob/master/lap/lapjv.cpp
// Ths copyright of gatagat/lap is as follows:
// MIT License
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "fastdeploy/vision/tracking/pptracking/lapjv.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
/** Column-reduction and reduction transfer for a dense cost matrix.
*/
int _ccrrt_dense(
const int n, float *cost[], int *free_rows, int *x, int *y, float *v) {
int n_free_rows;
bool *unique;
for (int i = 0; i < n; i++) {
x[i] = -1;
v[i] = LARGE;
y[i] = 0;
}
for (int i = 0; i < n; i++) {
for (int j = 0; j < n; j++) {
const float c = cost[i][j];
if (c < v[j]) {
v[j] = c;
y[j] = i;
}
}
}
NEW(unique, bool, n);
memset(unique, TRUE, n);
{
int j = n;
do {
j--;
const int i = y[j];
if (x[i] < 0) {
x[i] = j;
} else {
unique[i] = FALSE;
y[j] = -1;
}
} while (j > 0);
}
n_free_rows = 0;
for (int i = 0; i < n; i++) {
if (x[i] < 0) {
free_rows[n_free_rows++] = i;
} else if (unique[i]) {
const int j = x[i];
float min = LARGE;
for (int j2 = 0; j2 < n; j2++) {
if (j2 == static_cast<int>(j)) {
continue;
}
const float c = cost[i][j2] - v[j2];
if (c < min) {
min = c;
}
}
v[j] -= min;
}
}
FREE(unique);
return n_free_rows;
}
/** Augmenting row reduction for a dense cost matrix.
*/
int _carr_dense(const int n,
float *cost[],
const int n_free_rows,
int *free_rows,
int *x,
int *y,
float *v) {
int current = 0;
int new_free_rows = 0;
int rr_cnt = 0;
while (current < n_free_rows) {
int i0;
int j1, j2;
float v1, v2, v1_new;
bool v1_lowers;
rr_cnt++;
const int free_i = free_rows[current++];
j1 = 0;
v1 = cost[free_i][0] - v[0];
j2 = -1;
v2 = LARGE;
for (int j = 1; j < n; j++) {
const float c = cost[free_i][j] - v[j];
if (c < v2) {
if (c >= v1) {
v2 = c;
j2 = j;
} else {
v2 = v1;
v1 = c;
j2 = j1;
j1 = j;
}
}
}
i0 = y[j1];
v1_new = v[j1] - (v2 - v1);
v1_lowers = v1_new < v[j1];
if (rr_cnt < current * n) {
if (v1_lowers) {
v[j1] = v1_new;
} else if (i0 >= 0 && j2 >= 0) {
j1 = j2;
i0 = y[j2];
}
if (i0 >= 0) {
if (v1_lowers) {
free_rows[--current] = i0;
} else {
free_rows[new_free_rows++] = i0;
}
}
} else {
if (i0 >= 0) {
free_rows[new_free_rows++] = i0;
}
}
x[free_i] = j1;
y[j1] = free_i;
}
return new_free_rows;
}
/** 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 hi = lo + 1;
float mind = d[cols[lo]];
for (int k = hi; k < n; k++) {
int j = cols[k];
if (d[j] <= mind) {
if (d[j] < mind) {
hi = lo;
mind = d[j];
}
cols[k] = cols[hi];
cols[hi++] = j;
}
}
return hi;
}
// Scan all columns in TODO starting from arbitrary column in SCAN
// and try to decrease d of the TODO columns using the SCAN column.
int _scan_dense(const int n,
float *cost[],
int *plo,
int *phi,
float *d,
int *cols,
int *pred,
int *y,
float *v) {
int lo = *plo;
int hi = *phi;
float h, cred_ij;
while (lo != hi) {
int j = cols[lo++];
const int i = y[j];
const float mind = d[j];
h = cost[i][j] - v[j] - mind;
// For all columns in TODO
for (int k = hi; k < n; k++) {
j = cols[k];
cred_ij = cost[i][j] - v[j] - h;
if (cred_ij < d[j]) {
d[j] = cred_ij;
pred[j] = i;
if (cred_ij == mind) {
if (y[j] < 0) {
return j;
}
cols[k] = cols[hi];
cols[hi++] = j;
}
}
}
}
*plo = lo;
*phi = hi;
return -1;
}
/** Single iteration of modified Dijkstra shortest path algorithm as explained
* in the JV paper.
*
* This is a dense matrix version.
*
* \return The closest free column index.
*/
int find_path_dense(const int n,
float *cost[],
const int start_i,
int *y,
float *v,
int *pred) {
int lo = 0, hi = 0;
int final_j = -1;
int n_ready = 0;
int *cols;
float *d;
NEW(cols, int, n);
NEW(d, float, n);
for (int i = 0; i < n; i++) {
cols[i] = i;
pred[i] = start_i;
d[i] = cost[start_i][i] - v[i];
}
while (final_j == -1) {
// No columns left on the SCAN list.
if (lo == hi) {
n_ready = lo;
hi = _find_dense(n, lo, d, cols, y);
for (int k = lo; k < hi; k++) {
const int j = cols[k];
if (y[j] < 0) {
final_j = j;
}
}
}
if (final_j == -1) {
final_j = _scan_dense(n, cost, &lo, &hi, d, cols, pred, y, v);
}
}
{
const float mind = d[cols[lo]];
for (int k = 0; k < n_ready; k++) {
const int j = cols[k];
v[j] += d[j] - mind;
}
}
FREE(cols);
FREE(d);
return final_j;
}
/** Augment for a dense cost matrix.
*/
int _ca_dense(const int n,
float *cost[],
const int n_free_rows,
int *free_rows,
int *x,
int *y,
float *v) {
int *pred;
NEW(pred, int, n);
for (int *pfree_i = free_rows; pfree_i < free_rows + n_free_rows; pfree_i++) {
int i = -1, j;
int k = 0;
j = find_path_dense(n, cost, *pfree_i, y, v, pred);
while (i != *pfree_i) {
i = pred[j];
y[j] = i;
SWAP_INDICES(j, x[i]);
k++;
}
}
FREE(pred);
return 0;
}
/** Solve dense sparse LAP.
*/
int lapjv_internal(const cv::Mat &cost,
const bool extend_cost,
const float cost_limit,
int *x,
int *y) {
int n_rows = cost.rows;
int n_cols = cost.cols;
int n;
if (n_rows == n_cols) {
n = n_rows;
} else if (!extend_cost) {
throw std::invalid_argument(
"Square cost array expected. If cost is intentionally non-square, pass "
"extend_cost=True.");
}
// Get extend cost
if (extend_cost || cost_limit < LARGE) {
n = n_rows + n_cols;
}
cv::Mat cost_expand(n, n, CV_32F);
float expand_value;
if (cost_limit < LARGE) {
expand_value = cost_limit / 2;
} else {
double max_v;
minMaxLoc(cost, nullptr, &max_v);
expand_value = static_cast<float>(max_v) + 1.;
}
for (int i = 0; i < n; ++i) {
for (int j = 0; j < n; ++j) {
cost_expand.at<float>(i, j) = expand_value;
if (i >= n_rows && j >= n_cols) {
cost_expand.at<float>(i, j) = 0;
} else if (i < n_rows && j < n_cols) {
cost_expand.at<float>(i, j) = cost.at<float>(i, j);
}
}
}
// Convert Mat to pointer array
float **cost_ptr;
NEW(cost_ptr, float *, n);
for (int i = 0; i < n; ++i) {
NEW(cost_ptr[i], float, n);
}
for (int i = 0; i < n; ++i) {
for (int j = 0; j < n; ++j) {
cost_ptr[i][j] = cost_expand.at<float>(i, j);
}
}
int ret;
int *free_rows;
float *v;
int *x_c;
int *y_c;
NEW(free_rows, int, n);
NEW(v, float, n);
NEW(x_c, int, n);
NEW(y_c, int, n);
ret = _ccrrt_dense(n, cost_ptr, free_rows, x_c, y_c, v);
int i = 0;
while (ret > 0 && i < 2) {
ret = _carr_dense(n, cost_ptr, ret, free_rows, x_c, y_c, v);
i++;
}
if (ret > 0) {
ret = _ca_dense(n, cost_ptr, ret, free_rows, x_c, y_c, v);
}
FREE(v);
FREE(free_rows);
for (int i = 0; i < n; ++i) {
FREE(cost_ptr[i]);
}
FREE(cost_ptr);
if (ret != 0) {
if (ret == -1) {
throw "Out of memory.";
}
throw "Unknown error (lapjv_internal)";
}
// Get output of x, y, opt
for (int i = 0; i < n; ++i) {
if (i < n_rows) {
x[i] = x_c[i];
if (x[i] >= n_cols) {
x[i] = -1;
}
}
if (i < n_cols) {
y[i] = y_c[i];
if (y[i] >= n_rows) {
y[i] = -1;
}
}
}
FREE(x_c);
FREE(y_c);
return ret;
}
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,66 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/gatagat/lap/blob/master/lap/lapjv.h
// Ths copyright of gatagat/lap is as follows:
// MIT License
#pragma once
#define LARGE 1000000
#if !defined TRUE
#define TRUE 1
#endif
#if !defined FALSE
#define FALSE 0
#endif
#define NEW(x, t, n) \
if ((x = reinterpret_cast<t *>(malloc(sizeof(t) * (n)))) == 0) { \
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>
namespace fastdeploy {
namespace vision {
namespace tracking {
typedef signed int int_t;
typedef unsigned int uint_t;
typedef double cost_t;
typedef char boolean;
typedef enum fp_t { FP_1 = 1, FP_2 = 2, FP_DYNAMIC = 3 } fp_t;
int lapjv_internal(const cv::Mat &cost,
const bool extend_cost,
const float cost_limit,
int *x,
int *y);
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,59 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "fastdeploy/vision/tracking/pptracking/letter_box.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
LetterBoxResize::LetterBoxResize(const std::vector<int>& target_size, const std::vector<float>& color){
target_size_=target_size;
color_=color;
}
bool LetterBoxResize::ImplByOpenCV(Mat* mat){
if (mat->Channels() != color_.size()) {
FDERROR << "Pad: Require input channels equals to size of padding value, "
"but now channels = "
<< mat->Channels()
<< ", the size of padding values = " << color_.size() << "."
<< std::endl;
return false;
}
// generate scale_factor
int origin_w = mat->Width();
int origin_h = mat->Height();
int target_h = target_size_[0];
int target_w = target_size_[1];
float ratio_h = static_cast<float>(target_h) / static_cast<float>(origin_h);
float ratio_w = static_cast<float>(target_w) / static_cast<float>(origin_w);
float resize_scale = std::min(ratio_h, ratio_w);
int new_shape_w = std::round(mat->Width() * resize_scale);
int new_shape_h = std::round(mat->Height() * resize_scale);
float padw = (target_size_[1] - new_shape_w) / 2.;
float padh = (target_size_[0] - new_shape_h) / 2.;
int top = std::round(padh - 0.1);
int bottom = std::round(padh + 0.1);
int left = std::round(padw - 0.1);
int right = std::round(padw + 0.1);
Resize::Run(mat,new_shape_w,new_shape_h);
Pad::Run(mat,top,bottom,left,right,color_);
return true;
}
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,36 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include "fastdeploy/vision/common/processors/transform.h"
#include "fastdeploy/fastdeploy_model.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
class LetterBoxResize: public Processor{
public:
LetterBoxResize(const std::vector<int>& target_size, const std::vector<float>& color);
bool ImplByOpenCV(Mat* mat) override;
std::string Name() override { return "LetterBoxResize"; }
private:
std::vector<int> target_size_;
std::vector<float> color_;
};
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,331 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "fastdeploy/vision/tracking/pptracking/model.h"
#include "yaml-cpp/yaml.h"
#include "paddle2onnx/converter.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
PPTracking::PPTracking(const std::string& model_file,
const std::string& params_file,
const std::string& config_file,
const RuntimeOption& custom_option,
const ModelFormat& model_format){
config_file_=config_file;
valid_cpu_backends = {Backend::PDINFER, Backend::ORT};
valid_gpu_backends = {Backend::PDINFER, Backend::ORT};
runtime_option = custom_option;
runtime_option.model_format = model_format;
runtime_option.model_file = model_file;
runtime_option.params_file = params_file;
initialized = Initialize();
}
bool PPTracking::BuildPreprocessPipelineFromConfig(){
processors_.clear();
YAML::Node cfg;
try {
cfg = YAML::LoadFile(config_file_);
} catch (YAML::BadFile& e) {
FDERROR << "Failed to load yaml file " << config_file_
<< ", maybe you should check this file." << std::endl;
return false;
}
// Get draw_threshold for visualization
if (cfg["draw_threshold"].IsDefined()) {
draw_threshold_ = cfg["draw_threshold"].as<float>();
} else {
FDERROR << "Please set draw_threshold." << std::endl;
return false;
}
// Get config for tracker
if (cfg["tracker"].IsDefined()) {
if (cfg["tracker"]["conf_thres"].IsDefined()) {
conf_thresh_ = cfg["tracker"]["conf_thres"].as<float>();
}
else {
std::cerr << "Please set conf_thres in tracker." << std::endl;
return false;
}
if (cfg["tracker"]["min_box_area"].IsDefined()) {
min_box_area_ = cfg["tracker"]["min_box_area"].as<float>();
}
if (cfg["tracker"]["tracked_thresh"].IsDefined()) {
tracked_thresh_ = cfg["tracker"]["tracked_thresh"].as<float>();
}
}
processors_.push_back(std::make_shared<BGR2RGB>());
for (const auto& op : cfg["Preprocess"]) {
std::string op_name = op["type"].as<std::string>();
if (op_name == "Resize") {
bool keep_ratio = op["keep_ratio"].as<bool>();
auto target_size = op["target_size"].as<std::vector<int>>();
int interp = op["interp"].as<int>();
FDASSERT(target_size.size() == 2,
"Require size of target_size be 2, but now it's %lu.",
target_size.size());
if (!keep_ratio) {
int width = target_size[1];
int height = target_size[0];
processors_.push_back(
std::make_shared<Resize>(width, height, -1.0, -1.0, interp, false));
} else {
int min_target_size = std::min(target_size[0], target_size[1]);
int max_target_size = std::max(target_size[0], target_size[1]);
std::vector<int> max_size;
if (max_target_size > 0) {
max_size.push_back(max_target_size);
max_size.push_back(max_target_size);
}
processors_.push_back(std::make_shared<ResizeByShort>(
min_target_size, interp, true, max_size));
}
}
else if(op_name == "LetterBoxResize"){
auto target_size = op["target_size"].as<std::vector<int>>();
FDASSERT(target_size.size() == 2,"Require size of target_size be 2, but now it's %lu.",
target_size.size());
std::vector<float> color{127.0f,127.0f,127.0f};
if (op["fill_value"].IsDefined()){
color =op["fill_value"].as<std::vector<float>>();
}
processors_.push_back(std::make_shared<LetterBoxResize>(target_size, color));
}
else if (op_name == "NormalizeImage") {
auto mean = op["mean"].as<std::vector<float>>();
auto std = op["std"].as<std::vector<float>>();
bool is_scale = true;
if (op["is_scale"]) {
is_scale = op["is_scale"].as<bool>();
}
std::string norm_type = "mean_std";
if (op["norm_type"]) {
norm_type = op["norm_type"].as<std::string>();
}
if (norm_type != "mean_std") {
std::fill(mean.begin(), mean.end(), 0.0);
std::fill(std.begin(), std.end(), 1.0);
}
processors_.push_back(std::make_shared<Normalize>(mean, std, is_scale));
}
else if (op_name == "Permute") {
// Do nothing, do permute as the last operation
continue;
// processors_.push_back(std::make_shared<HWC2CHW>());
} else if (op_name == "Pad") {
auto size = op["size"].as<std::vector<int>>();
auto value = op["fill_value"].as<std::vector<float>>();
processors_.push_back(std::make_shared<Cast>("float"));
processors_.push_back(
std::make_shared<PadToSize>(size[1], size[0], value));
} else if (op_name == "PadStride") {
auto stride = op["stride"].as<int>();
processors_.push_back(
std::make_shared<StridePad>(stride, std::vector<float>(3, 0)));
} else {
FDERROR << "Unexcepted preprocess operator: " << op_name << "."
<< std::endl;
return false;
}
}
processors_.push_back(std::make_shared<HWC2CHW>());
return true;
}
void PPTracking::GetNmsInfo() {
if (runtime_option.model_format == ModelFormat::PADDLE) {
std::string contents;
if (!ReadBinaryFromFile(runtime_option.model_file, &contents)) {
return;
}
auto reader = paddle2onnx::PaddleReader(contents.c_str(), contents.size());
if (reader.has_nms) {
has_nms_ = true;
background_label = reader.nms_params.background_label;
keep_top_k = reader.nms_params.keep_top_k;
nms_eta = reader.nms_params.nms_eta;
nms_threshold = reader.nms_params.nms_threshold;
score_threshold = reader.nms_params.score_threshold;
nms_top_k = reader.nms_params.nms_top_k;
normalized = reader.nms_params.normalized;
}
}
}
bool PPTracking::Initialize() {
// remove multiclass_nms3 now
// this is a trick operation for ppyoloe while inference on trt
GetNmsInfo();
runtime_option.remove_multiclass_nms_ = true;
runtime_option.custom_op_info_["multiclass_nms3"] = "MultiClassNMS";
if (!BuildPreprocessPipelineFromConfig()) {
FDERROR << "Failed to build preprocess pipeline from configuration file."
<< std::endl;
return false;
}
if (!InitRuntime()) {
FDERROR << "Failed to initialize fastdeploy backend." << std::endl;
return false;
}
if (has_nms_ && runtime_option.backend == Backend::TRT) {
FDINFO << "Detected operator multiclass_nms3 in your model, will replace "
"it with fastdeploy::backend::MultiClassNMS(background_label="
<< background_label << ", keep_top_k=" << keep_top_k
<< ", nms_eta=" << nms_eta << ", nms_threshold=" << nms_threshold
<< ", score_threshold=" << score_threshold
<< ", nms_top_k=" << nms_top_k << ", normalized=" << normalized
<< ")." << std::endl;
has_nms_ = false;
}
// create JDETracker instance
std::unique_ptr<JDETracker> jdeTracker(new JDETracker);
jdeTracker_ = std::move(jdeTracker);
return true;
}
bool PPTracking::Predict(cv::Mat *img, MOTResult *result) {
Mat mat(*img);
std::vector<FDTensor> input_tensors;
if (!Preprocess(&mat, &input_tensors)) {
FDERROR << "Failed to preprocess input image." << std::endl;
return false;
}
std::vector<FDTensor> output_tensors;
if (!Infer(input_tensors, &output_tensors)) {
FDERROR << "Failed to inference." << std::endl;
return false;
}
if (!Postprocess(output_tensors, result)) {
FDERROR << "Failed to post process." << std::endl;
return false;
}
return true;
}
bool PPTracking::Preprocess(Mat* mat, std::vector<FDTensor>* outputs) {
int origin_w = mat->Width();
int origin_h = mat->Height();
for (size_t i = 0; i < processors_.size(); ++i) {
if (!(*(processors_[i].get()))(mat)) {
FDERROR << "Failed to process image data in " << processors_[i]->Name()
<< "." << std::endl;
return false;
}
}
// LetterBoxResize(mat);
// Normalize::Run(mat,mean_,scale_,is_scale_);
// HWC2CHW::Run(mat);
Cast::Run(mat, "float");
outputs->resize(3);
// image_shape
(*outputs)[0].Allocate({1, 2}, FDDataType::FP32, InputInfoOfRuntime(0).name);
float* shape = static_cast<float*>((*outputs)[0].MutableData());
shape[0] = mat->Height();
shape[1] = mat->Width();
// image
(*outputs)[1].name = InputInfoOfRuntime(1).name;
mat->ShareWithTensor(&((*outputs)[1]));
(*outputs)[1].ExpandDim(0);
// scale
(*outputs)[2].Allocate({1, 2}, FDDataType::FP32, InputInfoOfRuntime(2).name);
float* scale = static_cast<float*>((*outputs)[2].MutableData());
scale[0] = mat->Height() * 1.0 / origin_h;
scale[1] = mat->Width() * 1.0 / origin_w;
return true;
}
void FilterDets(const float conf_thresh,const cv::Mat& dets,std::vector<int>* index) {
for (int i = 0; i < dets.rows; ++i) {
float score = *dets.ptr<float>(i, 4);
if (score > conf_thresh) {
index->push_back(i);
}
}
}
bool PPTracking::Postprocess(std::vector<FDTensor>& infer_result, MOTResult *result){
auto bbox_shape = infer_result[0].shape;
auto bbox_data = static_cast<float*>(infer_result[0].Data());
auto emb_shape = infer_result[1].shape;
auto emb_data = static_cast<float*>(infer_result[1].Data());
cv::Mat dets(bbox_shape[0], 6, CV_32FC1, bbox_data);
cv::Mat emb(bbox_shape[0], emb_shape[1], CV_32FC1, emb_data);
result->Clear();
std::vector<Track> tracks;
std::vector<int> valid;
FilterDets(conf_thresh_, dets, &valid);
cv::Mat new_dets, new_emb;
for (int i = 0; i < valid.size(); ++i) {
new_dets.push_back(dets.row(valid[i]));
new_emb.push_back(emb.row(valid[i]));
}
jdeTracker_->update(new_dets, new_emb, &tracks);
if (tracks.size() == 0) {
std::array<int ,4> box={int(*dets.ptr<float>(0, 0)),
int(*dets.ptr<float>(0, 1)),
int(*dets.ptr<float>(0, 2)),
int(*dets.ptr<float>(0, 3))};
result->boxes.push_back(box);
result->ids.push_back(1);
result->scores.push_back(*dets.ptr<float>(0, 4));
} else {
std::vector<Track>::iterator titer;
for (titer = tracks.begin(); titer != tracks.end(); ++titer) {
if (titer->score < tracked_thresh_) {
continue;
} else {
float w = titer->ltrb[2] - titer->ltrb[0];
float h = titer->ltrb[3] - titer->ltrb[1];
bool vertical = w / h > 1.6;
float area = w * h;
if (area > min_box_area_ && !vertical) {
std::array<int ,4> box = {
int(titer->ltrb[0]), int(titer->ltrb[1]), int(titer->ltrb[2]), int(titer->ltrb[3])};
result->boxes.push_back(box);
result->ids.push_back(titer->id);
result->scores.push_back(titer->score);
}
}
}
}
return true;
}
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,90 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include "fastdeploy/vision/common/processors/transform.h"
#include "fastdeploy/fastdeploy_model.h"
#include "fastdeploy/vision/common/result.h"
#include "fastdeploy/vision/tracking/pptracking/tracker.h"
#include "fastdeploy/vision/tracking/pptracking/letter_box.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
class FASTDEPLOY_DECL PPTracking: public FastDeployModel {
public:
/** \brief Set path of model file and configuration file, and the configuration of runtime
*
* \param[in] model_file Path of model file, e.g pptracking/model.pdmodel
* \param[in] params_file Path of parameter file, e.g pptracking/model.pdiparams, if the model format is ONNX, this parameter will be ignored
* \param[in] config_file Path of configuration file for deployment, e.g pptracking/infer_cfg.yml
* \param[in] custom_option RuntimeOption for inference, the default will use cpu, and choose the backend defined in `valid_cpu_backends`
* \param[in] model_format Model format of the loaded model, default is Paddle format
*/
PPTracking(const std::string& model_file,
const std::string& params_file,
const std::string& config_file,
const RuntimeOption& custom_option = RuntimeOption(),
const ModelFormat& model_format = ModelFormat::PADDLE);
/// Get model's name
std::string ModelName() const override { return "pptracking"; }
/** \brief Predict the detection result for an input image(consecutive)
*
* \param[in] im The input image data which is consecutive frame, comes from imread() or videoCapture.read()
* \param[in] result The output tracking result will be writen to this structure
* \return true if the prediction successed, otherwise false
*/
virtual bool Predict(cv::Mat* img, MOTResult* result);
private:
bool BuildPreprocessPipelineFromConfig();
bool Initialize();
void GetNmsInfo();
bool Preprocess(Mat* img, std::vector<FDTensor>* outputs);
bool Postprocess(std::vector<FDTensor>& infer_result, MOTResult *result);
std::vector<std::shared_ptr<Processor>> processors_;
std::string config_file_;
float draw_threshold_;
float conf_thresh_;
float tracked_thresh_;
float min_box_area_;
bool is_scale_ = true;
std::unique_ptr<JDETracker> jdeTracker_;
// configuration for nms
int64_t background_label = -1;
int64_t keep_top_k = 300;
float nms_eta = 1.0;
float nms_threshold = 0.7;
float score_threshold = 0.01;
int64_t nms_top_k = 10000;
bool normalized = true;
bool has_nms_ = true;
};
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,31 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "fastdeploy/pybind/main.h"
namespace fastdeploy {
void BindPPTracking(pybind11::module &m) {
pybind11::class_<vision::tracking::PPTracking, FastDeployModel>(
m, "PPTracking")
.def(pybind11::init<std::string, std::string, std::string, RuntimeOption,
ModelFormat>())
.def("predict",
[](vision::tracking::PPTracking &self,
pybind11::array &data) {
auto mat = PyArrayToCvMat(data);
vision::MOTResult *res = new vision::MOTResult();
self.Predict(&mat, res);
return res;
});
}
} // namespace fastdeploy

View File

@@ -0,0 +1,305 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/CnybTseng/JDE/blob/master/platforms/common/jdetracker.cpp
// Ths copyright of CnybTseng/JDE is as follows:
// MIT License
#include <limits.h>
#include <stdio.h>
#include <algorithm>
#include <map>
#include "fastdeploy/vision/tracking/pptracking/lapjv.h"
#include "fastdeploy/vision/tracking/pptracking/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))
namespace fastdeploy {
namespace vision {
namespace tracking {
static std::map<int, float> chi2inv95 = {{1, 3.841459f},
{2, 5.991465f},
{3, 7.814728f},
{4, 9.487729f},
{5, 11.070498f},
{6, 12.591587f},
{7, 14.067140f},
{8, 15.507313f},
{9, 16.918978f}};
JDETracker::JDETracker()
: timestamp(0), max_lost_time(30), lambda(0.98f), det_thresh(0.3f) {}
bool JDETracker::update(const cv::Mat &dets,
const cv::Mat &emb,
std::vector<Track> *tracks) {
++timestamp;
TrajectoryPool candidates(dets.rows);
for (int i = 0; i < dets.rows; ++i) {
float score = *dets.ptr<float>(i, 1);
const cv::Mat &ltrb_ = dets(cv::Rect(2, i, 4, 1));
cv::Vec4f ltrb = mat2vec4f(ltrb_);
const cv::Mat &embedding = emb(cv::Rect(0, i, emb.cols, 1));
candidates[i] = Trajectory(ltrb, score, embedding);
}
TrajectoryPtrPool tracked_trajectories;
TrajectoryPtrPool unconfirmed_trajectories;
for (size_t i = 0; i < this->tracked_trajectories.size(); ++i) {
if (this->tracked_trajectories[i].is_activated)
tracked_trajectories.push_back(&this->tracked_trajectories[i]);
else
unconfirmed_trajectories.push_back(&this->tracked_trajectories[i]);
}
TrajectoryPtrPool trajectory_pool =
tracked_trajectories + &(this->lost_trajectories);
for (size_t i = 0; i < trajectory_pool.size(); ++i)
trajectory_pool[i]->predict();
Match matches;
std::vector<int> mismatch_row;
std::vector<int> mismatch_col;
cv::Mat cost = motion_distance(trajectory_pool, candidates);
linear_assignment(cost, 0.7f, &matches, &mismatch_row, &mismatch_col);
MatchIterator miter;
TrajectoryPtrPool activated_trajectories;
TrajectoryPtrPool retrieved_trajectories;
for (miter = matches.begin(); miter != matches.end(); miter++) {
Trajectory *pt = trajectory_pool[miter->first];
Trajectory &ct = candidates[miter->second];
if (pt->state == Tracked) {
pt->update(&ct, timestamp);
activated_trajectories.push_back(pt);
} else {
pt->reactivate(&ct, count,timestamp);
retrieved_trajectories.push_back(pt);
}
}
TrajectoryPtrPool next_candidates(mismatch_col.size());
for (size_t i = 0; i < mismatch_col.size(); ++i)
next_candidates[i] = &candidates[mismatch_col[i]];
TrajectoryPtrPool next_trajectory_pool;
for (size_t i = 0; i < mismatch_row.size(); ++i) {
int j = mismatch_row[i];
if (trajectory_pool[j]->state == Tracked)
next_trajectory_pool.push_back(trajectory_pool[j]);
}
cost = iou_distance(next_trajectory_pool, next_candidates);
linear_assignment(cost, 0.5f, &matches, &mismatch_row, &mismatch_col);
for (miter = matches.begin(); miter != matches.end(); miter++) {
Trajectory *pt = next_trajectory_pool[miter->first];
Trajectory *ct = next_candidates[miter->second];
if (pt->state == Tracked) {
pt->update(ct, timestamp);
activated_trajectories.push_back(pt);
} else {
pt->reactivate(ct,count, timestamp);
retrieved_trajectories.push_back(pt);
}
}
TrajectoryPtrPool lost_trajectories;
for (size_t i = 0; i < mismatch_row.size(); ++i) {
Trajectory *pt = next_trajectory_pool[mismatch_row[i]];
if (pt->state != Lost) {
pt->mark_lost();
lost_trajectories.push_back(pt);
}
}
TrajectoryPtrPool nnext_candidates(mismatch_col.size());
for (size_t i = 0; i < mismatch_col.size(); ++i)
nnext_candidates[i] = next_candidates[mismatch_col[i]];
cost = iou_distance(unconfirmed_trajectories, nnext_candidates);
linear_assignment(cost, 0.7f, &matches, &mismatch_row, &mismatch_col);
for (miter = matches.begin(); miter != matches.end(); miter++) {
unconfirmed_trajectories[miter->first]->update(
nnext_candidates[miter->second], timestamp);
activated_trajectories.push_back(unconfirmed_trajectories[miter->first]);
}
TrajectoryPtrPool removed_trajectories;
for (size_t i = 0; i < mismatch_row.size(); ++i) {
unconfirmed_trajectories[mismatch_row[i]]->mark_removed();
removed_trajectories.push_back(unconfirmed_trajectories[mismatch_row[i]]);
}
for (size_t i = 0; i < mismatch_col.size(); ++i) {
if (nnext_candidates[mismatch_col[i]]->score < det_thresh) continue;
nnext_candidates[mismatch_col[i]]->activate(count, timestamp);
activated_trajectories.push_back(nnext_candidates[mismatch_col[i]]);
}
for (size_t i = 0; i < this->lost_trajectories.size(); ++i) {
Trajectory &lt = this->lost_trajectories[i];
if (timestamp - lt.timestamp > max_lost_time) {
lt.mark_removed();
removed_trajectories.push_back(&lt);
}
}
TrajectoryPoolIterator piter;
for (piter = this->tracked_trajectories.begin();
piter != this->tracked_trajectories.end();) {
if (piter->state != Tracked)
piter = this->tracked_trajectories.erase(piter);
else
++piter;
}
this->tracked_trajectories += activated_trajectories;
this->tracked_trajectories += retrieved_trajectories;
this->lost_trajectories -= this->tracked_trajectories;
this->lost_trajectories += lost_trajectories;
this->lost_trajectories -= this->removed_trajectories;
this->removed_trajectories += removed_trajectories;
remove_duplicate_trajectory(&this->tracked_trajectories,
&this->lost_trajectories);
tracks->clear();
for (size_t i = 0; i < this->tracked_trajectories.size(); ++i) {
if (this->tracked_trajectories[i].is_activated) {
Track track = {this->tracked_trajectories[i].id,
this->tracked_trajectories[i].score,
this->tracked_trajectories[i].ltrb};
tracks->push_back(track);
}
}
return 0;
}
cv::Mat JDETracker::motion_distance(const TrajectoryPtrPool &a,
const TrajectoryPool &b) {
if (0 == a.size() || 0 == b.size())
return cv::Mat(a.size(), b.size(), CV_32F);
cv::Mat edists = embedding_distance(a, b);
cv::Mat mdists = mahalanobis_distance(a, b);
cv::Mat fdists = lambda * edists + (1 - lambda) * mdists;
const float gate_thresh = chi2inv95[4];
for (int i = 0; i < fdists.rows; ++i) {
for (int j = 0; j < fdists.cols; ++j) {
if (*mdists.ptr<float>(i, j) > gate_thresh)
*fdists.ptr<float>(i, j) = FLT_MAX;
}
}
return fdists;
}
void JDETracker::linear_assignment(const cv::Mat &cost,
float cost_limit,
Match *matches,
std::vector<int> *mismatch_row,
std::vector<int> *mismatch_col) {
matches->clear();
mismatch_row->clear();
mismatch_col->clear();
if (cost.empty()) {
for (int i = 0; i < cost.rows; ++i) mismatch_row->push_back(i);
for (int i = 0; i < cost.cols; ++i) mismatch_col->push_back(i);
return;
}
float opt = 0;
cv::Mat x(cost.rows, 1, CV_32S);
cv::Mat y(cost.cols, 1, CV_32S);
lapjv_internal(cost,
true,
cost_limit,
reinterpret_cast<int *>(x.data),
reinterpret_cast<int *>(y.data));
for (int i = 0; i < x.rows; ++i) {
int j = *x.ptr<int>(i);
if (j >= 0)
matches->insert({i, j});
else
mismatch_row->push_back(i);
}
for (int i = 0; i < y.rows; ++i) {
int j = *y.ptr<int>(i);
if (j < 0) mismatch_col->push_back(i);
}
return;
}
void JDETracker::remove_duplicate_trajectory(TrajectoryPool *a,
TrajectoryPool *b,
float iou_thresh) {
if (a->size() == 0 || b->size() == 0) return;
cv::Mat dist = iou_distance(*a, *b);
cv::Mat mask = dist < iou_thresh;
std::vector<cv::Point> idx;
cv::findNonZero(mask, idx);
std::vector<int> da;
std::vector<int> db;
for (size_t i = 0; i < idx.size(); ++i) {
int ta = (*a)[idx[i].y].timestamp - (*a)[idx[i].y].starttime;
int tb = (*b)[idx[i].x].timestamp - (*b)[idx[i].x].starttime;
if (ta > tb)
db.push_back(idx[i].x);
else
da.push_back(idx[i].y);
}
int id = 0;
TrajectoryPoolIterator piter;
for (piter = a->begin(); piter != a->end();) {
std::vector<int>::iterator iter = find(da.begin(), da.end(), id++);
if (iter != da.end())
piter = a->erase(piter);
else
++piter;
}
id = 0;
for (piter = b->begin(); piter != b->end();) {
std::vector<int>::iterator iter = find(db.begin(), db.end(), id++);
if (iter != db.end())
piter = b->erase(piter);
else
++piter;
}
}
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,78 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/CnybTseng/JDE/blob/master/platforms/common/jdetracker.h
// Ths copyright of CnybTseng/JDE is as follows:
// MIT License
#pragma once
#include <map>
#include <vector>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "fastdeploy/fastdeploy_model.h"
#include "fastdeploy/vision/tracking/pptracking/trajectory.h"
namespace fastdeploy {
namespace vision {
namespace tracking {
typedef std::map<int, int> Match;
typedef std::map<int, int>::iterator MatchIterator;
struct Track {
int id;
float score;
cv::Vec4f ltrb;
};
class FASTDEPLOY_DECL JDETracker {
public:
JDETracker();
virtual bool update(const cv::Mat &dets,
const cv::Mat &emb,
std::vector<Track> *tracks);
virtual ~JDETracker() {}
private:
cv::Mat motion_distance(const TrajectoryPtrPool &a, const TrajectoryPool &b);
void linear_assignment(const cv::Mat &cost,
float cost_limit,
Match *matches,
std::vector<int> *mismatch_row,
std::vector<int> *mismatch_col);
void remove_duplicate_trajectory(TrajectoryPool *a,
TrajectoryPool *b,
float iou_thresh = 0.15f);
private:
int timestamp;
TrajectoryPool tracked_trajectories;
TrajectoryPool lost_trajectories;
TrajectoryPool removed_trajectories;
int max_lost_time;
float lambda;
float det_thresh;
int count = 0;
};
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,519 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/CnybTseng/JDE/blob/master/platforms/common/trajectory.cpp
// Ths copyright of CnybTseng/JDE is as follows:
// MIT License
#include "fastdeploy/vision/tracking/pptracking/trajectory.h"
#include <algorithm>
namespace fastdeploy {
namespace vision {
namespace tracking {
void TKalmanFilter::init(const cv::Mat &measurement) {
measurement.copyTo(statePost(cv::Rect(0, 0, 1, 4)));
statePost(cv::Rect(0, 4, 1, 4)).setTo(0);
statePost.copyTo(statePre);
float varpos = 2 * std_weight_position * (*measurement.ptr<float>(3));
varpos *= varpos;
float varvel = 10 * std_weight_velocity * (*measurement.ptr<float>(3));
varvel *= varvel;
errorCovPost.setTo(0);
*errorCovPost.ptr<float>(0, 0) = varpos;
*errorCovPost.ptr<float>(1, 1) = varpos;
*errorCovPost.ptr<float>(2, 2) = 1e-4f;
*errorCovPost.ptr<float>(3, 3) = varpos;
*errorCovPost.ptr<float>(4, 4) = varvel;
*errorCovPost.ptr<float>(5, 5) = varvel;
*errorCovPost.ptr<float>(6, 6) = 1e-10f;
*errorCovPost.ptr<float>(7, 7) = varvel;
errorCovPost.copyTo(errorCovPre);
}
const cv::Mat &TKalmanFilter::predict() {
float varpos = std_weight_position * (*statePre.ptr<float>(3));
varpos *= varpos;
float varvel = std_weight_velocity * (*statePre.ptr<float>(3));
varvel *= varvel;
processNoiseCov.setTo(0);
*processNoiseCov.ptr<float>(0, 0) = varpos;
*processNoiseCov.ptr<float>(1, 1) = varpos;
*processNoiseCov.ptr<float>(2, 2) = 1e-4f;
*processNoiseCov.ptr<float>(3, 3) = varpos;
*processNoiseCov.ptr<float>(4, 4) = varvel;
*processNoiseCov.ptr<float>(5, 5) = varvel;
*processNoiseCov.ptr<float>(6, 6) = 1e-10f;
*processNoiseCov.ptr<float>(7, 7) = varvel;
return cv::KalmanFilter::predict();
}
const cv::Mat &TKalmanFilter::correct(const cv::Mat &measurement) {
float varpos = std_weight_position * (*measurement.ptr<float>(3));
varpos *= varpos;
measurementNoiseCov.setTo(0);
*measurementNoiseCov.ptr<float>(0, 0) = varpos;
*measurementNoiseCov.ptr<float>(1, 1) = varpos;
*measurementNoiseCov.ptr<float>(2, 2) = 1e-2f;
*measurementNoiseCov.ptr<float>(3, 3) = varpos;
return cv::KalmanFilter::correct(measurement);
}
void TKalmanFilter::project(cv::Mat *mean, cv::Mat *covariance) const {
float varpos = std_weight_position * (*statePost.ptr<float>(3));
varpos *= varpos;
cv::Mat measurementNoiseCov_ = cv::Mat::eye(4, 4, CV_32F);
*measurementNoiseCov_.ptr<float>(0, 0) = varpos;
*measurementNoiseCov_.ptr<float>(1, 1) = varpos;
*measurementNoiseCov_.ptr<float>(2, 2) = 1e-2f;
*measurementNoiseCov_.ptr<float>(3, 3) = varpos;
*mean = measurementMatrix * statePost;
cv::Mat temp = measurementMatrix * errorCovPost;
gemm(temp,
measurementMatrix,
1,
measurementNoiseCov_,
1,
*covariance,
cv::GEMM_2_T);
}
const cv::Mat &Trajectory::predict(void) {
if (state != Tracked) *cv::KalmanFilter::statePost.ptr<float>(7) = 0;
return TKalmanFilter::predict();
}
void Trajectory::update(Trajectory *traj,
int timestamp_,
bool update_embedding_) {
timestamp = timestamp_;
++length;
ltrb = traj->ltrb;
xyah = traj->xyah;
TKalmanFilter::correct(cv::Mat(traj->xyah));
state = Tracked;
is_activated = true;
score = traj->score;
if (update_embedding_) update_embedding(traj->current_embedding);
}
void Trajectory::activate(int &cnt,int timestamp_) {
id = next_id(cnt);
TKalmanFilter::init(cv::Mat(xyah));
length = 0;
state = Tracked;
if (timestamp_ == 1) {
is_activated = true;
}
timestamp = timestamp_;
starttime = timestamp_;
}
void Trajectory::reactivate(Trajectory *traj,int &cnt, int timestamp_, bool newid) {
TKalmanFilter::correct(cv::Mat(traj->xyah));
update_embedding(traj->current_embedding);
length = 0;
state = Tracked;
is_activated = true;
timestamp = timestamp_;
if (newid) id = next_id(cnt);
}
void Trajectory::update_embedding(const cv::Mat &embedding) {
current_embedding = embedding / cv::norm(embedding);
if (smooth_embedding.empty()) {
smooth_embedding = current_embedding;
} else {
smooth_embedding = eta * smooth_embedding + (1 - eta) * current_embedding;
}
smooth_embedding = smooth_embedding / cv::norm(smooth_embedding);
}
TrajectoryPool operator+(const TrajectoryPool &a, const TrajectoryPool &b) {
TrajectoryPool sum;
sum.insert(sum.end(), a.begin(), a.end());
std::vector<int> ids(a.size());
for (size_t i = 0; i < a.size(); ++i) ids[i] = a[i].id;
for (size_t i = 0; i < b.size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), b[i].id);
if (iter == ids.end()) {
sum.push_back(b[i]);
ids.push_back(b[i].id);
}
}
return sum;
}
TrajectoryPool operator+(const TrajectoryPool &a, const TrajectoryPtrPool &b) {
TrajectoryPool sum;
sum.insert(sum.end(), a.begin(), a.end());
std::vector<int> ids(a.size());
for (size_t i = 0; i < a.size(); ++i) ids[i] = a[i].id;
for (size_t i = 0; i < b.size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), b[i]->id);
if (iter == ids.end()) {
sum.push_back(*b[i]);
ids.push_back(b[i]->id);
}
}
return sum;
}
TrajectoryPool &operator+=(TrajectoryPool &a, // NOLINT
const TrajectoryPtrPool &b) {
std::vector<int> ids(a.size());
for (size_t i = 0; i < a.size(); ++i) ids[i] = a[i].id;
for (size_t i = 0; i < b.size(); ++i) {
if (b[i]->smooth_embedding.empty()) continue;
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), b[i]->id);
if (iter == ids.end()) {
a.push_back(*b[i]);
ids.push_back(b[i]->id);
}
}
return a;
}
TrajectoryPool operator-(const TrajectoryPool &a, const TrajectoryPool &b) {
TrajectoryPool dif;
std::vector<int> ids(b.size());
for (size_t i = 0; i < b.size(); ++i) ids[i] = b[i].id;
for (size_t i = 0; i < a.size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), a[i].id);
if (iter == ids.end()) dif.push_back(a[i]);
}
return dif;
}
TrajectoryPool &operator-=(TrajectoryPool &a, // NOLINT
const TrajectoryPool &b) {
std::vector<int> ids(b.size());
for (size_t i = 0; i < b.size(); ++i) ids[i] = b[i].id;
TrajectoryPoolIterator piter;
for (piter = a.begin(); piter != a.end();) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), piter->id);
if (iter == ids.end())
++piter;
else
piter = a.erase(piter);
}
return a;
}
TrajectoryPtrPool operator+(const TrajectoryPtrPool &a,
const TrajectoryPtrPool &b) {
TrajectoryPtrPool sum;
sum.insert(sum.end(), a.begin(), a.end());
std::vector<int> ids(a.size());
for (size_t i = 0; i < a.size(); ++i) ids[i] = a[i]->id;
for (size_t i = 0; i < b.size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), b[i]->id);
if (iter == ids.end()) {
sum.push_back(b[i]);
ids.push_back(b[i]->id);
}
}
return sum;
}
TrajectoryPtrPool operator+(const TrajectoryPtrPool &a, TrajectoryPool *b) {
TrajectoryPtrPool sum;
sum.insert(sum.end(), a.begin(), a.end());
std::vector<int> ids(a.size());
for (size_t i = 0; i < a.size(); ++i) ids[i] = a[i]->id;
for (size_t i = 0; i < b->size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), (*b)[i].id);
if (iter == ids.end()) {
sum.push_back(&(*b)[i]);
ids.push_back((*b)[i].id);
}
}
return sum;
}
TrajectoryPtrPool operator-(const TrajectoryPtrPool &a,
const TrajectoryPtrPool &b) {
TrajectoryPtrPool dif;
std::vector<int> ids(b.size());
for (size_t i = 0; i < b.size(); ++i) ids[i] = b[i]->id;
for (size_t i = 0; i < a.size(); ++i) {
std::vector<int>::iterator iter = find(ids.begin(), ids.end(), a[i]->id);
if (iter == ids.end()) dif.push_back(a[i]);
}
return dif;
}
cv::Mat embedding_distance(const TrajectoryPool &a, const TrajectoryPool &b) {
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
cv::Mat u = a[i].smooth_embedding;
cv::Mat v = b[j].smooth_embedding;
double uv = u.dot(v);
double uu = u.dot(u);
double vv = v.dot(v);
double dist = std::abs(1. - uv / std::sqrt(uu * vv));
// double dist = cv::norm(a[i].smooth_embedding, b[j].smooth_embedding,
// cv::NORM_L2);
distsi[j] = static_cast<float>(std::max(std::min(dist, 2.), 0.));
}
}
return dists;
}
cv::Mat embedding_distance(const TrajectoryPtrPool &a,
const TrajectoryPtrPool &b) {
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
// double dist = cv::norm(a[i]->smooth_embedding, b[j]->smooth_embedding,
// cv::NORM_L2);
// distsi[j] = static_cast<float>(dist);
cv::Mat u = a[i]->smooth_embedding;
cv::Mat v = b[j]->smooth_embedding;
double uv = u.dot(v);
double uu = u.dot(u);
double vv = v.dot(v);
double dist = std::abs(1. - uv / std::sqrt(uu * vv));
distsi[j] = static_cast<float>(std::max(std::min(dist, 2.), 0.));
}
}
return dists;
}
cv::Mat embedding_distance(const TrajectoryPtrPool &a,
const TrajectoryPool &b) {
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
// double dist = cv::norm(a[i]->smooth_embedding, b[j].smooth_embedding,
// cv::NORM_L2);
// distsi[j] = static_cast<float>(dist);
cv::Mat u = a[i]->smooth_embedding;
cv::Mat v = b[j].smooth_embedding;
double uv = u.dot(v);
double uu = u.dot(u);
double vv = v.dot(v);
double dist = std::abs(1. - uv / std::sqrt(uu * vv));
distsi[j] = static_cast<float>(std::max(std::min(dist, 2.), 0.));
}
}
return dists;
}
cv::Mat mahalanobis_distance(const TrajectoryPool &a, const TrajectoryPool &b) {
std::vector<cv::Mat> means(a.size());
std::vector<cv::Mat> icovariances(a.size());
for (size_t i = 0; i < a.size(); ++i) {
cv::Mat covariance;
a[i].project(&means[i], &covariance);
cv::invert(covariance, icovariances[i]);
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Mat x(b[j].xyah);
float dist =
static_cast<float>(cv::Mahalanobis(x, means[i], icovariances[i]));
distsi[j] = dist * dist;
}
}
return dists;
}
cv::Mat mahalanobis_distance(const TrajectoryPtrPool &a,
const TrajectoryPtrPool &b) {
std::vector<cv::Mat> means(a.size());
std::vector<cv::Mat> icovariances(a.size());
for (size_t i = 0; i < a.size(); ++i) {
cv::Mat covariance;
a[i]->project(&means[i], &covariance);
cv::invert(covariance, icovariances[i]);
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Mat x(b[j]->xyah);
float dist =
static_cast<float>(cv::Mahalanobis(x, means[i], icovariances[i]));
distsi[j] = dist * dist;
}
}
return dists;
}
cv::Mat mahalanobis_distance(const TrajectoryPtrPool &a,
const TrajectoryPool &b) {
std::vector<cv::Mat> means(a.size());
std::vector<cv::Mat> icovariances(a.size());
for (size_t i = 0; i < a.size(); ++i) {
cv::Mat covariance;
a[i]->project(&means[i], &covariance);
cv::invert(covariance, icovariances[i]);
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Mat x(b[j].xyah);
float dist =
static_cast<float>(cv::Mahalanobis(x, means[i], icovariances[i]));
distsi[j] = dist * dist;
}
}
return dists;
}
static inline float calc_inter_area(const cv::Vec4f &a, const cv::Vec4f &b) {
if (a[2] < b[0] || a[0] > b[2] || a[3] < b[1] || a[1] > b[3]) return 0.f;
float w = std::min(a[2], b[2]) - std::max(a[0], b[0]);
float h = std::min(a[3], b[3]) - std::max(a[1], b[1]);
return w * h;
}
cv::Mat iou_distance(const TrajectoryPool &a, const TrajectoryPool &b) {
std::vector<float> areaa(a.size());
for (size_t i = 0; i < a.size(); ++i) {
float w = a[i].ltrb[2] - a[i].ltrb[0];
float h = a[i].ltrb[3] - a[i].ltrb[1];
areaa[i] = w * h;
}
std::vector<float> areab(b.size());
for (size_t j = 0; j < b.size(); ++j) {
float w = b[j].ltrb[2] - b[j].ltrb[0];
float h = b[j].ltrb[3] - b[j].ltrb[1];
areab[j] = w * h;
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
const cv::Vec4f &boxa = a[i].ltrb;
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Vec4f &boxb = b[j].ltrb;
float inters = calc_inter_area(boxa, boxb);
distsi[j] = 1.f - inters / (areaa[i] + areab[j] - inters);
}
}
return dists;
}
cv::Mat iou_distance(const TrajectoryPtrPool &a, const TrajectoryPtrPool &b) {
std::vector<float> areaa(a.size());
for (size_t i = 0; i < a.size(); ++i) {
float w = a[i]->ltrb[2] - a[i]->ltrb[0];
float h = a[i]->ltrb[3] - a[i]->ltrb[1];
areaa[i] = w * h;
}
std::vector<float> areab(b.size());
for (size_t j = 0; j < b.size(); ++j) {
float w = b[j]->ltrb[2] - b[j]->ltrb[0];
float h = b[j]->ltrb[3] - b[j]->ltrb[1];
areab[j] = w * h;
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
const cv::Vec4f &boxa = a[i]->ltrb;
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Vec4f &boxb = b[j]->ltrb;
float inters = calc_inter_area(boxa, boxb);
distsi[j] = 1.f - inters / (areaa[i] + areab[j] - inters);
}
}
return dists;
}
cv::Mat iou_distance(const TrajectoryPtrPool &a, const TrajectoryPool &b) {
std::vector<float> areaa(a.size());
for (size_t i = 0; i < a.size(); ++i) {
float w = a[i]->ltrb[2] - a[i]->ltrb[0];
float h = a[i]->ltrb[3] - a[i]->ltrb[1];
areaa[i] = w * h;
}
std::vector<float> areab(b.size());
for (size_t j = 0; j < b.size(); ++j) {
float w = b[j].ltrb[2] - b[j].ltrb[0];
float h = b[j].ltrb[3] - b[j].ltrb[1];
areab[j] = w * h;
}
cv::Mat dists(a.size(), b.size(), CV_32F);
for (size_t i = 0; i < a.size(); ++i) {
const cv::Vec4f &boxa = a[i]->ltrb;
float *distsi = dists.ptr<float>(i);
for (size_t j = 0; j < b.size(); ++j) {
const cv::Vec4f &boxb = b[j].ltrb;
float inters = calc_inter_area(boxa, boxb);
distsi[j] = 1.f - inters / (areaa[i] + areab[j] - inters);
}
}
return dists;
}
} // namespace tracking
} // namespace vision
} // namespace fastdeploy

View File

@@ -0,0 +1,234 @@
// Copyright (c) 2022 PaddlePaddle Authors. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// The code is based on:
// https://github.com/CnybTseng/JDE/blob/master/platforms/common/trajectory.h
// Ths copyright of CnybTseng/JDE is as follows:
// MIT License
#pragma once
#include <vector>
#include "fastdeploy/fastdeploy_model.h"
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include "opencv2/video/tracking.hpp"
namespace fastdeploy {
namespace vision {
namespace tracking {
typedef enum { New = 0, Tracked = 1, Lost = 2, Removed = 3 } TrajectoryState;
class Trajectory;
typedef std::vector<Trajectory> TrajectoryPool;
typedef std::vector<Trajectory>::iterator TrajectoryPoolIterator;
typedef std::vector<Trajectory *> TrajectoryPtrPool;
typedef std::vector<Trajectory *>::iterator TrajectoryPtrPoolIterator;
class FASTDEPLOY_DECL TKalmanFilter : public cv::KalmanFilter {
public:
TKalmanFilter(void);
virtual ~TKalmanFilter(void) {}
virtual void init(const cv::Mat &measurement);
virtual const cv::Mat &predict();
virtual const cv::Mat &correct(const cv::Mat &measurement);
virtual void project(cv::Mat *mean, cv::Mat *covariance) const;
private:
float std_weight_position;
float std_weight_velocity;
};
inline TKalmanFilter::TKalmanFilter(void) : cv::KalmanFilter(8, 4) {
cv::KalmanFilter::transitionMatrix = cv::Mat::eye(8, 8, CV_32F);
for (int i = 0; i < 4; ++i)
cv::KalmanFilter::transitionMatrix.at<float>(i, i + 4) = 1;
cv::KalmanFilter::measurementMatrix = cv::Mat::eye(4, 8, CV_32F);
std_weight_position = 1 / 20.f;
std_weight_velocity = 1 / 160.f;
}
class FASTDEPLOY_DECL Trajectory : public TKalmanFilter {
public:
Trajectory();
Trajectory(const cv::Vec4f &ltrb, float score, const cv::Mat &embedding);
Trajectory(const Trajectory &other);
Trajectory &operator=(const Trajectory &rhs);
virtual ~Trajectory(void) {}
int next_id(int &nt);
virtual const cv::Mat &predict(void);
virtual void update(Trajectory *traj,
int timestamp,
bool update_embedding = true);
virtual void activate(int& cnt, int timestamp);
virtual void reactivate(Trajectory *traj, int & cnt,int timestamp, bool newid = false);
virtual void mark_lost(void);
virtual void mark_removed(void);
friend TrajectoryPool operator+(const TrajectoryPool &a,
const TrajectoryPool &b);
friend TrajectoryPool operator+(const TrajectoryPool &a,
const TrajectoryPtrPool &b);
friend TrajectoryPool &operator+=(TrajectoryPool &a, // NOLINT
const TrajectoryPtrPool &b);
friend TrajectoryPool operator-(const TrajectoryPool &a,
const TrajectoryPool &b);
friend TrajectoryPool &operator-=(TrajectoryPool &a, // NOLINT
const TrajectoryPool &b);
friend TrajectoryPtrPool operator+(const TrajectoryPtrPool &a,
const TrajectoryPtrPool &b);
friend TrajectoryPtrPool operator+(const TrajectoryPtrPool &a,
TrajectoryPool *b);
friend TrajectoryPtrPool operator-(const TrajectoryPtrPool &a,
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 TrajectoryPtrPool &a,
const TrajectoryPtrPool &b);
friend cv::Mat iou_distance(const TrajectoryPtrPool &a,
const TrajectoryPool &b);
private:
void update_embedding(const cv::Mat &embedding);
public:
TrajectoryState state;
cv::Vec4f ltrb;
cv::Mat smooth_embedding;
int id;
bool is_activated;
int timestamp;
int starttime;
float score;
private:
// int count=0;
cv::Vec4f xyah;
cv::Mat current_embedding;
float eta;
int length;
};
inline cv::Vec4f ltrb2xyah(const cv::Vec4f &ltrb) {
cv::Vec4f xyah;
xyah[0] = (ltrb[0] + ltrb[2]) * 0.5f;
xyah[1] = (ltrb[1] + ltrb[3]) * 0.5f;
xyah[3] = ltrb[3] - ltrb[1];
xyah[2] = (ltrb[2] - ltrb[0]) / xyah[3];
return xyah;
}
inline Trajectory::Trajectory()
: state(New),
ltrb(cv::Vec4f()),
smooth_embedding(cv::Mat()),
id(0),
is_activated(false),
timestamp(0),
starttime(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);
update_embedding(embedding);
}
inline Trajectory::Trajectory(const Trajectory &other)
: state(other.state),
ltrb(other.ltrb),
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.current_embedding.copyTo(current_embedding);
// copy state in KalmanFilter
other.statePre.copyTo(cv::KalmanFilter::statePre);
other.statePost.copyTo(cv::KalmanFilter::statePost);
other.errorCovPre.copyTo(cv::KalmanFilter::errorCovPre);
other.errorCovPost.copyTo(cv::KalmanFilter::errorCovPost);
}
inline Trajectory &Trajectory::operator=(const Trajectory &rhs) {
this->state = rhs.state;
this->ltrb = rhs.ltrb;
rhs.smooth_embedding.copyTo(this->smooth_embedding);
this->id = rhs.id;
this->is_activated = rhs.is_activated;
this->timestamp = rhs.timestamp;
this->starttime = rhs.starttime;
this->xyah = rhs.xyah;
this->score = rhs.score;
rhs.current_embedding.copyTo(this->current_embedding);
this->eta = rhs.eta;
this->length = rhs.length;
// copy state in KalmanFilter
rhs.statePre.copyTo(cv::KalmanFilter::statePre);
rhs.statePost.copyTo(cv::KalmanFilter::statePost);
rhs.errorCovPre.copyTo(cv::KalmanFilter::errorCovPre);
rhs.errorCovPost.copyTo(cv::KalmanFilter::errorCovPost);
return *this;
}
inline int Trajectory::next_id(int &cnt) {
++cnt;
return cnt;
}
inline void Trajectory::mark_lost(void) { state = Lost; }
inline void Trajectory::mark_removed(void) { state = Removed; }
} // namespace tracking
} // namespace vision
} // namespace fastdeploy