Public Member Functions | |
def | __init__ |
def | gating_distance |
def | initiate |
def | predict |
def | project |
def | update |
Private Attributes | |
_motion_mat | |
_std_weight_position | |
_std_weight_velocity | |
_update_mat |
A simple Kalman filter for tracking bounding boxes in image space. The 8-dimensional state space x, y, a, h, vx, vy, va, vh contains the bounding box center position (x, y), aspect ratio a, height h, and their respective velocities. Object motion follows a constant velocity model. The bounding box location (x, y, a, h) is taken as direct observation of the state space (linear observation model).
Definition at line 23 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.__init__ | ( | self | ) |
Definition at line 40 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.gating_distance | ( | self, | |
mean, | |||
covariance, | |||
measurements, | |||
only_position = False |
|||
) |
Compute gating distance between state distribution and measurements. A suitable distance threshold can be obtained from `chi2inv95`. If `only_position` is False, the chi-square distribution has 4 degrees of freedom, otherwise 2. Parameters ---------- mean : ndarray Mean vector over the state distribution (8 dimensional). covariance : ndarray Covariance of the state distribution (8x8 dimensional). measurements : ndarray An Nx4 dimensional matrix of N measurements, each in format (x, y, a, h) where (x, y) is the bounding box center position, a the aspect ratio, and h the height. only_position : Optional[bool] If True, distance computation is done with respect to the bounding box center position only. Returns ------- ndarray Returns an array of length N, where the i-th element contains the squared Mahalanobis distance between (mean, covariance) and `measurements[i]`.
Definition at line 188 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.initiate | ( | self, | |
measurement | |||
) |
Create track from unassociated measurement. Parameters ---------- measurement : ndarray Bounding box coordinates (x, y, a, h) with center position (x, y), aspect ratio a, and height h. Returns ------- (ndarray, ndarray) Returns the mean vector (8 dimensional) and covariance matrix (8x8 dimensional) of the new track. Unobserved velocities are initialized to 0 mean.
Definition at line 55 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.predict | ( | self, | |
mean, | |||
covariance | |||
) |
Run Kalman filter prediction step. Parameters ---------- mean : ndarray The 8 dimensional mean vector of the object state at the previous time step. covariance : ndarray The 8x8 dimensional covariance matrix of the object state at the previous time step. Returns ------- (ndarray, ndarray) Returns the mean vector and covariance matrix of the predicted state. Unobserved velocities are initialized to 0 mean.
Definition at line 88 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.project | ( | self, | |
mean, | |||
covariance | |||
) |
Project state distribution to measurement space. Parameters ---------- mean : ndarray The state's mean vector (8 dimensional array). covariance : ndarray The state's covariance matrix (8x8 dimensional). Returns ------- (ndarray, ndarray) Returns the projected mean and covariance matrix of the given state estimate.
Definition at line 125 of file kalman_filter.py.
def deep_sort.kalman_filter.KalmanFilter.update | ( | self, | |
mean, | |||
covariance, | |||
measurement | |||
) |
Run Kalman filter correction step. Parameters ---------- mean : ndarray The predicted state's mean vector (8 dimensional). covariance : ndarray The state's covariance matrix (8x8 dimensional). measurement : ndarray The 4 dimensional measurement vector (x, y, a, h), where (x, y) is the center position, a the aspect ratio, and h the height of the bounding box. Returns ------- (ndarray, ndarray) Returns the measurement-corrected state distribution.
Definition at line 154 of file kalman_filter.py.
Definition at line 40 of file kalman_filter.py.
Definition at line 40 of file kalman_filter.py.
Definition at line 40 of file kalman_filter.py.
Definition at line 40 of file kalman_filter.py.