pub struct TrackingParams {
pub motion_noise_scale: f64,
pub initial_position_std_meters: f64,
pub initial_vel_std_meters_per_sec: f64,
pub ekf_observation_covariance_pixels: f64,
pub accept_observation_min_likelihood: f64,
pub max_position_std_meters: f32,
pub hypothesis_test_params: Option<HypothesisTestParams>,
pub num_observations_to_visibility: u8,
pub mini_arena_config: MiniArenaConfig,
}Expand description
Tracking parameters
The terminology used is as defined at the Wikipedia page on the Kalman filter.
The state estimated is a six component vector with position and velocity x = <x, y, z, x’, y’, z’>. The motion model is a constant velocity model with noise term, (see description).
The state covariance matrix P is initialized with the value (α is
defined in the field TrackingParams::initial_position_std_meters and β is
defined in the field TrackingParams::initial_vel_std_meters_per_sec:
Pinitial = [[α2, 0, 0, 0, 0, 0],
[0, α2, 0, 0, 0, 0],
[0, 0, α2, 0, 0, 0],
[0, 0, 0, β2, 0, 0],
[0, 0, 0, 0, β2, 0],
[0, 0, 0, 0, 0, β2]]
The covariance of the state process update Q(τ) is defined as a function
of τ, the time interval from the previous update):
Q(τ) = TrackingParams::motion_noise_scale [[τ3/3, 0, 0, τ2/2, 0,
0],
[0, τ3/3, 0, 0, τ2/2, 0],
[0, 0, τ3/3, 0, 0, τ2/2],
[τ2/2, 0, 0, τ, 0, 0],
[0, τ2/2, 0, 0, τ, 0],
[0, 0, τ2/2, 0, 0, τ]]
Note that this form of the state process update covariance has the property that 2Q(τ) = Q(2τ). In other words, two successive additions of this covariance will have an identical effect to a single addtion for twice the time interval.
Fields§
§motion_noise_scale: f64This is used to scale the state noise covariance matrix Q as described at the struct-level (Kalman filter parameter).
initial_position_std_meters: f64This is α in the above formula used to build the position terms in the initial estimate covariance matrix P as described at the struct-level (Kalman filter parameter).
initial_vel_std_meters_per_sec: f64This is β in the above formula used to build the velocity terms in the initial estimate covariance matrix P as described at the struct-level (Kalman filter parameter).
ekf_observation_covariance_pixels: f64The observation noise covariance matrix R (Kalman filter parameter).
accept_observation_min_likelihood: f64This sets a minimum threshold for using an obervation to update an object being tracked (data association parameter).
max_position_std_meters: f32This is used to compute the maximum allowable covariance before an object is “killed” and no longer tracked.
hypothesis_test_params: Option<HypothesisTestParams>These are the hypothesis testing parameters used to “birth” a new new object and start tracking it.
This is None if 2D (flat-3d) tracking.
num_observations_to_visibility: u8This is the minimum number of observations before object becomes visible.
mini_arena_config: MiniArenaConfigParameters defining mini arena configuration.
This is MiniArenaConfig::NoMiniArena if no mini arena is in use.
Trait Implementations§
Source§impl Clone for TrackingParams
impl Clone for TrackingParams
Source§fn clone(&self) -> TrackingParams
fn clone(&self) -> TrackingParams
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read more