Processing math: 0%
Drake
Drake C++ Documentation
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Modules Pages
drake::systems::estimators Namespace Reference

Classes

class  LuenbergerObserver
 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

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...

 
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...
 
std::unique_ptr< LuenbergerObserver< double > > SteadyStateKalmanFilter (std::unique_ptr< System< double >> system, std::unique_ptr< Context< double >> context, const Eigen::Ref< const Eigen::MatrixXd > &W, const Eigen::Ref< const Eigen::MatrixXd > &V)
 (Deprecated.) More...
 

Function Documentation

◆ SteadyStateKalmanFilter()

std::unique_ptr<LuenbergerObserver<double> > drake::systems::estimators::SteadyStateKalmanFilter ( std::unique_ptr< System< double >>  system,
std::unique_ptr< Context< double >>  context,
const Eigen::Ref< const Eigen::MatrixXd > &  W,
const Eigen::Ref< const Eigen::MatrixXd > &  V 
)

(Deprecated.)

Deprecated:
This overload is deprecated for removal. Instead, use the other overload by passing a const-ref to the context. (Add an asterisk at the call site to de-reference the context.)
This will be removed from Drake on or after 2025-06-01.