Skip to content

Commit 559f102

Browse files
committed
add docstring comments
1 parent 2729dd5 commit 559f102

File tree

2 files changed

+9
-2
lines changed

2 files changed

+9
-2
lines changed

lib/ControlSystemsBase/src/discrete.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -195,7 +195,7 @@ Ref: "Discrete-time Solutions to the Continuous-time
195195
Differential Lyapunov Equation With Applications to Kalman Filtering",
196196
Patrik Axelsson and Fredrik Gustafsson
197197
198-
On singular covariance matrices: The traditional double integrator with covariance matrix `Q = diagm([0,σ²])` can not be sampled with this method. Instead, the input matrix ("Cholesky factor") of `Q` must be manually kept track of, e.g., the noise of variance `σ²` enters like `N = [0, 1]` which is sampled using ZoH and becomes `Nd = [1/2 Ts^2; Ts]` which results in the covariance matrix `σ² * Nd * Nd'`.
198+
**On singular covariance matrices:** The traditional double integrator with covariance matrix `Qc = diagm([0,σ²])` warrants special consideration since it is rank-deficient, i.e., it indicates that there is a single source of randomness only, despite the presence of two state variables. If we assume that the noise is piecewise constant, we can use the input matrix ("Cholesky factor") of `Qc`, e.g., the noise of variance `σ²` enters like `N = [0, 1]` which is sampled using ZoH and becomes `Nd = [Ts^2 / 2; Ts]` which results in the covariance matrix `σ² * Nd * Nd'`. If we assume that the noise is a continuous-time white noise process, the discretized covariance matrix is full rank and can be computed by `c2d(sys::StateSpace{Continuous}, Qc, Ts)`. In some applications, a rank-1 approximation to this matrix is favored. In such situation, a good rank-1 approximation to this matrix is obtained by `σ² * Nd * Nd' ./ Ts`. This has the benefit of being both low rank, and produce covariance dynamics that are approximately invariant to the choice of sample interval. If the ZoH assumption is made, the covariance matrix is rank 1 but the covariance dynamics are not invariant to the choice of sample interval.`
199199
200200
# Example:
201201
The following example designs a continuous-time LQR controller for a resonant system. This is simulated with OrdinaryDiffEq to allow the ODE integrator to also integrate the continuous-time LQR cost (the cost is added as an additional state variable). We then discretize both the system and the cost matrices and simulate the same thing. The discretization of an LQR contorller in this way is sometimes refered to as `lqrd`.

lib/ControlSystemsBase/src/matrix_comps.jl

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -124,6 +124,8 @@ Compute the observability matrix with `n` rows for the system described by `(A,
124124
Note that checking for observability by computing the rank from `obsv` is
125125
not the most numerically accurate way, a better method is checking if
126126
`gram(sys, :o)` is positive definite or to call the function [`observability`](@ref).
127+
128+
The unobservable subspace is `nullspace(obsv(A, C))`, initial conditions in this subspace produce a zero response.
127129
"""
128130
function obsv(A::AbstractMatrix, C::AbstractMatrix, n::Int = size(A,1))
129131
T = promote_type(eltype(A), eltype(C))
@@ -151,6 +153,8 @@ Compute the controllability matrix for the system described by `(A, B)` or
151153
Note that checking for controllability by computing the rank from
152154
`ctrb` is not the most numerically accurate way, a better method is
153155
checking if `gram(sys, :c)` is positive definite or to call the function [`controllability`](@ref).
156+
157+
The controllable subspace is given by the range of this matrix, and the uncontrollable subspace is `nullspace(ctrb(A, B)') (note the transpose)`.
154158
"""
155159
function ctrb(A::AbstractMatrix, B::AbstractVecOrMat)
156160
T = promote_type(eltype(A), eltype(B))
@@ -226,7 +230,10 @@ Calculate the stationary covariance `P = E[y(t)y(t)']` of the output `y` of a
226230
227231
Remark: If `sys` is unstable then the resulting covariance is a matrix of `Inf`s.
228232
Entries corresponding to direct feedthrough (D*W*D' .!= 0) will equal `Inf`
229-
for continuous-time systems."""
233+
for continuous-time systems.
234+
235+
See also [`innovation_form`](@ref).
236+
"""
230237
function covar(sys::AbstractStateSpace, W)
231238
(A, B, C, D) = ssdata(sys)
232239
if !isa(W, UniformScaling) && (size(B,2) != size(W, 1) || size(W, 1) != size(W, 2))

0 commit comments

Comments
 (0)