Public Member Functions | Public Attributes | Private Attributes | List of all members
deep_sort.track.Track Class Reference

Public Member Functions

def __init__ (self, mean, covariance, track_id, n_init, max_age, feature=None)
 
def is_confirmed (self)
 
def is_deleted (self)
 
def is_tentative (self)
 
def mark_missed (self)
 
def predict (self, kf)
 
def to_tlbr (self)
 
def to_tlwh (self)
 
def update (self, kf, detection)
 

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 67 of file track.py.

Member Function Documentation

def deep_sort.track.Track.is_confirmed (   self)
Returns True if this track is confirmed.

Definition at line 160 of file track.py.

def deep_sort.track.Track.is_deleted (   self)
Returns True if this track is dead and should be deleted.

Definition at line 164 of file track.py.

def deep_sort.track.Track.is_tentative (   self)
Returns True if this track is tentative (unconfirmed).

Definition at line 155 of file track.py.

def deep_sort.track.Track.mark_missed (   self)
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.

def deep_sort.track.Track.to_tlbr (   self)
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.

def deep_sort.track.Track.to_tlwh (   self)
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

deep_sort.track.Track._max_age
private

Definition at line 81 of file track.py.

deep_sort.track.Track._n_init
private

Definition at line 80 of file track.py.

deep_sort.track.Track.age

Definition at line 72 of file track.py.

deep_sort.track.Track.covariance

Definition at line 69 of file track.py.

deep_sort.track.Track.features

Definition at line 76 of file track.py.

deep_sort.track.Track.hits

Definition at line 71 of file track.py.

deep_sort.track.Track.mean

Definition at line 68 of file track.py.

deep_sort.track.Track.state

Definition at line 75 of file track.py.

deep_sort.track.Track.time_since_update

Definition at line 73 of file track.py.

deep_sort.track.Track.track_id

Definition at line 70 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 Mon May 3 2021 03:03:27