Struct adskalman::KalmanFilterNoControl
source · pub struct KalmanFilterNoControl<'a, R, SS, OS>{ /* private fields */ }
Expand description
A Kalman filter with no control inputs, a linear process model and linear observation model
Note that the structure is cheap to create, storing only references to the state transition model and the observation model. (The system state is passed as an argument to methods like Self::step.) Given the lifetime bound of this struct, a useful strategy to avoid requiring lifetime annotations is to construct it just before Self::step and then dropping it immediately afterward.
Implementations§
source§impl<'a, R, SS, OS> KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> KalmanFilterNoControl<'a, R, SS, OS>
sourcepub fn new(
transition_model: &'a dyn TransitionModelLinearNoControl<R, SS>,
observation_matrix: &'a dyn ObservationModel<R, SS, OS>
) -> Self
pub fn new( transition_model: &'a dyn TransitionModelLinearNoControl<R, SS>, observation_matrix: &'a dyn ObservationModel<R, SS, OS> ) -> Self
Initialize a new KalmanFilterNoControl
struct.
The first parameter, transition_model
, specifies the state transition
model, including the function F
and the process covariance Q
. The
second parameter, observation_matrix
, specifies the observation model,
including the measurement function H
and the measurement covariance
R
.
sourcepub fn step(
&self,
previous_estimate: &StateAndCovariance<R, SS>,
observation: &OVector<R, OS>
) -> Result<StateAndCovariance<R, SS>, Error>
pub fn step( &self, previous_estimate: &StateAndCovariance<R, SS>, observation: &OVector<R, OS> ) -> Result<StateAndCovariance<R, SS>, Error>
Perform Kalman prediction and update steps with default values
If any component of the observation is NaN (not a number), the observation will not be used but rather the prior will be returned as the posterior without performing the update step.
This calls the prediction step of the transition model and then, if
there is a (non-nan
) observation, calls the update step of the
observation model using the CovarianceUpdateMethod::JosephForm
covariance update method.
This is a convenience method that calls step_with_options.
sourcepub fn step_with_options(
&self,
previous_estimate: &StateAndCovariance<R, SS>,
observation: &OVector<R, OS>,
covariance_update_method: CovarianceUpdateMethod
) -> Result<StateAndCovariance<R, SS>, Error>
pub fn step_with_options( &self, previous_estimate: &StateAndCovariance<R, SS>, observation: &OVector<R, OS>, covariance_update_method: CovarianceUpdateMethod ) -> Result<StateAndCovariance<R, SS>, Error>
Perform Kalman prediction and update steps with default values
If any component of the observation is NaN (not a number), the observation will not be used but rather the prior will be returned as the posterior without performing the update step.
This calls the prediction step of the transition model and then, if
there is a (non-nan
) observation, calls the update step of the
observation model using the specified covariance update method.
sourcepub fn filter_inplace(
&self,
initial_estimate: &StateAndCovariance<R, SS>,
observations: &[OVector<R, OS>],
state_estimates: &mut [StateAndCovariance<R, SS>]
) -> Result<(), Error>
pub fn filter_inplace( &self, initial_estimate: &StateAndCovariance<R, SS>, observations: &[OVector<R, OS>], state_estimates: &mut [StateAndCovariance<R, SS>] ) -> Result<(), Error>
Kalman filter (operates on in-place data without allocating)
Operates on entire time series (by repeatedly calling
step
for each
observation) and returns a vector of state estimates. To be
mathematically correct, the interval between observations must be the
dt
specified in the motion model.
If any observation has a NaN component, it is treated as missing.
sourcepub fn filter(
&self,
initial_estimate: &StateAndCovariance<R, SS>,
observations: &[OVector<R, OS>]
) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
pub fn filter( &self, initial_estimate: &StateAndCovariance<R, SS>, observations: &[OVector<R, OS>] ) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
Kalman filter
This is a convenience function that calls filter_inplace
.
sourcepub fn smooth(
&self,
initial_estimate: &StateAndCovariance<R, SS>,
observations: &[OVector<R, OS>]
) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
pub fn smooth( &self, initial_estimate: &StateAndCovariance<R, SS>, observations: &[OVector<R, OS>] ) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
Rauch-Tung-Striebel (RTS) smoother
Operates on entire time series (by calling
filter
then
smooth_from_filtered
)
and returns a vector of state estimates. To be mathematically correct,
the interval between observations must be the dt
specified in the
motion model.
Operates on entire time series in one shot and returns a vector of state
estimates. To be mathematically correct, the interval between
observations must be the dt
specified in the motion model.
If any observation has a NaN component, it is treated as missing.
sourcepub fn smooth_from_filtered(
&self,
forward_results: Vec<StateAndCovariance<R, SS>>
) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
pub fn smooth_from_filtered( &self, forward_results: Vec<StateAndCovariance<R, SS>> ) -> Result<Vec<StateAndCovariance<R, SS>>, Error>
Rauch-Tung-Striebel (RTS) smoother using already Kalman filtered estimates
Operates on entire time series in one shot and returns a vector of state
estimates. To be mathematically correct, the interval between
observations must be the dt
specified in the motion model.
Auto Trait Implementations§
impl<'a, R, SS, OS> Freeze for KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> !RefUnwindSafe for KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> !Send for KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> !Sync for KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> Unpin for KalmanFilterNoControl<'a, R, SS, OS>
impl<'a, R, SS, OS> !UnwindSafe for KalmanFilterNoControl<'a, R, SS, OS>
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moresource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.