track.py
Go to the documentation of this file.
00001 # vim: expandtab:ts=4:sw=4
00002 
00003 
00004 class TrackState:
00005     """
00006     Enumeration type for the single target track state. Newly created tracks are
00007     classified as `tentative` until enough evidence has been collected. Then,
00008     the track state is changed to `confirmed`. Tracks that are no longer alive
00009     are classified as `deleted` to mark them for removal from the set of active
00010     tracks.
00011 
00012     """
00013 
00014     Tentative = 1
00015     Confirmed = 2
00016     Deleted = 3
00017 
00018 
00019 class Track:
00020     """
00021     A single target track with state space `(x, y, a, h)` and associated
00022     velocities, where `(x, y)` is the center of the bounding box, `a` is the
00023     aspect ratio and `h` is the height.
00024 
00025     Parameters
00026     ----------
00027     mean : ndarray
00028         Mean vector of the initial state distribution.
00029     covariance : ndarray
00030         Covariance matrix of the initial state distribution.
00031     track_id : int
00032         A unique track identifier.
00033     n_init : int
00034         Number of consecutive detections before the track is confirmed. The
00035         track state is set to `Deleted` if a miss occurs within the first
00036         `n_init` frames.
00037     max_age : int
00038         The maximum number of consecutive misses before the track state is
00039         set to `Deleted`.
00040     feature : Optional[ndarray]
00041         Feature vector of the detection this track originates from. If not None,
00042         this feature is added to the `features` cache.
00043 
00044     Attributes
00045     ----------
00046     mean : ndarray
00047         Mean vector of the initial state distribution.
00048     covariance : ndarray
00049         Covariance matrix of the initial state distribution.
00050     track_id : int
00051         A unique track identifier.
00052     hits : int
00053         Total number of measurement updates.
00054     age : int
00055         Total number of frames since first occurance.
00056     time_since_update : int
00057         Total number of frames since last measurement update.
00058     state : TrackState
00059         The current track state.
00060     features : List[ndarray]
00061         A cache of features. On each measurement update, the associated feature
00062         vector is added to this list.
00063 
00064     """
00065 
00066     def __init__(self, mean, covariance, track_id, n_init, max_age,
00067                  feature=None):
00068         self.mean = mean
00069         self.covariance = covariance
00070         self.track_id = track_id
00071         self.hits = 1
00072         self.age = 1
00073         self.time_since_update = 0
00074 
00075         self.state = TrackState.Tentative
00076         self.features = []
00077         if feature is not None:
00078             self.features.append(feature)
00079 
00080         self._n_init = n_init
00081         self._max_age = max_age
00082 
00083     def to_tlwh(self):
00084         """Get current position in bounding box format `(top left x, top left y,
00085         width, height)`.
00086 
00087         Returns
00088         -------
00089         ndarray
00090             The bounding box.
00091 
00092         """
00093         ret = self.mean[:4].copy()
00094         ret[2] *= ret[3]
00095         ret[:2] -= ret[2:] / 2
00096         return ret
00097 
00098     def to_tlbr(self):
00099         """Get current position in bounding box format `(min x, miny, max x,
00100         max y)`.
00101 
00102         Returns
00103         -------
00104         ndarray
00105             The bounding box.
00106 
00107         """
00108         ret = self.to_tlwh()
00109         ret[2:] = ret[:2] + ret[2:]
00110         return ret
00111 
00112     def predict(self, kf):
00113         """Propagate the state distribution to the current time step using a
00114         Kalman filter prediction step.
00115 
00116         Parameters
00117         ----------
00118         kf : kalman_filter.KalmanFilter
00119             The Kalman filter.
00120 
00121         """
00122         self.mean, self.covariance = kf.predict(self.mean, self.covariance)
00123         self.age += 1
00124         self.time_since_update += 1
00125 
00126     def update(self, kf, detection):
00127         """Perform Kalman filter measurement update step and update the feature
00128         cache.
00129 
00130         Parameters
00131         ----------
00132         kf : kalman_filter.KalmanFilter
00133             The Kalman filter.
00134         detection : Detection
00135             The associated detection.
00136 
00137         """
00138         self.mean, self.covariance = kf.update(
00139             self.mean, self.covariance, detection.to_xyah())
00140         self.features.append(detection.feature)
00141 
00142         self.hits += 1
00143         self.time_since_update = 0
00144         if self.state == TrackState.Tentative and self.hits >= self._n_init:
00145             self.state = TrackState.Confirmed
00146 
00147     def mark_missed(self):
00148         """Mark this track as missed (no association at the current time step).
00149         """
00150         if self.state == TrackState.Tentative:
00151             self.state = TrackState.Deleted
00152         elif self.time_since_update > self._max_age:
00153             self.state = TrackState.Deleted
00154 
00155     def is_tentative(self):
00156         """Returns True if this track is tentative (unconfirmed).
00157         """
00158         return self.state == TrackState.Tentative
00159 
00160     def is_confirmed(self):
00161         """Returns True if this track is confirmed."""
00162         return self.state == TrackState.Confirmed
00163 
00164     def is_deleted(self):
00165         """Returns True if this track is dead and should be deleted."""
00166         return self.state == TrackState.Deleted


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07