c4dynamics.filters.ekf.ekf.predict#
- ekf.predict(F: ndarray | None = None, fx: ndarray | None = None, dt=None, u: ndarray | None = None, Q: ndarray | None = None)[source]#
Predicts the next state of the system based on the current state and an optional nonlinear state transition function.
- Parameters:
F (np.ndarray, optional) – The state transition Jacobian matrix. If not provided, the previously set F matrix is used.
fx (np.ndarray, optional) – Nonlinear state transition function derivative. If specified, this value is used for updating the state with nonlinear dynamics.
dt (float, optional) – Time step duration. Must be provided if fx is specified.
u (np.ndarray, optional) – Control input vector, affecting the state based on the G matrix.
Q (np.ndarray, optional) – Process noise covariance matrix, representing uncertainty in the model during prediction.
- Raises:
TypeError – If fx is provided without a corresponding dt value.
Examples
The examples in this section are intended to demonstrate the usage of the ekf class and specifically the predict method. However, they are not limited to nonlinear dynamics. For detailed usage that highlights the properties of nonlinear dynamics, refer to the
filters
module introduction.Import required packages:
>>> from c4dynamics.filters import ekf
Plain predict step (predict in steady-state mode where the process variance matrix remains constant and is provided once to initialize the filter):
>>> _ekf = ekf({'x': 0}, P0 = 0.5**2, F = 1, H = 1, Q = 0.05, R = 200) >>> print(_ekf) [ x ] >>> _ekf.X [0] >>> _ekf.P [[0.25]] >>> _ekf.predict() >>> _ekf.X [0] >>> _ekf.P [[0.3]]
Predict with control input:
>>> _ekf = ekf({'x': 0}, P0 = 0.5**2, F = 1, G = 150, H = 1, R = 200, Q = 0.05) >>> _ekf.X [0] >>> _ekf.P [[0.25]] >>> _ekf.predict(u = 1) >>> _ekf.X [150] >>> _ekf.P [[0.3]]
Predict with updated process noise covariance matrix:
>>> _ekf = ekf({'x': 0}, P0 = 0.5**2, F = 1, G = 150, H = 1, R = 200, Q = 0.05) >>> _ekf.X [0] >>> _ekf.P [[0.25]] >>> _ekf.predict(u = 1, Q = 0.01) >>> _ekf.X [150] >>> _ekf.P [[0.26]]