tracker.py
Go to the documentation of this file.
1 # vim: expandtab:ts=4:sw=4
2 from __future__ import absolute_import
3 import numpy as np
4 from . import kalman_filter
5 from . import linear_assignment
6 from . import iou_matching
7 from .track import Track
8 
9 
10 class Tracker:
11  """
12  This is the multi-target tracker.
13 
14  Parameters
15  ----------
16  metric : nn_matching.NearestNeighborDistanceMetric
17  A distance metric for measurement-to-track association.
18  max_age : int
19  Maximum number of missed misses before a track is deleted.
20  n_init : int
21  Number of consecutive detections before the track is confirmed. The
22  track state is set to `Deleted` if a miss occurs within the first
23  `n_init` frames.
24 
25  Attributes
26  ----------
27  metric : nn_matching.NearestNeighborDistanceMetric
28  The distance metric used for measurement to track association.
29  max_age : int
30  Maximum number of missed misses before a track is deleted.
31  n_init : int
32  Number of frames that a track remains in initialization phase.
33  kf : kalman_filter.KalmanFilter
34  A Kalman filter to filter target trajectories in image space.
35  tracks : List[Track]
36  The list of active tracks at the current time step.
37 
38  """
39 
40  def __init__(self, metric, max_iou_distance=0.7, max_age=30, n_init=3):
41  self.metric = metric
42  self.max_iou_distance = max_iou_distance
43  self.max_age = max_age
44  self.n_init = n_init
45 
47  self.tracks = []
48  self._next_id = 1
49 
50  def predict(self):
51  """Propagate track state distributions one time step forward.
52 
53  This function should be called once every time step, before `update`.
54  """
55  for track in self.tracks:
56  track.predict(self.kf)
57 
58  def update(self, detections):
59  """Perform measurement update and track management.
60 
61  Parameters
62  ----------
63  detections : List[deep_sort.detection.Detection]
64  A list of detections at the current time step.
65 
66  """
67  # Run matching cascade.
68  matches, unmatched_tracks, unmatched_detections = \
69  self._match(detections)
70 
71  # Update track set.
72  for track_idx, detection_idx in matches:
73  self.tracks[track_idx].update(
74  self.kf, detections[detection_idx])
75  for track_idx in unmatched_tracks:
76  self.tracks[track_idx].mark_missed()
77  for detection_idx in unmatched_detections:
78  self._initiate_track(detections[detection_idx])
79  self.tracks = [t for t in self.tracks if not t.is_deleted()]
80 
81  # Update distance metric.
82  active_targets = [t.track_id for t in self.tracks if t.is_confirmed()]
83  features, targets = [], []
84  for track in self.tracks:
85  if not track.is_confirmed():
86  continue
87  features += track.features
88  targets += [track.track_id for _ in track.features]
89  track.features = []
90  self.metric.partial_fit(
91  np.asarray(features), np.asarray(targets), active_targets)
92 
93  def _match(self, detections):
94 
95  def gated_metric(tracks, dets, track_indices, detection_indices):
96  features = np.array([dets[i].feature for i in detection_indices])
97  targets = np.array([tracks[i].track_id for i in track_indices])
98  cost_matrix = self.metric.distance(features, targets)
99  cost_matrix = linear_assignment.gate_cost_matrix(
100  self.kf, cost_matrix, tracks, dets, track_indices,
101  detection_indices)
102 
103  return cost_matrix
104 
105  # Split track set into confirmed and unconfirmed tracks.
106  confirmed_tracks = [
107  i for i, t in enumerate(self.tracks) if t.is_confirmed()]
108  unconfirmed_tracks = [
109  i for i, t in enumerate(self.tracks) if not t.is_confirmed()]
110 
111  # Associate confirmed tracks using appearance features.
112  matches_a, unmatched_tracks_a, unmatched_detections = \
113  linear_assignment.matching_cascade(
114  gated_metric, self.metric.matching_threshold, self.max_age,
115  self.tracks, detections, confirmed_tracks)
116 
117  # Associate remaining tracks together with unconfirmed tracks using IOU.
118  iou_track_candidates = unconfirmed_tracks + [
119  k for k in unmatched_tracks_a if
120  self.tracks[k].time_since_update == 1]
121  unmatched_tracks_a = [
122  k for k in unmatched_tracks_a if
123  self.tracks[k].time_since_update != 1]
124  matches_b, unmatched_tracks_b, unmatched_detections = \
125  linear_assignment.min_cost_matching(
126  iou_matching.iou_cost, self.max_iou_distance, self.tracks,
127  detections, iou_track_candidates, unmatched_detections)
128 
129  matches = matches_a + matches_b
130  unmatched_tracks = list(set(unmatched_tracks_a + unmatched_tracks_b))
131  return matches, unmatched_tracks, unmatched_detections
132 
133  def _initiate_track(self, detection):
134  mean, covariance = self.kf.initiate(detection.to_xyah())
135  self.tracks.append(Track(
136  mean, covariance, self._next_id, self.n_init, self.max_age,
137  detection.feature))
138  self._next_id += 1
def __init__(self, metric, max_iou_distance=0.7, max_age=30, n_init=3)
Definition: tracker.py:40
def update(self, detections)
Definition: tracker.py:58
def _match(self, detections)
Definition: tracker.py:93
def _initiate_track(self, detection)
Definition: tracker.py:133


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27