Implementations of estimators that operate as Systems in a block diagram.
Algorithms that synthesize controllers are located in State Estimation.
Classes | |
class | LuenbergerObserver< T > |
A simple state observer for a continuous-time dynamical system of the form: \[ \dot{x} = f(x,u) \] \[ y = g(x,u) \] the observer dynamics takes the form \[ \dot{\hat{x}} = f(\hat{x},u) + L(y - g(\hat{x},u)) \] where \(\hat{x}\) is the estimated state of the original system. More... | |
Functions | |
std::unique_ptr< LuenbergerObserver< double > > | SteadyStateKalmanFilter (std::shared_ptr< const LinearSystem< double >> system, const Eigen::Ref< const Eigen::MatrixXd > &W, const Eigen::Ref< const Eigen::MatrixXd > &V) |
Creates a Luenberger observer system using the optimal steady-state Kalman filter gain matrix, L, as described in SteadyStateKalmanFilter and DiscreteTimeSteadyStateKalmanFilter. More... | |
std::unique_ptr< LuenbergerObserver< double > > | SteadyStateKalmanFilter (std::shared_ptr< const System< double >> system, const Context< double > &context, const Eigen::Ref< const Eigen::MatrixXd > &W, const Eigen::Ref< const Eigen::MatrixXd > &V) |
Creates a Luenberger observer system using the steady-state Kalman filter observer gain. More... | |
Eigen::MatrixXd | ObservabilityMatrix (const LinearSystem< double > &sys) |
Returns the observability matrix: O = [ C; CA; ...; CA^{n-1} ]. More... | |
bool | IsObservable (const LinearSystem< double > &sys, std::optional< double > threshold=std::nullopt) |
Returns true iff the observability matrix is full column rank. More... | |
bool | IsDetectable (const LinearSystem< double > &sys, std::optional< double > threshold=std::nullopt) |
Returns true iff the system is detectable. More... | |
bool drake::systems::IsDetectable | ( | const LinearSystem< double > & | sys, |
std::optional< double > | threshold = std::nullopt |
||
) |
Returns true iff the system is detectable.
bool drake::systems::IsObservable | ( | const LinearSystem< double > & | sys, |
std::optional< double > | threshold = std::nullopt |
||
) |
Returns true iff the observability matrix is full column rank.
Eigen::MatrixXd drake::systems::ObservabilityMatrix | ( | const LinearSystem< double > & | sys | ) |
Returns the observability matrix: O = [ C; CA; ...; CA^{n-1} ].
std::unique_ptr<LuenbergerObserver<double> > drake::systems::estimators::SteadyStateKalmanFilter | ( | std::shared_ptr< const LinearSystem< double >> | system, |
const Eigen::Ref< const Eigen::MatrixXd > & | W, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | V | ||
) |
Creates a Luenberger observer system using the optimal steady-state Kalman filter gain matrix, L, as described in SteadyStateKalmanFilter and DiscreteTimeSteadyStateKalmanFilter.
system | The LinearSystem describing the system to be observed. |
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. |
std::unique_ptr<LuenbergerObserver<double> > drake::systems::estimators::SteadyStateKalmanFilter | ( | std::shared_ptr< const System< double >> | system, |
const Context< double > & | context, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | W, | ||
const Eigen::Ref< const Eigen::MatrixXd > & | V | ||
) |
Creates a Luenberger observer system using the steady-state Kalman filter observer gain.
If system
has continuous-time dynamics: ẋ = f(x,u), and the output: y = g(x,u), then the resulting observer will have the form dx̂/dt = f(x̂,u) + L(y − g(x̂,u)), where x̂ is the estimated state and the gain matrix, L, is designed as a steady-state Kalman filter using a linearization of f(x,u) at context
as described above.
If system
has discrete-time dynamics: x[n+1] = f(x[n],u[n]), and the output: y[n] = g(x[n],u[n]), then the resulting observer will have the form x̂[n+1] = f(x̂[n],u[n]) + L(y − g(x̂[n],u[n])), where x̂[n+1] is the estimated state and the gain matrix, L, is designed as a steady-state Kalman filter using a linearization of f(x,u) at context
as described above.
system | The System describing the system to be observed. |
context | The context describing a fixed-point of the system (plus any additional parameters). |
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. |