Struct flydra_types::TrackingParams

source ·
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: 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.

§mini_arena_config: MiniArenaConfig

Parameters defining mini arena configuration.

This is MiniArenaConfig::NoMiniArena if no mini arena is in use.

Trait Implementations§

source§

impl Clone for TrackingParams

source§

fn clone(&self) -> TrackingParams

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for TrackingParams

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl<'de> Deserialize<'de> for TrackingParams

source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl Serialize for TrackingParams

source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for T
where T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for T
where T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T> FromRef<T> for T
where T: Clone,

source§

fn from_ref(input: &T) -> T

Converts to this type from a reference to the input type.
source§

impl<T> Instrument for T

source§

fn instrument(self, span: Span) -> Instrumented<Self>

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

fn in_current_span(self) -> Instrumented<Self>

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

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

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

source§

impl<T> Same for T

§

type Output = T

Should always be Self
source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
source§

impl<T> ToOwned for T
where T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

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

fn clone_into(&self, target: &mut T)

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

impl<T, U> TryFrom<U> for T
where U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

source§

fn vzip(self) -> V

source§

impl<T> WithSubscriber for T

source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

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

fn with_current_subscriber(self) -> WithDispatch<Self>

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

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,