Tracking
Multi-object track pool with birth, death, and data association
class TrackPool
Track pool: manages multiple IMM estimators keyed by UUID.
Tracks are stored in a contiguous vector, partitioned as
[active | suspended]. `predict()` sweeps only active tracks
via OpenMP; `correct()` updates an arbitrary subset by UUID.
Parameters
----------
models : list
Motion models — same set used for every track's IMMEstimator.
process_noises : list[NDArray]
Per-model process noise covariances.
measurement_noise : NDArray
Shared measurement noise R.
initial_covariance : NDArray
Default P₀ used when adding tracks without explicit covariance.
p_same : float
Markov self-transition probability (default 0.95).
probability_floor : float
Minimum model probability floor (default 0.01).
Properties
states- All track states as (N, StateDim) array.
model_probabilities- All model probabilities as (N, NumModels) array.
track_ids- All track UUIDs (order matches states rows).
active_track_ids- Active track UUIDs only.
active_count- Number of active tracks.
time_mode- Current TimeMode (Unset, Relative, or Absolute).
Constructors
TrackPool.__init____init__( self, models: list, process_noises: list[np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]]], measurement_noise: np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]], initial_covariance: np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]], *, p_same: float = 0.95, probability_floor: float = 0.01 )
Methods
TrackPool.set_time_modeset_time_mode(self, mode) -> None
Pre-declare the time mode (optional — auto-detected on first predict).
Parameters
- mode
- TimeMode.Relative or TimeMode.Absolute.
TrackPool.addadd( self, track_id: str, state: np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]], time: float | datetime.datetime | np.datetime64, covariance: np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]] | None = None ) -> None
Add a new active track with an initial timestamp.
Parameters
----------
track_id : str
Unique UUID for this track.
state : NDArray
Initial state vector.
time : float or datetime or numpy.datetime64
Timestamp of the initial state (epoch seconds).
covariance : NDArray, optional
Initial covariance. Uses the pool default if omitted.
TrackPool.removeremove(self, track_id: str) -> None
Remove a track by UUID.
TrackPool.suspendsuspend(self, track_id: str) -> None
Move a track to the suspended partition (skipped by predict).
TrackPool.resumeresume(self, track_id: str) -> None
Move a suspended track back to active.
TrackPool.predictpredict(self, dt: float | datetime.timedelta | np.timedelta64) -> None
Predict all active tracks forward by dt seconds (Relative mode).
TrackPool.predict_topredict_to(self, timestamp: float | datetime.datetime | np.datetime64) -> None
Predict all active tracks to a target timestamp (Absolute mode).
Computes per-track dt from stored timestamps.
Parameters
- timestamp
- Target time to propagate all active tracks to.
TrackPool.get_snapshot_atget_snapshot_at(self, timestamp: float | datetime.datetime | np.datetime64) -> list
Non-mutating snapshot at a target timestamp (Absolute mode).
Returns a list of StateEstimate without modifying any filter state
or timestamps. Uses projectTo internally for shadow predictions.
Parameters
- timestamp
- Target time for the snapshot.
Returns
List of StateEstimate, one per active track.
TrackPool.correctcorrect( self, track_ids: list[str], measurements: np.ndarray[tuple[Any, ...], np.dtype[~_ScalarT]], *, sensor=None ) -> None
Correct a subset of tracks.
Parameters
----------
track_ids : list[str]
UUIDs of the tracks to update.
measurements : NDArray
(K, MeasDim) — one row per track.
sensor : MeasurementModel, optional
Standalone sensor for multi-sensor correction.
TrackPool.get_estimateget_estimate(self, track_id: str)
Get a StateEstimate for a single track by UUID.
Parameters
- track_id
- UUID of the track.
Returns
StateEstimate with state, covariance, model probabilities, and timestamp.
TrackPool.get_estimatesget_estimates(self) -> list
Get StateEstimates for all active tracks.
Returns
List of StateEstimate, one per active track.
TrackPool.get_timestampsget_timestamps(self) -> list[float]
Get per-track timestamps as a list of epoch seconds.
All tracks have timestamps assigned at creation time.
Returns
List of timestamps as epoch seconds (float).
class StateEstimate
Properties
track_id- (self) -> str
state- (self) -> numpy.ndarray[dtype=float64, shape=(*), order='C']
covariance- (self) -> numpy.ndarray[dtype=float64, shape=(*, *), order='F']
model_probabilities- (self) -> numpy.ndarray[dtype=float64, shape=(*), order='C']
timestamp- (self) -> float
Constructors
StateEstimate.__init____init__(unknown)
__init__(self) -> None
class TimeMode Enum
Members
| Name | Value |
|---|---|
Unset | — |
Relative | — |
Absolute | — |