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,
}
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: f64

This is used to scale the state noise covariance matrix Q as described at the struct-level (Kalman filter parameter).

initial_position_std_meters: f64

This 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: f64

This 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: f64

The observation noise covariance matrix R (Kalman filter parameter).

accept_observation_min_likelihood: f64

This sets a minimum threshold for using an obervation to update an object being tracked (data association parameter).

max_position_std_meters: f32

This 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: u8

This is the minimum number of observations before object becomes visible.

Trait Implementations

Returns a copy of the value. Read more

Performs copy-assignment from source. Read more

Formats the value using the given formatter. Read more

Deserialize this value from the given Serde deserializer. Read more

Serialize this value into the given Serde serializer. Read more

Auto Trait Implementations

Blanket Implementations

Gets the TypeId of self. Read more

Immutably borrows from an owned value. Read more

Mutably borrows from an owned value. Read more

Returns the argument unchanged.

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more

Instruments this type with the current Span, returning an Instrumented wrapper. Read more

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

The resulting type after obtaining ownership.

Creates owned data from borrowed data, usually by cloning. Read more

🔬 This is a nightly-only experimental API. (toowned_clone_into)

Uses borrowed data to replace owned data, usually by cloning. Read more

The type returned in the event of a conversion error.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more