Skip to content

Commit

Permalink
Merge pull request ifzhang#166 from chirag4798/main
Browse files Browse the repository at this point in the history
ByteTrack Integration with DeepStream
  • Loading branch information
ifzhang authored Apr 27, 2022
2 parents f1eaccd + 4c27498 commit 7a5507c
Show file tree
Hide file tree
Showing 16 changed files with 1,795 additions and 0 deletions.
25 changes: 25 additions & 0 deletions deploy/DeepStream/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake)
cmake_minimum_required(VERSION 3.16)
set(CMAKE_CUDA_COMPILER /usr/local/cuda/bin/nvcc)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_SOURCE_DIR}/lib)
set(DS_ROOT_DIR /opt/nvidia/deepstream/deepstream)
set(DS_LIBS_DIR ${DS_ROOT_DIR}/lib)
set(DS_INCLUDES_DIR ${DS_ROOT_DIR}/sources/includes)

find_package(GLib)
find_package(OpenCV)

include_directories(${GLIB2_INCLUDE_DIR})
include_directories(${OpenCV_INCLUDE_DIRS})
include_directories(${DS_INCLUDES_DIR})
include_directories(${CMAKE_SOURCE_DIR}/includes)

file(GLOB TRACK ${CMAKE_SOURCE_DIR}/src/*.cpp)

set(CMAKE_CXX_FLAGS "-Wall -Wextra -fPIC")
set(CMAKE_CUDA_FLAGS "--compiler-options -fPIC")

link_directories(${DS_LIBS_DIR})
add_library(ByteTracker SHARED ${TRACK})
target_link_libraries(ByteTracker nvds_meta)
17 changes: 17 additions & 0 deletions deploy/DeepStream/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Byte-Track Integration with Deepstream
Integrating Byte-Track C++ code with the Deepstream-5.1

## Build Instructions
```
$mkdir build && cd build
$cmake ..
$make ByteTracker
```

This will create lib/libByteTracker.so file which can be passed as the custom low level tracker library to deepstream.

## References
1. [How to Implement a Custom Low-Level Tracker Library in Deepstream](https://docs.nvidia.com/metropolis/deepstream/dev-guide/text/DS_plugin_gst-nvtracker.html#how-to-implement-a-custom-low-level-tracker-library)
2. [Byte-Track](https://github.com/ifzhang/ByteTrack)
66 changes: 66 additions & 0 deletions deploy/DeepStream/cmake/FindGLib.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
# - Try to find the GLIB2 libraries
# Once done this will define
#
# GLIB2_FOUND - system has glib2
# GLIB2_INCLUDE_DIR - the glib2 include directory
# GLIB2_LIBRARIES - glib2 library

# Copyright (c) 2008 Laurent Montel, <[email protected]>
#
# Redistribution and use is allowed according to the terms of the BSD license.
# For details see the accompanying COPYING-CMAKE-SCRIPTS file.


if (GLIB2_INCLUDE_DIR AND GLIB2_LIBRARIES)
# Already in cache, be silent
set(GLIB2_FIND_QUIETLY TRUE)
endif (GLIB2_INCLUDE_DIR AND GLIB2_LIBRARIES)

if (NOT WIN32)
find_package(PkgConfig QUIET)
if (PKG_CONFIG_FOUND)
pkg_check_modules(PKG_GLIB QUIET glib-2.0)
endif ()
endif (NOT WIN32)

find_path(GLIB2_MAIN_INCLUDE_DIR glib.h
PATH_SUFFIXES glib-2.0
HINTS ${PKG_GLIB_INCLUDE_DIRS} ${PKG_GLIB_INCLUDEDIR})

# search the glibconfig.h include dir under the same root where the library is found
find_library(GLIB2_LIBRARIES
NAMES glib-2.0
HINTS ${PKG_GLIB_LIBRARY_DIRS} ${PKG_GLIB_LIBDIR})

find_path(GLIB2_INTERNAL_INCLUDE_DIR glibconfig.h
PATH_SUFFIXES glib-2.0/include ../lib/glib-2.0/include
HINTS ${PKG_GLIB_INCLUDE_DIRS} ${PKG_GLIB_LIBRARIES} ${CMAKE_SYSTEM_LIBRARY_PATH})

set(GLIB2_INCLUDE_DIR ${GLIB2_MAIN_INCLUDE_DIR})

# not sure if this include dir is optional or required
# for now it is optional
if (GLIB2_INTERNAL_INCLUDE_DIR)
set(GLIB2_INCLUDE_DIR ${GLIB2_INCLUDE_DIR} ${GLIB2_INTERNAL_INCLUDE_DIR})
endif (GLIB2_INTERNAL_INCLUDE_DIR)

include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(GLIB2 DEFAULT_MSG GLIB2_LIBRARIES GLIB2_MAIN_INCLUDE_DIR)

mark_as_advanced(GLIB2_INCLUDE_DIR GLIB2_LIBRARIES)


find_program(GLIB2_GENMARSHAL_UTIL glib-genmarshal)

macro(glib2_genmarshal output_name)
file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/genmarshal_tmp)
foreach (_declaration ${ARGN})
file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/genmarshal_tmp "${_declaration}\n")
endforeach ()
add_custom_command(
OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/${output_name}.h ${CMAKE_CURRENT_BINARY_DIR}/${output_name}.c
COMMAND ${GLIB2_GENMARSHAL_UTIL} --header genmarshal_tmp > ${output_name}.h
COMMAND ${GLIB2_GENMARSHAL_UTIL} --body genmarshal_tmp > ${output_name}.c
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}
)
endmacro()
61 changes: 61 additions & 0 deletions deploy/DeepStream/includes/BYTETracker.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
#pragma once

#include "STrack.h"
#include "BYTETracker.h"
#include "nvdstracker.h"
#include <map>
#include "DataType.h"
#include <iostream>

class NvObject {
public:
float rect[4];
int label;
float prob;
NvMOTObjToTrack *associatedObjectIn;
};

class BYTETracker {
public:
BYTETracker(int frame_rate = 30, int track_buffer = 30);

~BYTETracker();

vector<STrack> update(const vector<NvObject> &nvObjects);

private:
vector<STrack *> joint_stracks(vector<STrack *> &tlista, vector<STrack> &tlistb);

vector<STrack> joint_stracks(vector<STrack> &tlista, vector<STrack> &tlistb);

vector<STrack> sub_stracks(vector<STrack> &tlista, vector<STrack> &tlistb);

void remove_duplicate_stracks(vector<STrack> &resa, vector<STrack> &resb, vector<STrack> &stracksa,
vector<STrack> &stracksb);

void linear_assignment(vector<vector<float> > &cost_matrix, int cost_matrix_size, int cost_matrix_size_size,
float thresh,
vector<vector<int> > &matches, vector<int> &unmatched_a, vector<int> &unmatched_b);

vector<vector<float>>iou_distance(vector<STrack *> &atracks, vector<STrack> &btracks, int &dist_size, int &dist_size_size);

vector<vector<float>> iou_distance(vector<STrack> &atracks, vector<STrack> &btracks);

vector<vector<float>> ious(vector<vector<float> > &atlbrs, vector<vector<float> > &btlbrs);

double lapjv(const vector<vector<float> > &cost, vector<int> &rowsol, vector<int> &colsol,
bool extend_cost = false, float cost_limit = LONG_MAX, bool return_cost = true);

private:

float track_thresh;
float high_thresh;
float match_thresh;
int frame_id;
int max_time_lost;

vector<STrack> tracked_stracks;
vector<STrack> lost_stracks;
vector<STrack> removed_stracks;
byte_kalman::KalmanFilter kalman_filter;
};
37 changes: 37 additions & 0 deletions deploy/DeepStream/includes/DataType.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#pragma once

#include <cstddef>
#include <vector>

#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Dense>

typedef Eigen::Matrix<float, 1, 4, Eigen::RowMajor> DETECTBOX;
typedef Eigen::Matrix<float, -1, 4, Eigen::RowMajor> DETECTBOXSS;
typedef Eigen::Matrix<float, 1, 128, Eigen::RowMajor> FEATURE;
typedef Eigen::Matrix<float, Eigen::Dynamic, 128, Eigen::RowMajor> FEATURESS;
//typedef std::vector<FEATURE> FEATURESS;

//Kalmanfilter
//typedef Eigen::Matrix<float, 8, 8, Eigen::RowMajor> KAL_FILTER;
typedef Eigen::Matrix<float, 1, 8, Eigen::RowMajor> KAL_MEAN;
typedef Eigen::Matrix<float, 8, 8, Eigen::RowMajor> KAL_COVA;
typedef Eigen::Matrix<float, 1, 4, Eigen::RowMajor> KAL_HMEAN;
typedef Eigen::Matrix<float, 4, 4, Eigen::RowMajor> KAL_HCOVA;
using KAL_DATA = std::pair<KAL_MEAN, KAL_COVA>;
using KAL_HDATA = std::pair<KAL_HMEAN, KAL_HCOVA>;

//main
using RESULT_DATA = std::pair<int, DETECTBOX>;

//tracker:
using TRACKER_DATA = std::pair<int, FEATURESS>;
using MATCH_DATA = std::pair<int, int>;
typedef struct t {
std::vector<MATCH_DATA> matches;
std::vector<int> unmatched_tracks;
std::vector<int> unmatched_detections;
} TRACHER_MATCHD;

//linear_assignment:
typedef Eigen::Matrix<float, -1, -1, Eigen::RowMajor> DYNAMICM;
34 changes: 34 additions & 0 deletions deploy/DeepStream/includes/KalmanFilter.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#pragma once

#include "DataType.h"

namespace byte_kalman {
class KalmanFilter {
public:
static const double chi2inv95[10];

KalmanFilter();

KAL_DATA initiate(const DETECTBOX &measurement);

void predict(KAL_MEAN &mean, KAL_COVA &covariance);

KAL_HDATA project(const KAL_MEAN &mean, const KAL_COVA &covariance);

KAL_DATA update(const KAL_MEAN &mean,
const KAL_COVA &covariance,
const DETECTBOX &measurement);

Eigen::Matrix<float, 1, -1> gating_distance(
const KAL_MEAN &mean,
const KAL_COVA &covariance,
const std::vector<DETECTBOX> &measurements,
bool only_position = false);

private:
Eigen::Matrix<float, 8, 8, Eigen::RowMajor> _motion_mat;
Eigen::Matrix<float, 4, 8, Eigen::RowMajor> _update_mat;
float _std_weight_position;
float _std_weight_velocity;
};
}
65 changes: 65 additions & 0 deletions deploy/DeepStream/includes/Lapjv.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
#ifndef LAPJV_H
#define LAPJV_H

#define LARGE 1000000

#if !defined TRUE
#define TRUE 1
#endif
#if !defined FALSE
#define FALSE 0
#endif

#define NEW(x, t, n) if ((x = (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; }

#if 0
#include <assert.h>
#define ASSERT(cond) assert(cond)
#define PRINTF(fmt, ...) printf(fmt, ##__VA_ARGS__)
#define PRINT_COST_ARRAY(a, n) \
while (1) { \
printf(#a" = ["); \
if ((n) > 0) { \
printf("%f", (a)[0]); \
for (uint_t j = 1; j < n; j++) { \
printf(", %f", (a)[j]); \
} \
} \
printf("]\n"); \
break; \
}
#define PRINT_INDEX_ARRAY(a, n) \
while (1) { \
printf(#a" = ["); \
if ((n) > 0) { \
printf("%d", (a)[0]); \
for (uint_t j = 1; j < n; j++) { \
printf(", %d", (a)[j]); \
} \
} \
printf("]\n"); \
break; \
}
#else
#define ASSERT(cond)
#define PRINTF(fmt, ...)
#define PRINT_COST_ARRAY(a, n)
#define PRINT_INDEX_ARRAY(a, n)
#endif


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;

extern int_t lapjv_internal(
const uint_t n, cost_t *cost[],
int_t *x, int_t *y);

#endif // LAPJV_H
63 changes: 63 additions & 0 deletions deploy/DeepStream/includes/STrack.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
#pragma once
#include <nvdstracker.h>
#include "KalmanFilter.h"

using namespace std;

enum TrackState {
New = 0, Tracked, Lost, Removed
};

class STrack {
public:
STrack(vector<float> tlwh_, float score, int label, NvMOTObjToTrack *associatedObjectIn);

~STrack();

vector<float> static tlbr_to_tlwh(vector<float> &tlbr);

void static multi_predict(vector<STrack *> &stracks, byte_kalman::KalmanFilter &kalman_filter);

void static_tlwh();

void static_tlbr();

vector<float> tlwh_to_xyah(vector<float> tlwh_tmp);

vector<float> to_xyah();

void mark_lost();

void mark_removed();

int next_id();

int end_frame();

void activate(byte_kalman::KalmanFilter &kalman_filter, int frame_id);

void re_activate(STrack &new_track, int frame_id, bool new_id = false);

void update(STrack &new_track, int frame_id);

public:
bool is_activated;
int track_id;
int state;

vector<float> original_tlwh;
vector<float> _tlwh;
vector<float> tlwh;
vector<float> tlbr;
int frame_id;
int tracklet_len;
int start_frame;
int label;
KAL_MEAN mean;
KAL_COVA covariance;
float score;
NvMOTObjToTrack *associatedObjectIn;

private:
byte_kalman::KalmanFilter kalman_filter;
};
Loading

0 comments on commit 7a5507c

Please sign in to comment.