Struct bayes_estimate::models::KalmanState [−][src]
pub struct KalmanState<N: SimdRealField, D: Dim> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>, { pub x: OVector<N, D>, pub X: OMatrix<N, D, D>, }
Expand description
Kalman state.
Linear representation as a state vector and the state covariance (symmetric positive semi-definite) matrix.
Fields
x: OVector<N, D>
State vector
X: OMatrix<N, D, 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]
impl<N: RealField, D: Dim> KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]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]
impl<N: RealField, D: Dim> KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D> + Allocator<N, U1, D>,
[src]pub fn predict_unscented(
&mut self,
f: fn(_: &OVector<N, D>) -> OVector<N, D>,
noise: &CorrelatedNoise<N, D>,
kappa: N
) -> Result<(), &'static str>
[src]
pub fn predict_unscented(
&mut self,
f: fn(_: &OVector<N, D>) -> OVector<N, D>,
noise: &CorrelatedNoise<N, D>,
kappa: N
) -> Result<(), &'static str>
[src]State prediction with a functional prediction model and additive noise.
pub fn observe_unscented<ZD: Dim>(
&mut self,
h: fn(_: &OVector<N, D>) -> OVector<N, ZD>,
h_normalise: fn(_: &mut OVector<N, ZD>, _: &OVector<N, ZD>),
noise: &CorrelatedNoise<N, ZD>,
s: &OVector<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(_: &OVector<N, D>) -> OVector<N, ZD>,
h_normalise: fn(_: &mut OVector<N, ZD>, _: &OVector<N, ZD>),
noise: &CorrelatedNoise<N, ZD>,
s: &OVector<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]
impl<N: Clone + SimdRealField, D: Clone + Dim> Clone for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]fn clone(&self) -> KalmanState<N, D>
[src]
fn clone(&self) -> KalmanState<N, D>
[src]Returns a copy of the value. Read more
fn clone_from(&mut self, source: &Self)
1.0.0[src]
fn clone_from(&mut self, source: &Self)
1.0.0[src]Performs copy-assignment from source
. Read more
impl<N: RealField, D: Dim> Estimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
impl<N: RealField, D: Dim> Estimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]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]
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]fn observe_innovation(
&mut self,
s: &OVector<N, ZD>,
hx: &OMatrix<N, ZD, D>,
noise: &CorrelatedNoise<N, ZD>
) -> Result<(), &'static str>
[src]
fn observe_innovation(
&mut self,
s: &OVector<N, ZD>,
hx: &OMatrix<N, ZD, D>,
noise: &CorrelatedNoise<N, ZD>
) -> Result<(), &'static str>
[src]Uses a non-linear state observation with linear estimation model with additive noise.
impl<N: RealField, D: Dim> ExtendedLinearPredictor<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
impl<N: RealField, D: Dim> ExtendedLinearPredictor<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]impl<N: RealField, D: Dim> KalmanEstimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]
impl<N: RealField, D: Dim> KalmanEstimator<N, D> for KalmanState<N, D> where
DefaultAllocator: Allocator<N, D, D> + Allocator<N, D>,
[src]fn init(&mut self, state: &KalmanState<N, D>) -> Result<(), &'static str>
[src]
fn init(&mut self, state: &KalmanState<N, D>) -> Result<(), &'static str>
[src]Initialise the estimator with a KalmanState.
fn kalman_state(&self) -> Result<KalmanState<N, D>, &'static str>
[src]
fn kalman_state(&self) -> Result<KalmanState<N, D>, &'static str>
[src]The estimator’s estimate of the system’s KalmanState.
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]
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]fn eq(&self, other: &KalmanState<N, D>) -> bool
[src]
fn eq(&self, other: &KalmanState<N, D>) -> bool
[src]This method tests for self
and other
values to be equal, and is used
by ==
. Read more
fn ne(&self, other: &KalmanState<N, D>) -> bool
[src]
fn ne(&self, other: &KalmanState<N, D>) -> bool
[src]This method tests for !=
.
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> BorrowMut<T> for T where
T: ?Sized,
[src]
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]pub fn borrow_mut(&mut self) -> &mut T
[src]
pub fn borrow_mut(&mut self) -> &mut T
[src]Mutably borrows from an owned value. Read more
impl<T> Same<T> for T
impl<T> Same<T> for T
type Output = T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.
impl<T> ToOwned for T where
T: Clone,
[src]
impl<T> ToOwned for T where
T: Clone,
[src]type Owned = T
type Owned = T
The resulting type after obtaining ownership.
pub fn to_owned(&self) -> T
[src]
pub fn to_owned(&self) -> T
[src]Creates owned data from borrowed data, usually by cloning. Read more
pub fn clone_into(&self, target: &mut T)
[src]
pub fn clone_into(&self, target: &mut T)
[src]🔬 This is a nightly-only experimental API. (toowned_clone_into
)
recently added
Uses borrowed data to replace owned data, usually by cloning. Read more
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
impl<V, T> VZip<V> for T where
V: MultiLane<T>,