track.py
Go to the documentation of this file.
1 # vim: expandtab:ts=4:sw=4
2 
3 
4 class TrackState:
5  """
6  Enumeration type for the single target track state. Newly created tracks are
7  classified as `tentative` until enough evidence has been collected. Then,
8  the track state is changed to `confirmed`. Tracks that are no longer alive
9  are classified as `deleted` to mark them for removal from the set of active
10  tracks.
11 
12  """
13 
14  Tentative = 1
15  Confirmed = 2
16  Deleted = 3
17 
18 
19 class Track:
20  """
21  A single target track with state space `(x, y, a, h)` and associated
22  velocities, where `(x, y)` is the center of the bounding box, `a` is the
23  aspect ratio and `h` is the height.
24 
25  Parameters
26  ----------
27  mean : ndarray
28  Mean vector of the initial state distribution.
29  covariance : ndarray
30  Covariance matrix of the initial state distribution.
31  track_id : int
32  A unique track identifier.
33  n_init : int
34  Number of consecutive detections before the track is confirmed. The
35  track state is set to `Deleted` if a miss occurs within the first
36  `n_init` frames.
37  max_age : int
38  The maximum number of consecutive misses before the track state is
39  set to `Deleted`.
40  feature : Optional[ndarray]
41  Feature vector of the detection this track originates from. If not None,
42  this feature is added to the `features` cache.
43 
44  Attributes
45  ----------
46  mean : ndarray
47  Mean vector of the initial state distribution.
48  covariance : ndarray
49  Covariance matrix of the initial state distribution.
50  track_id : int
51  A unique track identifier.
52  hits : int
53  Total number of measurement updates.
54  age : int
55  Total number of frames since first occurance.
56  time_since_update : int
57  Total number of frames since last measurement update.
58  state : TrackState
59  The current track state.
60  features : List[ndarray]
61  A cache of features. On each measurement update, the associated feature
62  vector is added to this list.
63 
64  """
65 
66  def __init__(self, mean, covariance, track_id, n_init, max_age,
67  feature=None):
68  self.mean = mean
69  self.covariance = covariance
70  self.track_id = track_id
71  self.hits = 1
72  self.age = 1
74 
75  self.state = TrackState.Tentative
76  self.features = []
77  if feature is not None:
78  self.features.append(feature)
79 
80  self._n_init = n_init
81  self._max_age = max_age
82 
83  def to_tlwh(self):
84  """Get current position in bounding box format `(top left x, top left y,
85  width, height)`.
86 
87  Returns
88  -------
89  ndarray
90  The bounding box.
91 
92  """
93  ret = self.mean[:4].copy()
94  ret[2] *= ret[3]
95  ret[:2] -= ret[2:] / 2
96  return ret
97 
98  def to_tlbr(self):
99  """Get current position in bounding box format `(min x, miny, max x,
100  max y)`.
101 
102  Returns
103  -------
104  ndarray
105  The bounding box.
106 
107  """
108  ret = self.to_tlwh()
109  ret[2:] = ret[:2] + ret[2:]
110  return ret
111 
112  def predict(self, kf):
113  """Propagate the state distribution to the current time step using a
114  Kalman filter prediction step.
115 
116  Parameters
117  ----------
118  kf : kalman_filter.KalmanFilter
119  The Kalman filter.
120 
121  """
122  self.mean, self.covariance = kf.predict(self.mean, self.covariance)
123  self.age += 1
124  self.time_since_update += 1
125 
126  def update(self, kf, detection):
127  """Perform Kalman filter measurement update step and update the feature
128  cache.
129 
130  Parameters
131  ----------
132  kf : kalman_filter.KalmanFilter
133  The Kalman filter.
134  detection : Detection
135  The associated detection.
136 
137  """
138  self.mean, self.covariance = kf.update(
139  self.mean, self.covariance, detection.to_xyah())
140  self.features.append(detection.feature)
141 
142  self.hits += 1
143  self.time_since_update = 0
144  if self.state == TrackState.Tentative and self.hits >= self._n_init:
145  self.state = TrackState.Confirmed
146 
147  def mark_missed(self):
148  """Mark this track as missed (no association at the current time step).
149  """
150  if self.state == TrackState.Tentative:
151  self.state = TrackState.Deleted
152  elif self.time_since_update > self._max_age:
153  self.state = TrackState.Deleted
154 
155  def is_tentative(self):
156  """Returns True if this track is tentative (unconfirmed).
157  """
158  return self.state == TrackState.Tentative
159 
160  def is_confirmed(self):
161  """Returns True if this track is confirmed."""
162  return self.state == TrackState.Confirmed
163 
164  def is_deleted(self):
165  """Returns True if this track is dead and should be deleted."""
166  return self.state == TrackState.Deleted
def __init__(self, mean, covariance, track_id, n_init, max_age, feature=None)
Definition: track.py:67
def is_deleted(self)
Definition: track.py:164
def to_tlwh(self)
Definition: track.py:83
def to_tlbr(self)
Definition: track.py:98
def is_confirmed(self)
Definition: track.py:160
def update(self, kf, detection)
Definition: track.py:126
def is_tentative(self)
Definition: track.py:155
def mark_missed(self)
Definition: track.py:147
def predict(self, kf)
Definition: track.py:112


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