Public Member Functions | Public Attributes | Private Attributes
deep_sort.track.Track Class Reference

List of all members.

Public Member Functions

def __init__
def is_confirmed
def is_deleted
def is_tentative
def mark_missed
def predict
def to_tlbr
def to_tlwh
def update

Public Attributes

 age
 covariance
 features
 hits
 mean
 state
 time_since_update
 track_id

Private Attributes

 _max_age
 _n_init

Detailed Description

A single target track with state space `(x, y, a, h)` and associated
velocities, where `(x, y)` is the center of the bounding box, `a` is the
aspect ratio and `h` is the height.

Parameters
----------
mean : ndarray
    Mean vector of the initial state distribution.
covariance : ndarray
    Covariance matrix of the initial state distribution.
track_id : int
    A unique track identifier.
n_init : int
    Number of consecutive detections before the track is confirmed. The
    track state is set to `Deleted` if a miss occurs within the first
    `n_init` frames.
max_age : int
    The maximum number of consecutive misses before the track state is
    set to `Deleted`.
feature : Optional[ndarray]
    Feature vector of the detection this track originates from. If not None,
    this feature is added to the `features` cache.

Attributes
----------
mean : ndarray
    Mean vector of the initial state distribution.
covariance : ndarray
    Covariance matrix of the initial state distribution.
track_id : int
    A unique track identifier.
hits : int
    Total number of measurement updates.
age : int
    Total number of frames since first occurance.
time_since_update : int
    Total number of frames since last measurement update.
state : TrackState
    The current track state.
features : List[ndarray]
    A cache of features. On each measurement update, the associated feature
    vector is added to this list.

Definition at line 19 of file track.py.


Constructor & Destructor Documentation

def deep_sort.track.Track.__init__ (   self,
  mean,
  covariance,
  track_id,
  n_init,
  max_age,
  feature = None 
)

Definition at line 66 of file track.py.


Member Function Documentation

Returns True if this track is confirmed.

Definition at line 160 of file track.py.

Returns True if this track is dead and should be deleted.

Definition at line 164 of file track.py.

Returns True if this track is tentative (unconfirmed).

Definition at line 155 of file track.py.

Mark this track as missed (no association at the current time step).

Definition at line 147 of file track.py.

def deep_sort.track.Track.predict (   self,
  kf 
)
Propagate the state distribution to the current time step using a
Kalman filter prediction step.

Parameters
----------
kf : kalman_filter.KalmanFilter
    The Kalman filter.

Definition at line 112 of file track.py.

Get current position in bounding box format `(min x, miny, max x,
max y)`.

Returns
-------
ndarray
    The bounding box.

Definition at line 98 of file track.py.

Get current position in bounding box format `(top left x, top left y,
width, height)`.

Returns
-------
ndarray
    The bounding box.

Definition at line 83 of file track.py.

def deep_sort.track.Track.update (   self,
  kf,
  detection 
)
Perform Kalman filter measurement update step and update the feature
cache.

Parameters
----------
kf : kalman_filter.KalmanFilter
    The Kalman filter.
detection : Detection
    The associated detection.

Definition at line 126 of file track.py.


Member Data Documentation

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.

Definition at line 66 of file track.py.


The documentation for this class was generated from the following file:


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