Functions | |
Eigen::MatrixXd | SteadyStateKalmanFilter (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &C, const Eigen::Ref< const Eigen::MatrixXd > &W, const Eigen::Ref< const Eigen::MatrixXd > &V) |
Computes the optimal observer gain, L, for the continuous-time linear system defined by \[ \dot{x} = Ax + Bu + w, \] \[ y = Cx + Du + v. \] The resulting observer is of the form \[ \dot{\hat{x}} = A\hat{x} + Bu + L(y - C\hat{x} - Du). \] The process noise, w, and the measurement noise, v, are assumed to be iid mean-zero Gaussian. More... | |
Eigen::MatrixXd | DiscreteTimeSteadyStateKalmanFilter (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &C, const Eigen::Ref< const Eigen::MatrixXd > &W, const Eigen::Ref< const Eigen::MatrixXd > &V) |
Computes the optimal observer gain, L, for the discrete-time linear system defined by \[ x[n+1] = Ax[n] + Bu[n] + w, \] \[ y[n] = Cx[n] + Du[n] + v. \] The resulting observer is of the form \[ \hat{x}[n+1] = A\hat{x}[n] + Bu[n] + L(y - C\hat{x}[n] - Du[n]). \] The process noise, w, and the measurement noise, v, are assumed to be iid mean-zero Gaussian. More... | |
Eigen::MatrixXd drake::systems::estimators::DiscreteTimeSteadyStateKalmanFilter | ( | const Eigen::Ref< const Eigen::MatrixXd > & | A, |
const Eigen::Ref< const Eigen::MatrixXd > & | C, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | W, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | V | ||
) |
Computes the optimal observer gain, L, for the discrete-time linear system defined by
\[ x[n+1] = Ax[n] + Bu[n] + w, \]
\[ y[n] = Cx[n] + Du[n] + v. \]
The resulting observer is of the form
\[ \hat{x}[n+1] = A\hat{x}[n] + Bu[n] + L(y - C\hat{x}[n] - Du[n]). \]
The process noise, w, and the measurement noise, v, are assumed to be iid mean-zero Gaussian.
This is a simplified form of the full Kalman filter obtained by assuming that the state-covariance matrix has already converged to its steady-state solution P, and the observer gain L = APC'(CPC' + V)⁻¹.
A | The state-space dynamics matrix of size num_states x num_states. |
C | The state-space output matrix of size num_outputs x num_states. |
W | The process noise covariance matrix, E[ww'], of size num_states x num_states. |
V | The measurement noise covariance matrix, E[vv'], of size num_outputs x num_outputs. |
std::exception | if W is not positive semi-definite or if V is not positive definite. |
Eigen::MatrixXd drake::systems::estimators::SteadyStateKalmanFilter | ( | const Eigen::Ref< const Eigen::MatrixXd > & | A, |
const Eigen::Ref< const Eigen::MatrixXd > & | C, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | W, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | V | ||
) |
Computes the optimal observer gain, L, for the continuous-time linear system defined by
\[ \dot{x} = Ax + Bu + w, \]
\[ y = Cx + Du + v. \]
The resulting observer is of the form
\[ \dot{\hat{x}} = A\hat{x} + Bu + L(y - C\hat{x} - Du). \]
The process noise, w, and the measurement noise, v, are assumed to be iid mean-zero Gaussian.
This is a simplified form of the full Kalman filter obtained by assuming that the state-covariance matrix has already converged to its steady-state solution.
A | The state-space dynamics matrix of size num_states x num_states. |
C | The state-space output matrix of size num_outputs x num_states. |
W | The process noise covariance matrix, E[ww'], of size num_states x num_states. |
V | The measurement noise covariance matrix, E[vv'], of size num_outputs x num_outputs. |
std::exception | if V is not positive definite. |