Kalman Linker
Implementation of SKT from [9]
- class byotrack.implementation.linker.frame_by_frame.kalman_linker.Cost(value)
Bases:
EnumThe cost to use for association
- LIKELIHOOD
Build the cost matrix to maximize the likelihood of the association. The cost is defined as: the negative log likelihood that the detections j is from track i. C[i, j] = - log P(det_j | track_i) The cost limit is expected to be the smallest probability to accept.
- MAHALANOBIS
Mahalanobis distance, using the track uncertainty to correct the euclidean distance. The cost limit is expected to be the largest Mahalanobis distance to accept.
- MAHALANOBIS_SQ
Squared Mahalanobis distance. The cost limit is expected to be the largest Mahalanobis distance to accept. (not squared)
- EUCLIDEAN
Euclidean distance. The cost limit is expected to be the largest Euclidean distance to accept.
- EUCLIDEAN_SQ
Squared euclidean distance. The cost limit is expected to be the largest Euclidean distance to accept. (not squared)
- class byotrack.implementation.linker.frame_by_frame.kalman_linker.TrackBuilding(value)
Bases:
EnumHow to build the final tracks
- DETECTION
Build tracks from detections without filtering nor filling gaps
- FILTERED
Build tracks from the Kalman filter outputs
- SMOOTHED
Add a backward run of the Kalman filter (RTS) to smooth tracks position
- class byotrack.implementation.linker.frame_by_frame.kalman_linker.KalmanLinkerParameters(association_threshold: float = 5.0, *, detection_std: float | Tensor = 3.0, process_std: float | Tensor = 1.5, kalman_order: int = 1, n_valid=3, n_gap=3, association_method: str | AssociationMethod = AssociationMethod.OPT_SMOOTH, cost: str | Cost = Cost.EUCLIDEAN, track_building: str | TrackBuilding = TrackBuilding.FILTERED)
Bases:
FrameByFrameLinkerParametersParameters of KalmanLinker
- association_threshold
This is the main hyperparameter, it defines the threshold on the distance used not to link tracks with detections. It prevents to link with false positive detections. Default: 5 pixels
- Type:
- detection_std
Expected measurement noise on the detection process. The detection process is modeled with a Gaussian noise with this given std. (You can provide a different noise for each dimension). See torch_kf.ckf.constant_kalman_filter. Default: 3.0 pixels
- Type:
Union[float, torch.Tensor]
- process_std
Expect process noise. See torch_kf.ckf.constant_kalman_filter, the process is modeled as constant order-th derivative motion. This quantify how much the supposely “constant” order-th derivative can change between two consecutive frames. A common rule of thumb is to use 3 * process_std ~= max_t(| x^(order)(t) - x^(order)(t+1)|). It can be provided for each dimension). Default: 1.5 pixels / frame^order
- Type:
Union[float, torch.Tensor]
- kalman_order
Order of the Kalman filter to use. 0 for brownian motions, 1 for directed brownian motion, 2 for accelerated brownian motions, etc… Default: 1
- Type:
- n_valid
Number of frames with a correct association required to validate the track at its creation. Default: 3
- Type:
- association_method
The frame-by-frame association to use. See AssociationMethod. It can be provided as a string. (Choice: GREEDY, OPT_HARD, OPT_SMOOTH) Default: OPT_SMOOTH
- Type:
- cost_method
The cost method to use. It can be provided as a string. See CostMethod. It also indicates what is the correct unit of association_threshold. Default: EUCLIDEAN
- Type:
CostMethod
- track_building
Tells the linker how to build the final tracks. Either from detections, or from filtered/smoothed positions computed by the Kalman filter. See TrackBuilding. It can be provided as a string. Default: FILTERED
- Type:
- class byotrack.implementation.linker.frame_by_frame.kalman_linker.KalmanLinker(specs: KalmanLinkerParameters, optflow: OpticalFlow | None = None, features_extractor: FeaturesExtractor | None = None, save_all=False)
Bases:
FrameByFrameLinkerFrame by frame linker using Kalman filters
Motion is modeled with a Kalman filter of a specified order (See torch_kf.ckf) Matching is done to optimize the given cost. If optical flow is provided, it is used online to warp the predicted state positions of the kalman filter. This will work, but it is sub-optimal: consider using KOFTLinker that exploits in a finer way optical flow inside Kalman filters.
This is an implementation of Simple Kalman Tracking (SKT) from KOFT [9].
Note
This implementation requires torch-kf. (pip install torch-kf)
See FrameByFrameLinker for the other attributes.
- specs
Parameters specifications of the algorithm. See KalmanLinkerParameters.
- Type:
- kalman_filter
The Kalman filter. (Build once the tracking starts allowing to adapt the dimension on the fly)
- Type:
Optional[torch_kf.KalmanFilter]
- active_states
The Kalman filter estimation for each track. Shape: mean=(N, D * (order + 1), 1), covariance=(N, D * (order + 1), dim * (order + 1)) dtype: float32
- Type:
Optional[torch_kf.GaussianState]
- projections
The Kalman filter projection for each track. Shape: mean=(N, D, 1), covariance=(N, D, D), precision=(N, D, D) dtype: float32
- Type:
Optional[torch_kf.GaussianState]
- all_states
The Kalman filter estimation for each track at each seen frame. States are only registered when save_all=True or if you build tracks from RTS smoothing. Shape: mean=(N, D * (order + 1), 1), covariance=(N, D * (order + 1), dim * (order + 1)) dtype: float32
- Type:
List[torch_kf.GaussianState]
- reset() None
Reset the linking algorithm
Flush all data stored from a previous linking and prepare a new linking
- collect() List[Track]
Collect and build all the tracks up to the last given frame
- Returns:
Tracks from the last reset to the last given frame.
- Return type:
Collection[byotrack.Track]
- motion_model() None
Optional modelisation of motion for tracks
It can be used to update some internal state of the tracker after the optical flow computation and before the distance computation.
- cost(_: ndarray, detections: Detections) Tuple[Tensor, float]
Compute the association cost between active tracks and detections
It also returns the threshold to use (Depending on the dist you use, association_threshold could be related to a more meaning full quantity than the cost itself). For instance, when using a squared Euclidean distance, the association threshold could be express as the distance in pixel, and this function could square it. For likelihood association, you could provide the association threshold as a probability and use -log(threshold) as the true threshold. (See KalmanLinker and NearestNeighborLinker)
- Parameters:
frame (np.ndarray) – The current frame of the video Shape: (H, W, C), dtype: float
detections (byotrack.Detections) – Detections for the given frame
- Returns:
- The cost matrix between active tracks and detections
Shape: (n_tracks, n_dets), dtype: float32
- float: The association threshold to use.
It can be different than self.association_threshold depeding on the dist build here
- Return type:
torch.Tensor
- post_association(_: ndarray, detections: Detections, links: Tensor)
Update the tracks and the internal variables of the tracker
It should call the update method of each active tracks and update any internal model/data. It should also create new track handlers for each extra detection. Finally, it is also responsible to register the position of each active track in all_positions for the current time frame.
- Parameters:
frame (np.ndarray) – The current frame of the video Shape: (H, W, C), dtype: float
detections (byotrack.Detections) – Detections for the given frame
links (torch.Tensor) – The links made between active tracks and the detections Shape: (L, 2), dtype: int32