pydrake.systems.estimators
- class pydrake.systems.estimators.LuenbergerObserver
Bases:
pydrake.systems.framework.LeafSystem
A simple state observer for a 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.
The output of the observer system is \(\hat{x}\).
observed system input→ observed_system_output→ LuenbergerObserver → estimated_state - __init__(self: pydrake.systems.estimators.LuenbergerObserver, observed_system: pydrake.systems.framework.System, observed_system_context: pydrake.systems.framework.Context, observer_gain: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) None
Constructs the observer.
- Parameter
observed_system
: The forward model for the observer. Currently, this system must have a maximum of one input port and exactly one output port.
- Parameter
observed_system_context
: Required because it may contain parameters which we need to evaluate the system.
- Parameter
observer_gain
: A m-by-n matrix where m is the number of state variables in
observed_system
, and n is the dimension of the output port ofobserved_system
.- Precondition:
The observed_system output port must be vector-valued.
Note: The
observed_system
reference must remain valid for the lifetime of this system.- Parameter
- get_estimated_state_output_port(self: pydrake.systems.estimators.LuenbergerObserver) pydrake.systems.framework.OutputPort
- get_observed_system_input_input_port(self: pydrake.systems.estimators.LuenbergerObserver) pydrake.systems.framework.InputPort
- get_observed_system_output_input_port(self: pydrake.systems.estimators.LuenbergerObserver) pydrake.systems.framework.InputPort
- L(self: pydrake.systems.estimators.LuenbergerObserver) numpy.ndarray[numpy.float64[m, n]]
Provides access via the short-hand name, L, too.
- observer_gain(self: pydrake.systems.estimators.LuenbergerObserver) numpy.ndarray[numpy.float64[m, n]]
Provides access to the observer gain.
- pydrake.systems.estimators.SteadyStateKalmanFilter(*args, **kwargs)
Overloaded function.
SteadyStateKalmanFilter(A: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], C: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], W: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], V: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) -> numpy.ndarray[numpy.float64[m, n]]
Computes the optimal observer gain, L, for the 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.
- Parameter
A
: The state-space dynamics matrix of size num_states x num_states.
- Parameter
C
: The state-space output matrix of size num_outputs x num_states.
- Parameter
W
: The process noise covariance matrix, E[ww’], of size num_states x num_states.
- Parameter
V
: The measurement noise covariance matrix, E[vv’], of size num_.
- Returns
The steady-state observer gain matrix of size num_states x num_outputs.
- Raises
RuntimeError if V is not positive definite. –
SteadyStateKalmanFilter(system: pydrake.systems.primitives.LinearSystem, W: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], V: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) -> pydrake.systems.estimators.LuenbergerObserver
Creates a Luenberger observer system using the optimal steady-state Kalman filter gain matrix, L, as described above.
- Parameter
system
: A unique_ptr to a LinearSystem describing the system to be observed. The new observer will take and maintain ownership of this pointer.
- Parameter
W
: The process noise covariance matrix, E[ww’], of size num_states x num_states.
- Parameter
V
: The measurement noise covariance matrix, E[vv’], of size num_.
- Returns
A unique_ptr to the constructed observer system.
- Raises
RuntimeError if V is not positive definite. –
SteadyStateKalmanFilter(system: pydrake.systems.framework.System, context: pydrake.systems.framework.Context, W: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], V: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) -> pydrake.systems.estimators.LuenbergerObserver
Creates a Luenberger observer system using the steady-state Kalman filter observer gain.
Assuming
system
has the (continuous-time) dynamics: dx/dt = 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) atcontext
as described above.- Parameter
system
: A unique_ptr to a System describing the system to be observed. The new observer will take and maintain ownership of this pointer.
- Parameter
context
: A unique_ptr to the context describing a fixed-point of the system (plus any additional parameters). The new observer will take and maintain ownership of this pointer for use in its internal forward simulation.
- Parameter
W
: The process noise covariance matrix, E[ww’], of size num_states x num_states.
- Parameter
V
: The measurement noise covariance matrix, E[vv’], of size num_.
- Returns
A unique_ptr to the constructed observer system.
- Raises
RuntimeError if V is not positive definite. –