KalmanBBox

Struct KalmanBBox 

Source
pub struct KalmanBBox { /* private fields */ }
Expand description

Implementation of Discrete Kalman filter for bounding box tracking. State vector contains: center_x, center_y, width, height, velocity_cx, velocity_cy, velocity_w, velocity_h

Implementations§

Source§

impl KalmanBBox

Source

pub fn new( dt: f32, u_cx: f32, u_cy: f32, u_w: f32, u_h: f32, std_dev_a: f32, std_dev_m_cx: f32, std_dev_m_cy: f32, std_dev_m_w: f32, std_dev_m_h: f32, ) -> Self

Creates new KalmanBBox

Basic usage:

use kalman_rust::kalman::KalmanBBox;
let dt = 0.04; // Single cycle time (1/25 fps)
let u_cx = 1.0; // Control input for center X
let u_cy = 1.0; // Control input for center Y
let u_w = 0.0; // Control input for width
let u_h = 0.0; // Control input for height
let std_dev_a = 2.0; // Standart deviation of acceleration
let std_dev_m_cx = 0.1; // Standart deviation of measurement for center X
let std_dev_m_cy = 0.1; // Standart deviation of measurement for center Y
let std_dev_m_w = 0.1; // Standart deviation of measurement for width
let std_dev_m_h = 0.1; // Standart deviation of measurement for height
let mut kalman = KalmanBBox::new(dt, u_cx, u_cy, u_w, u_h, std_dev_a, std_dev_m_cx, std_dev_m_cy, std_dev_m_w, std_dev_m_h);
Source

pub fn new_with_state( dt: f32, u_cx: f32, u_cy: f32, u_w: f32, u_h: f32, std_dev_a: f32, std_dev_m_cx: f32, std_dev_m_cy: f32, std_dev_m_w: f32, std_dev_m_h: f32, cx: f32, cy: f32, w: f32, h: f32, ) -> Self

Creates new KalmanBBox with initial state

Why is it needed to set the initial state to the actual first observed bounding box (sometimes)? When the first state vector is initialized with zeros, it assumes that the object is at the origin and the filter needs to estimate the position of the object from scratch, which can result in some initial inaccuracies. On the other hand, initializing the first state vector with the actual observed bounding box can provide a more accurate estimate from the beginning, which can improve the overall tracking performance of the filter

Basic usage:

use kalman_rust::kalman::KalmanBBox;
let dt = 0.04; // Single cycle time (1/25 fps)
let u_cx = 1.0; // Control input for center X
let u_cy = 1.0; // Control input for center Y
let u_w = 0.0; // Control input for width
let u_h = 0.0; // Control input for height
let std_dev_a = 2.0; // Standart deviation of acceleration
let std_dev_m_cx = 0.1; // Standart deviation of measurement for center X
let std_dev_m_cy = 0.1; // Standart deviation of measurement for center Y
let std_dev_m_w = 0.1; // Standart deviation of measurement for width
let std_dev_m_h = 0.1; // Standart deviation of measurement for height
let i_cx = 100.0; // Initial center X
let i_cy = 50.0; // Initial center Y
let i_w = 40.0; // Initial width
let i_h = 80.0; // Initial height
let mut kalman = KalmanBBox::new_with_state(dt, u_cx, u_cy, u_w, u_h, std_dev_a, std_dev_m_cx, std_dev_m_cy, std_dev_m_w, std_dev_m_h, i_cx, i_cy, i_w, i_h);
Source

pub fn predict(&mut self)

Projects the state and the error covariance ahead Mutates the state vector and the error covariance matrix

Basic usage:

use kalman_rust::kalman::KalmanBBox;
let dt = 0.04;
let mut kalman = KalmanBBox::new(dt, 1.0, 1.0, 0.0, 0.0, 2.0, 0.1, 0.1, 0.1, 0.1);
let measurements = vec![(100.0, 50.0, 40.0, 80.0), (102.0, 52.0, 41.0, 81.0)];
for _ in measurements.iter() {
    // get measurement
    kalman.predict();
    // then do update
}
Source

pub fn update( &mut self, _z_cx: f32, _z_cy: f32, _z_w: f32, _z_h: f32, ) -> Result<(), KalmanBBoxError>

Computes the Kalman gain and then updates the state vector and the error covariance matrix Mutates the state vector and the error covariance matrix.

Basic usage:

use kalman_rust::kalman::KalmanBBox;
let dt = 0.04;
let mut kalman = KalmanBBox::new(dt, 1.0, 1.0, 0.0, 0.0, 2.0, 0.1, 0.1, 0.1, 0.1);
let measurements = vec![(100.0, 50.0, 40.0, 80.0), (102.0, 52.0, 41.0, 81.0)];
for (cx, cy, w, h) in measurements.iter() {
    kalman.predict();
    kalman.update(*cx, *cy, *w, *h).unwrap();
}
Source

pub fn get_state(&self) -> (f32, f32, f32, f32)

Returns the current state (only cx, cy, w, h - not velocities)

Source

pub fn get_velocity(&self) -> (f32, f32, f32, f32)

Returns the current velocity (only vx, vy, vw, vh)

Source

pub fn get_predicted_state(&self) -> (f32, f32, f32, f32)

Returns prediction without mutating the state vector and the error covariance matrix

Source

pub fn get_position_uncertainty(&self) -> f32

Returns position uncertainty from P matrix (for center coordinates)

Source

pub fn get_vector_state(&self) -> SVector<f32, 8>

Returns the current state (full 8-element vector)

Source

pub fn mahalanobis_distance_squared( &self, z_cx: f32, z_cy: f32, z_w: f32, z_h: f32, ) -> Result<f32, KalmanBBoxError>

Computes the squared Mahalanobis distance between measurement and predicted state Ref.: Eq.(66)

This is useful for data association in multi-object tracking. A detection passes the gate if mahalanobis_distance_squared < threshold Common threshold for 4 DOF at 95% confidence: 9.488

Source

pub fn mahalanobis_distance( &self, z_cx: f32, z_cy: f32, z_w: f32, z_h: f32, ) -> Result<f32, KalmanBBoxError>

Computes the Mahalanobis distance (square root of squared distance) Ref.: Eq.(67)

Source

pub fn get_innovation_covariance(&self) -> SMatrix<f32, 4, 4>

Returns the innovation covariance matrix S Ref.: Eq.(65)

S = H * P * H^T + R

Source

pub fn gating_check( &self, z_cx: f32, z_cy: f32, z_w: f32, z_h: f32, threshold: f32, ) -> bool

Checks if a measurement passes the gating threshold Ref.: Eq.(70)

Common thresholds for alpha = 0.95:

  • 4 DOF (bounding box): 9.488
  • 2 DOF (position only): 5.991

Trait Implementations§

Source§

impl Clone for KalmanBBox

Source§

fn clone(&self) -> KalmanBBox

Returns a duplicate 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 KalmanBBox

Source§

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

Formats the value using the given formatter. 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> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

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

Source§

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,

Source§

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>,

Source§

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>,

Source§

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.