Struct bayes_estimate::models::KalmanState [−][src]
Kalman state.
Linear representation as a state vector and the state covariance (symmetric positive semi-definite) matrix.
Fields
x: VectorN<N, D>
State vector
X: MatrixN<N, D>
State covariance matrix (symmetric positive semi-definite)
Implementations
impl<N: RealField, D: Dim> KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
pub fn new_zero(d: D) -> KalmanState<N, D>
[src]
impl<N: RealField, D: Dim> KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D> + Allocator<N, U1, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D> + Allocator<N, U1, D>,
pub fn predict_unscented(
&mut self,
f: fn(_: &VectorN<N, D>) -> VectorN<N, D>,
noise: &CorrelatedNoise<N, D>,
kappa: N
) -> Result<(), &'static str>
[src]
&mut self,
f: fn(_: &VectorN<N, D>) -> VectorN<N, D>,
noise: &CorrelatedNoise<N, D>,
kappa: N
) -> Result<(), &'static str>
State prediction with a functional prediction model and additive noise.
pub fn observe_unscented<ZD: Dim>(
&mut self,
h: fn(_: &VectorN<N, D>) -> VectorN<N, ZD>,
h_normalise: fn(_: &mut VectorN<N, ZD>, _: &VectorN<N, ZD>),
noise: &CorrelatedNoise<N, ZD>,
s: &VectorN<N, ZD>,
kappa: N
) -> Result<(), &'static str> where
DefaultAllocator: Allocator<N, D, ZD> + Allocator<N, ZD, ZD> + Allocator<N, U1, ZD> + Allocator<N, ZD>,
[src]
&mut self,
h: fn(_: &VectorN<N, D>) -> VectorN<N, ZD>,
h_normalise: fn(_: &mut VectorN<N, ZD>, _: &VectorN<N, ZD>),
noise: &CorrelatedNoise<N, ZD>,
s: &VectorN<N, ZD>,
kappa: N
) -> Result<(), &'static str> where
DefaultAllocator: Allocator<N, D, ZD> + Allocator<N, ZD, ZD> + Allocator<N, U1, ZD> + Allocator<N, ZD>,
Trait Implementations
impl<N: Clone + SimdRealField, D: Clone + Dim> Clone for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
fn clone(&self) -> KalmanState<N, D>
[src]
pub fn clone_from(&mut self, source: &Self)
1.0.0[src]
impl<N: RealField, D: Dim> Estimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
impl<N: RealField, D: Dim, ZD: Dim> ExtendedLinearObserver<N, D, ZD> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, ZD, ZD> + Allocator<N, ZD, D> + Allocator<N, D, ZD> + Allocator<N, D> + Allocator<N, ZD>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, ZD, ZD> + Allocator<N, ZD, D> + Allocator<N, D, ZD> + Allocator<N, D> + Allocator<N, ZD>,
fn observe_innovation(
&mut self,
s: &VectorN<N, ZD>,
hx: &MatrixMN<N, ZD, D>,
noise: &CorrelatedNoise<N, ZD>
) -> Result<(), &'static str>
[src]
&mut self,
s: &VectorN<N, ZD>,
hx: &MatrixMN<N, ZD, D>,
noise: &CorrelatedNoise<N, ZD>
) -> Result<(), &'static str>
impl<N: RealField, D: Dim> ExtendedLinearPredictor<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
fn predict(
&mut self,
x_pred: &VectorN<N, D>,
fx: &MatrixN<N, D>,
noise: &CorrelatedNoise<N, D>
) -> Result<(), &'static str>
[src]
&mut self,
x_pred: &VectorN<N, D>,
fx: &MatrixN<N, D>,
noise: &CorrelatedNoise<N, D>
) -> Result<(), &'static str>
impl<N: RealField, D: Dim> KalmanEstimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
fn init(&mut self, state: &KalmanState<N, D>) -> Result<(), &'static str>
[src]
fn kalman_state(&self) -> Result<KalmanState<N, D>, &'static str>
[src]
impl<N: PartialEq + SimdRealField, D: PartialEq + Dim> PartialEq<KalmanState<N, D>> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
fn eq(&self, other: &KalmanState<N, D>) -> bool
[src]
fn ne(&self, other: &KalmanState<N, D>) -> bool
[src]
impl<N: SimdRealField, D: Dim> StructuralPartialEq for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
Auto Trait Implementations
impl<N, D> !RefUnwindSafe for KalmanState<N, D>
impl<N, D> !Send for KalmanState<N, D>
impl<N, D> !Sync for KalmanState<N, D>
impl<N, D> !Unpin for KalmanState<N, D>
impl<N, D> !UnwindSafe for KalmanState<N, D>
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<T> ToOwned for T where
T: Clone,
[src]
T: Clone,
type Owned = T
The resulting type after obtaining ownership.
pub fn to_owned(&self) -> T
[src]
pub fn clone_into(&self, target: &mut T)
[src]
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
pub fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,