Skip to content

Commit

Permalink
Merge pull request #1054 from mikel-brostrom/fix-strong-sort
Browse files Browse the repository at this point in the history
Clean up strong sort
  • Loading branch information
mikel-brostrom authored Aug 7, 2023
2 parents 69527de + 12019c1 commit 937a81e
Show file tree
Hide file tree
Showing 14 changed files with 108 additions and 248 deletions.
8 changes: 3 additions & 5 deletions boxmot/appearance/reid_multibackend.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,9 +284,7 @@ def from_numpy(self, x):
return torch.from_numpy(x).to(self.device) if isinstance(x, np.ndarray) else x

def warmup(self, imgsz=[(256, 128, 3)]):
# Warmup model by running inference once
warmup_types = self.pt, self.jit, self.onnx, self.engine, self.tflite
if any(warmup_types) and self.device.type != "cpu":
# warmup model by running inference once
if self.device.type != "cpu":
im = [np.empty(*imgsz).astype(np.uint8)] # input
for _ in range(2 if self.jit else 1): #
self.forward(im) # warmup
self.forward(im) # warmup
4 changes: 2 additions & 2 deletions boxmot/configs/deepocsort.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# Trial number: 0
# HOTA, MOTA, IDF1: [27.884, 11.425, 21.545]
alpha_fixed_emb: 0.95
asso_func: iou
asso_func: giou
aw_off: false
aw_param: 0.5
cmc_off: false
Expand All @@ -12,6 +12,6 @@ embedding_off: false
inertia: 0.2
iou_thresh: 0.3
max_age: 30
min_hits: 3
min_hits: 1
new_kf_off: false
w_association_emb: 0.75
8 changes: 4 additions & 4 deletions boxmot/configs/ocsort.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
# HOTA, MOTA, IDF1: [55.567]
asso_func: giou
conf_thres: 0.5122620708221085
delta_t: 1
delta_t: 3
det_thresh: 0
inertia: 0.3941737016672115
iou_thresh: 0.22136877277096445
max_age: 50
inertia: 0.2
iou_thresh: 0.3
max_age: 30
min_hits: 1
use_byte: false
11 changes: 5 additions & 6 deletions boxmot/configs/strongsort.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
ecc: true
ema_alpha: 0.8962157769329083
max_age: 40
max_dist: 0.1594374041012136
max_iou_dist: 0.5431835667667874
max_unmatched_preds: 0
ema_alpha: 0.8
max_age: 30
max_dist: 0.2
max_iou_dist: 0.7
mc_lambda: 0.995
n_init: 3
n_init: 1
nn_budget: 100
conf_thres: 0.5122620708221085
1 change: 0 additions & 1 deletion boxmot/tracker_zoo.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ def create_tracker(tracker_type, tracker_config, reid_weights, device, half, per
max_dist=cfg.max_dist,
max_iou_dist=cfg.max_iou_dist,
max_age=cfg.max_age,
max_unmatched_preds=cfg.max_unmatched_preds,
n_init=cfg.n_init,
nn_budget=cfg.nn_budget,
mc_lambda=cfg.mc_lambda,
Expand Down
4 changes: 2 additions & 2 deletions boxmot/trackers/deepocsort/deep_ocsort.py
Original file line number Diff line number Diff line change
Expand Up @@ -341,7 +341,7 @@ def __init__(
self.per_class = per_class
KalmanBoxTracker.count = 0

self.embedder = ReIDDetectMultiBackend(weights=model_weights, device=device, fp16=fp16)
self.model = ReIDDetectMultiBackend(weights=model_weights, device=device, fp16=fp16)
# "similarity transforms using feature point extraction, optical flow, and RANSAC"
self.cmc = get_cmc_method('sof')()
self.embedding_off = embedding_off
Expand Down Expand Up @@ -528,7 +528,7 @@ def _get_features(self, bbox_xyxy, ori_img):
im = ori_img[y1:y2, x1:x2]
im_crops.append(im)
if im_crops:
features = self.embedder(im_crops).cpu()
features = self.model(im_crops).cpu()
else:
features = np.array([])

Expand Down
18 changes: 0 additions & 18 deletions boxmot/trackers/strongsort/sort/detection.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,6 @@ def __init__(self, tlwh, confidence, feature):
self.confidence = float(confidence)
self.feature = np.asarray(feature.cpu(), dtype=np.float32)

def to_tlbr(self):
"""Convert bounding box to format `(min x, min y, max x, max y)`, i.e.,
`(top left, bottom right)`.
"""
ret = self.tlwh.copy()
ret[2:] += ret[:2]
return ret

def to_xyah(self):
"""Convert bounding box to format `(center x, center y, aspect ratio,
height)`, where the aspect ratio is `width / height`.
Expand All @@ -48,13 +40,3 @@ def to_xyah(self):
ret[:2] += ret[2:] / 2
ret[2] /= ret[3]
return ret


def to_xyah_ext(bbox):
"""Convert bounding box to format `(center x, center y, aspect ratio,
height)`, where the aspect ratio is `width / height`.
"""
ret = bbox.copy()
ret[:2] += ret[2:] / 2
ret[2] /= ret[3]
return ret
9 changes: 2 additions & 7 deletions boxmot/trackers/strongsort/sort/linear_assignment.py
Original file line number Diff line number Diff line change
Expand Up @@ -127,11 +127,7 @@ def matching_cascade(

unmatched_detections = detection_indices
matches = []
track_indices_l = [
k
for k in track_indices
# if tracks[k].time_since_update == 1 + level
]
track_indices_l = [k for k in track_indices]
matches_l, _, unmatched_detections = min_cost_matching(
distance_metric,
max_distance,
Expand Down Expand Up @@ -186,8 +182,7 @@ def gate_cost_matrix(
ndarray
Returns the modified cost matrix.
"""
gating_dim = 2 if only_position else 4
gating_threshold = chi2inv95[gating_dim]
gating_threshold = chi2inv95[4]
measurements = np.asarray([detections[i].to_xyah() for i in detection_indices])
for row, track_idx in enumerate(track_indices):
track = tracks[track_idx]
Expand Down
37 changes: 4 additions & 33 deletions boxmot/trackers/strongsort/sort/track.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

import numpy as np

from ....motion.kalman_filters.adapters import StrongSortKalmanFilterAdapter
from boxmot.motion.kalman_filters.adapters import StrongSortKalmanFilterAdapter


class TrackState:
Expand Down Expand Up @@ -85,8 +85,6 @@ def __init__(
self.hits = 1
self.age = 1
self.time_since_update = 0
self.max_num_updates_wo_assignment = 7
self.updates_wo_assignment = 0
self.ema_alpha = ema_alpha

self.state = TrackState.Tentative
Expand Down Expand Up @@ -134,25 +132,13 @@ def to_tlbr(self):
ret[2:] = ret[:2] + ret[2:]
return ret

def get_matrix(self, matrix):
eye = np.eye(3)
dist = np.linalg.norm(eye - matrix)
if dist < 100:
return matrix
else:
return eye

def camera_update(self, warp_matrix):
if warp_matrix is None:
return
[a, b] = warp_matrix
warp_matrix = np.array([a, b, [0, 0, 1]])
warp_matrix = warp_matrix.tolist()
matrix = self.get_matrix(warp_matrix)

x1, y1, x2, y2 = self.to_tlbr()
x1_, y1_, _ = matrix @ np.array([x1, y1, 1]).T
x2_, y2_, _ = matrix @ np.array([x2, y2, 1]).T
x1_, y1_, _ = warp_matrix @ np.array([x1, y1, 1]).T
x2_, y2_, _ = warp_matrix @ np.array([x2, y2, 1]).T
w, h = x2_ - x1_, y2_ - y1_
cx, cy = x1_ + w / 2, y1_ + h / 2
self.mean[:4] = [cx, cy, w / h, h]
Expand All @@ -169,16 +155,6 @@ def predict(self):
self.age += 1
self.time_since_update += 1

def update_kf(self, bbox, confidence=0.5):
self.updates_wo_assignment = self.updates_wo_assignment + 1
self.mean, self.covariance = self.kf.update(
self.mean, self.covariance, bbox, confidence
)
tlbr = self.to_tlbr()
x_c = int((tlbr[0] + tlbr[2]) / 2)
y_c = int((tlbr[1] + tlbr[3]) / 2)
self.q.append(("predupdate", (x_c, y_c)))

def update(self, detection, class_id, conf):
"""Perform Kalman filter measurement update step and update the feature
cache.
Expand All @@ -188,7 +164,7 @@ def update(self, detection, class_id, conf):
The associated detection.
"""
self.conf = conf
self.class_id = class_id.astype("int64")
self.class_id = class_id.astype("int")
self.mean, self.covariance = self.kf.update(
self.mean, self.covariance, detection.to_xyah(), detection.confidence
)
Expand All @@ -206,11 +182,6 @@ def update(self, detection, class_id, conf):
if self.state == TrackState.Tentative and self.hits >= self._n_init:
self.state = TrackState.Confirmed

tlbr = self.to_tlbr()
x_c = int((tlbr[0] + tlbr[2]) / 2)
y_c = int((tlbr[1] + tlbr[3]) / 2)
self.q.append(("observationupdate", (x_c, y_c)))

def mark_missed(self):
"""Mark this track as missed (no association at the current time step)."""
if self.state == TrackState.Tentative:
Expand Down
87 changes: 9 additions & 78 deletions boxmot/trackers/strongsort/sort/tracker.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,10 @@

import numpy as np

from boxmot.motion.cmc.ecc import ECC

from ....utils.matching import chi2inv95
from . import detection, iou_matching, linear_assignment
from .track import Track
from boxmot.motion.cmc import get_cmc_method
from boxmot.trackers.strongsort.sort import iou_matching, linear_assignment
from boxmot.trackers.strongsort.sort.track import Track
from boxmot.utils.matching import chi2inv95


class Tracker:
Expand Down Expand Up @@ -43,7 +42,6 @@ def __init__(
metric,
max_iou_dist=0.9,
max_age=30,
max_unmatched_preds=7,
n_init=3,
_lambda=0,
ema_alpha=0.9,
Expand All @@ -56,11 +54,10 @@ def __init__(
self._lambda = _lambda
self.ema_alpha = ema_alpha
self.mc_lambda = mc_lambda
self.max_unmatched_preds = max_unmatched_preds

self.tracks = []
self._next_id = 1
self.ecc = ECC()
self.cmc = get_cmc_method('ecc')()

def predict(self):
"""Propagate track state distributions one time step forward.
Expand All @@ -75,23 +72,6 @@ def increment_ages(self):
track.increment_age()
track.mark_missed()

def camera_update(self, curr_img):
if len(self.tracks) > 0:
warp_matrix = self.ecc.apply(curr_img=curr_img, dets=None)
for track in self.tracks:
track.camera_update(warp_matrix)

def pred_n_update_all_tracks(self):
"""Perform predictions and updates for all tracks by its own predicted state."""
self.predict()
for t in self.tracks:
if (
self.max_unmatched_preds != 0 and
t.updates_wo_assignment < t.max_num_updates_wo_assignment
):
bbox = t.to_tlwh()
t.update_kf(detection.to_xyah_ext(bbox))

def update(self, detections, classes, confidences):
"""Perform measurement update and track management.
Expand All @@ -113,13 +93,6 @@ def update(self, detections, classes, confidences):
)
for track_idx in unmatched_tracks:
self.tracks[track_idx].mark_missed()
if (
self.max_unmatched_preds != 0 and
self.tracks[track_idx].updates_wo_assignment <
self.tracks[track_idx].max_num_updates_wo_assignment
):
bbox = self.tracks[track_idx].to_tlwh()
self.tracks[track_idx].update_kf(detection.to_xyah_ext(bbox))
for detection_idx in unmatched_detections:
self._initiate_track(
detections[detection_idx],
Expand All @@ -140,39 +113,6 @@ def update(self, detections, classes, confidences):
np.asarray(features), np.asarray(targets), active_targets
)

def _full_cost_metric(self, tracks, dets, track_indices, detection_indices):
"""
This implements the full lambda-based cost-metric. However, in doing so, it disregards
the possibility to gate the position only which is provided by
linear_assignment.gate_cost_matrix(). Instead, I gate by everything.
Note that the Mahalanobis distance is itself an unnormalised metric. Given the cosine
distance being normalised, we employ a quick and dirty normalisation based on the
threshold: that is, we divide the positional-cost by the gating threshold, thus ensuring
that the valid values range 0-1.
Note also that the authors work with the squared distance. I also sqrt this, so that it
is more intuitive in terms of values.
"""
# Compute First the Position-based Cost Matrix
pos_cost = np.empty([len(track_indices), len(detection_indices)])
msrs = np.asarray([dets[i].to_xyah() for i in detection_indices])
for row, track_idx in enumerate(track_indices):
pos_cost[row, :] = (
np.sqrt(tracks[track_idx].kf.gating_distance(msrs)) /
self.GATING_THRESHOLD
)
pos_gate = pos_cost > 1.0
# Now Compute the Appearance-based Cost Matrix
app_cost = self.metric.distance(
np.array([dets[i].feature for i in detection_indices]),
np.array([tracks[i].track_id for i in track_indices]),
)
app_gate = app_cost > self.metric.matching_threshold
# Now combine and threshold
cost_matrix = self._lambda * pos_cost + (1 - self._lambda) * app_cost
cost_matrix[np.logical_or(pos_gate, app_gate)] = linear_assignment.INFTY_COST
# Return Matrix
return cost_matrix

def _match(self, detections):
def gated_metric(tracks, dets, track_indices, detection_indices):
features = np.array([dets[i].feature for i in detection_indices])
Expand All @@ -191,16 +131,10 @@ def gated_metric(tracks, dets, track_indices, detection_indices):

# Split track set into confirmed and unconfirmed tracks.
confirmed_tracks = [i for i, t in enumerate(self.tracks) if t.is_confirmed()]
unconfirmed_tracks = [
i for i, t in enumerate(self.tracks) if not t.is_confirmed()
]
unconfirmed_tracks = [i for i, t in enumerate(self.tracks) if not t.is_confirmed()]

# Associate confirmed tracks using appearance features.
(
matches_a,
unmatched_tracks_a,
unmatched_detections,
) = linear_assignment.matching_cascade(
matches_a, unmatched_tracks_a, unmatched_detections = linear_assignment.matching_cascade(
gated_metric,
self.metric.matching_threshold,
self.max_age,
Expand All @@ -216,11 +150,8 @@ def gated_metric(tracks, dets, track_indices, detection_indices):
unmatched_tracks_a = [
k for k in unmatched_tracks_a if self.tracks[k].time_since_update != 1
]
(
matches_b,
unmatched_tracks_b,
unmatched_detections,
) = linear_assignment.min_cost_matching(

matches_b, unmatched_tracks_b, unmatched_detections = linear_assignment.min_cost_matching(
iou_matching.iou_cost,
self.max_iou_dist,
self.tracks,
Expand Down
Loading

0 comments on commit 937a81e

Please sign in to comment.