Struct bayes_estimate::estimators::ud::UDState[][src]

pub struct UDState<N: RealField, D: Dim> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
{ pub x: VectorN<N, D>, pub UD: MatrixN<N, D>, // some fields omitted }

UD State representation.

Linear representation as a state vector and ‘square root’ factorisation of the state covariance matrix. Numerically the this ‘square root’ factorisation is advantageous as conditioning for inverting is improved by the square root.

The state covariance is represented as a U.d.U’ factorisation, where U is upper triangular matrix (0 diagonal) and d is a diagonal vector. U and d are packed into a single UD Matrix, the lower Triangle ist not part of state representation.

Fields

x: VectorN<N, D>

State vector

UD: MatrixN<N, D>

UD matrix representation of state covariance

Implementations

impl<N: RealField, D: Dim> UDState<N, D> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
[src]

pub fn new(UD: MatrixN<N, D>, x: VectorN<N, D>) -> Self[src]

Create a UDState for given state dimensions.

D is the size of states vector and rows in UD.

pub fn new_zero(d: D) -> Self[src]

Create a UDState for given state dimensions.

d is the size of states vector and rows in UD.

pub fn predict<QD: Dim>(
    &mut self,
    fx: &MatrixN<N, D>,
    x_pred: &VectorN<N, D>,
    noise: &CoupledNoise<N, D, QD>
) -> Result<N, &'static str> where
    D: DimAdd<QD>,
    DefaultAllocator: Allocator<N, DimSum<D, QD>, U1> + Allocator<N, D, QD> + Allocator<N, QD>, 
[src]

pub fn observe_innovation<ZD: Dim>(
    &mut self,
    hx: &MatrixMN<N, ZD, D>,
    noise: &UncorrelatedNoise<N, ZD>,
    s: &VectorN<N, ZD>
) -> Result<N, &'static str> where
    DefaultAllocator: Allocator<N, ZD, D> + Allocator<N, ZD>, 
[src]

Implement observe using sequential observation updates.

Uncorrelated observations are applied sequentially in the order they appear in z.

Therefore the model of each observation needs to be computed sequentially. Generally this is inefficient and observe (UD_sequential_observe_model&) should be used instead

impl<N: RealField, D: Dim> UDState<N, D> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
[src]

pub fn observe_correlated<ZD: Dim>(
    &mut self,
    z: &VectorN<N, ZD>,
    hx: &MatrixMN<N, ZD, D>,
    h_normalize: fn(_: &mut VectorN<N, ZD>, _: &VectorN<N, ZD>),
    noise_factor: &CorrelatedFactorNoise<N, ZD>
) -> Result<N, &'static str> where
    DefaultAllocator: Allocator<N, ZD, ZD> + Allocator<N, ZD, D> + Allocator<N, ZD>, 
[src]

Special Linear Hx observe for correlated factorised noise.

Applies observations sequentially in the order they appear in z

Return: Minimum rcond of all sequential observe

impl<N: RealField, D: Dim> UDState<N, D> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
[src]

pub fn new_predict_scratch<QD: Dim>(&self, qd: QD) -> PredictScratch<N, D, QD> where
    D: DimAdd<QD>,
    DefaultAllocator: Allocator<N, D, QD> + Allocator<N, DimSum<D, QD>, U1>, 
[src]

pub fn new_observe_scratch(&self) -> ObserveScratch<N, D>[src]

pub fn predict_use_scratch<QD: Dim>(
    &mut self,
    scratch: &mut PredictScratch<N, D, QD>,
    x_pred: &VectorN<N, D>,
    fx: &MatrixN<N, D>,
    noise: &CoupledNoise<N, D, QD>
) -> Result<N, &'static str> where
    D: DimAdd<QD>,
    DefaultAllocator: Allocator<N, DimSum<D, QD>> + Allocator<N, D, QD> + Allocator<N, QD>, 
[src]

pub fn observe_innovation_use_scratch<ZD: Dim>(
    &mut self,
    scratch: &mut ObserveScratch<N, D>,
    s: &VectorN<N, ZD>,
    hx: &MatrixMN<N, ZD, D>,
    noise: &UncorrelatedNoise<N, ZD>
) -> Result<N, &'static str> where
    DefaultAllocator: Allocator<N, ZD, D> + Allocator<N, ZD>, 
[src]

Trait Implementations

impl<N: RealField, D: Dim> Estimator<N, D> for UDState<N, D> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
[src]

impl<N: RealField, D: Dim> KalmanEstimator<N, D> for UDState<N, D> where
    DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, 
[src]

fn init(&mut self, state: &KalmanState<N, D>) -> Result<(), &'static str>[src]

Initialise the UDState with a KalmanState.

The covariance matrix X is factorised into a U.d.U’ as a UD matrix.

fn kalman_state(&self) -> Result<KalmanState<N, D>, &'static str>[src]

Derive the KalmanState from the UDState.

The covariance matrix X is recomposed from U.d.U’ in the UD matrix.

Auto Trait Implementations

impl<N, D> !RefUnwindSafe for UDState<N, D>

impl<N, D> !Send for UDState<N, D>

impl<N, D> !Sync for UDState<N, D>

impl<N, D> !Unpin for UDState<N, D>

impl<N, D> !UnwindSafe for UDState<N, D>

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> Same<T> for T

type Output = T

Should always be Self

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

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

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

The type returned in the event of a conversion error.

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