From f7e45af0ff81739079e631fd84de1082a9c23a83 Mon Sep 17 00:00:00 2001 From: Fredrik Bagge Carlson Date: Mon, 31 Jan 2022 16:33:16 +0100 Subject: [PATCH 1/3] use timeevol types to discpatch matrix equations --- README.md | 14 ++-- docs/src/examples/example.md | 2 +- example/dc_motor_lqg_design.jl | 2 +- src/ControlSystems.jl | 6 +- src/matrix_comps.jl | 29 +++++--- src/synthesis.jl | 119 +++++++++++++-------------------- src/types/Lti.jl | 17 ++--- test/test_linalg.jl | 16 ++--- test/test_plots.jl | 2 +- test/test_synthesis.jl | 10 +-- 10 files changed, 95 insertions(+), 122 deletions(-) diff --git a/README.md b/README.md index 08ba48ca4..21f61fab6 100644 --- a/README.md +++ b/README.md @@ -50,19 +50,19 @@ A documentation website is available at [http://juliacontrol.github.io/ControlSy Some of the available commands are: ##### Constructing systems -ss, tf, zpk +`ss, tf, zpk` ##### Analysis -poles, tzeros, norm, hinfnorm, linfnorm, ctrb, obsv, gangoffour, margin, markovparam, damp, dampreport, zpkdata, dcgain, covar, gram, sigma, sisomargin +`poles, tzeros, norm, hinfnorm, linfnorm, ctrb, obsv, gangoffour, margin, markovparam, damp, dampreport, zpkdata, dcgain, covar, gram, sigma, sisomargin` ##### Synthesis -care, dare, dlyap, lqr, dlqr, place, leadlink, laglink, leadlinkat, rstd, rstc, dab, balreal, baltrunc +`are, lyap, lqr, place, leadlink, laglink, leadlinkat, rstd, rstc, dab, balreal, baltrunc` ###### PID design -pid, stabregionPID, loopshapingPI, pidplots +`pid, stabregionPID, loopshapingPI, pidplots` ##### Time and Frequency response -step, impulse, lsim, freqresp, evalfr, bode, nyquist +`step, impulse, lsim, freqresp, evalfr, bode, nyquist` ##### Plotting -lsimplot, stepplot, impulseplot, bodeplot, nyquistplot, sigmaplot, marginplot, gangoffourplot, pidplots, pzmap, nicholsplot, pidplots, rlocus, leadlinkcurve +`lsimplot, stepplot, impulseplot, bodeplot, nyquistplot, sigmaplot, marginplot, gangoffourplot, pidplots, pzmap, nicholsplot, pidplots, rlocus, leadlinkcurve` ##### Other -minreal, sminreal, c2d +`minreal, sminreal, c2d` ## Usage This toolbox works similar to that of other major computer-aided control diff --git a/docs/src/examples/example.md b/docs/src/examples/example.md index 46892d222..b24652d3c 100644 --- a/docs/src/examples/example.md +++ b/docs/src/examples/example.md @@ -21,7 +21,7 @@ C = [1 0] sys = ss(A,B,C,0, Ts) Q = I R = I -L = dlqr(A,B,Q,R) # lqr(sys,Q,R) can also be used +L = lqr(Discrete,A,B,Q,R) # lqr(sys,Q,R) can also be used u(x,t) = -L*x .+ 1.5(t>=2.5)# Form control law (u is a function of t and x), a constant input disturbance is affecting the system from t≧2.5 t =0:Ts:5 diff --git a/example/dc_motor_lqg_design.jl b/example/dc_motor_lqg_design.jl index 53e72e7d2..6f0ea0f6f 100644 --- a/example/dc_motor_lqg_design.jl +++ b/example/dc_motor_lqg_design.jl @@ -37,7 +37,7 @@ Q = [1. 0; 0 1] R = 20. -K = lqr(p60.A, p60.B, Q, R) +K = lqr(p60, Q, R) # needs to be modified if Nbar is not a scalar Nbar = 1. ./ (p60.D - (p60.C - p60.D*K) * inv(p60.A - p60.B*K) * p60.B) diff --git a/src/ControlSystems.jl b/src/ControlSystems.jl index ec13bc56c..90844475e 100644 --- a/src/ControlSystems.jl +++ b/src/ControlSystems.jl @@ -15,13 +15,9 @@ export LTISystem, # Linear Algebra balance, balance_statespace, - care, - dare, - dlyap, + are, lqr, - dlqr, kalman, - dkalman, lqg, lqgi, covar, diff --git a/src/matrix_comps.jl b/src/matrix_comps.jl index ac5026b65..11c3958d6 100644 --- a/src/matrix_comps.jl +++ b/src/matrix_comps.jl @@ -1,9 +1,11 @@ -"""`care(A, B, Q, R)` +""" + care(A, B, Q, R) Compute 'X', the solution to the continuous-time algebraic Riccati equation, defined as A'X + XA - (XB)R^-1(B'X) + Q = 0, where R is non-singular. Uses `MatrixEquations.arec`. +This function exists for legacy reasons, users are encouraged to use the interface `are(Continuous, A, B, Q, R)` instead. """ function care(A, B, Q, R) arec(A, B, R, Q)[1] @@ -18,6 +20,7 @@ Compute `X`, the solution to the discrete-time algebraic Riccati equation, defined as A'XA - X - (A'XB)(B'XB + R)^-1(B'XA) + Q = 0, where Q>=0 and R>0 Uses `MatrixEquations.ared`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.ared` +This function exists for legacy reasons, users are encouraged to use the interface `are(Discrete, A, B, Q, R)` instead. """ function dare(A, B, Q, R; kwargs...) ared(A, B, R, Q; kwargs...)[1] @@ -25,6 +28,10 @@ end dare(A::Number, B::Number, Q::Number, R::Number) = dare(fill(A,1,1),fill(B,1,1),fill(Q,1,1),fill(R,1,1)) + +are(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = care(args...; kwargs...) +are(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dare(args...; kwargs...) + """ dlyap(A, Q; kwargs...) @@ -32,11 +39,17 @@ Compute the solution `X` to the discrete Lyapunov equation `AXA' - X + Q = 0`. Uses `MatrixEquations.lyapd`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.lyapd` +This function exists for legacy reasons, users are encouraged to use the interface `lyap(Discrete, A, B, Q, R)` instead. """ function dlyap(A::AbstractMatrix, Q; kwargs...) lyapd(A, Q; kwargs...) end +LinearAlgebra.lyap(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = lyap(args...; kwargs...) +LinearAlgebra.lyap(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dlyap(args...; kwargs...) + +plyap(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = MatrixEquations.plyapc(args...; kwargs...) +plyap(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = MatrixEquations.plyapd(args...; kwargs...) """ U = grampd(sys, opt; kwargs...) @@ -53,11 +66,10 @@ function grampd(sys::AbstractStateSpace, opt::Symbol; kwargs...) if !isstable(sys) error("gram only valid for stable A") end - func = iscontinuous(sys) ? MatrixEquations.plyapc : MatrixEquations.plyapd if opt === :c - func(sys.A, sys.B; kwargs...) + plyap(sys.timeevol, sys.A, sys.B; kwargs...) elseif opt === :o - func(sys.A', sys.C'; kwargs...) + plyap(sys.timeevol, sys.A', sys.C'; kwargs...) else error("opt must be either :c for controllability grammian, or :o for observability grammian") @@ -147,10 +159,9 @@ function covar(sys::AbstractStateSpace, W) if !isstable(sys) return fill(Inf,(size(C,1),size(C,1))) end - func = iscontinuous(sys) ? plyapc : plyapd Wc = cholesky(W).L Q1 = sys.nx == 0 ? B*Wc : try - func(A, B*Wc) + plyap(sys.timeevol, A, B*Wc) catch e @error("No solution to the Lyapunov equation was found in covar.") rethrow(e) @@ -178,7 +189,7 @@ covar(sys::TransferFunction, W) = covar(ss(sys), W) # Note: the H∞ norm computation is probably not as accurate as with SLICOT, # but this seems to be still reasonably ok as a first step """ -`.. norm(sys, p=2; tol=1e-6)` + norm(sys, p=2; tol=1e-6) `norm(sys)` or `norm(sys,2)` computes the H2 norm of the LTI system `sys`. @@ -206,7 +217,7 @@ LinearAlgebra.norm(sys::TransferFunction, p::Real=2; tol=1e-6) = norm(ss(sys), p """ -` (Ninf, ω_peak) = hinfnorm(sys; tol=1e-6)` + Ninf, ω_peak = hinfnorm(sys; tol=1e-6) Compute the H∞ norm `Ninf` of the LTI system `sys`, together with a frequency `ω_peak` at which the gain Ninf is achieved. @@ -234,7 +245,7 @@ hinfnorm(sys::AbstractStateSpace{<:Discrete}; tol=1e-6) = _infnorm_two_steps_dt( hinfnorm(sys::TransferFunction; tol=1e-6) = hinfnorm(ss(sys); tol=tol) """ -` (Ninf, ω_peak) = linfnorm(sys; tol=1e-6)` + Ninf, ω_peak = linfnorm(sys; tol=1e-6) Compute the L∞ norm `Ninf` of the LTI system `sys`, together with a frequency `ω_peak` at which the gain `Ninf` is achieved. diff --git a/src/synthesis.jl b/src/synthesis.jl index 261a2d839..21df52c05 100644 --- a/src/synthesis.jl +++ b/src/synthesis.jl @@ -1,32 +1,31 @@ """ - lqr(A, B, Q, R, args...; kwargs...) + lqr(sys, Q, R) + lqr(Continuous, A, B, Q, R, args...; kwargs...) + lqr(Discrete, A, B, Q, R, args...; kwargs...) Calculate the optimal gain matrix `K` for the state-feedback law `u = -K*x` that minimizes the cost function: -J = integral(x'Qx + u'Ru, 0, inf). - -For the continuous time model `dx = Ax + Bu`. - -`lqr(sys, Q, R)` +J = integral(x'Qx + u'Ru, 0, inf) for the continuous-time model `dx = Ax + Bu`. +J = sum(x'Qx + u'Ru, 0, inf) for the discrete-time model `x[k+1] = Ax[k] + Bu[k]`. Solve the LQR problem for state-space system `sys`. Works for both discrete and continuous time systems. -The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.arec` for more help. +The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.arec / ared` for more help. -See also `LQG` -Usage example: +# Examples +Continuous time ```julia using LinearAlgebra # For identity matrix I using Plots A = [0 1; 0 0] -B = [0;1] +B = [0; 1] C = [1 0] sys = ss(A,B,C,0) Q = I R = I -L = lqr(sys,Q,R) +L = lqr(sys,Q,R) # lqr(Continuous,A,B,Q,R) can also be used u(x,t) = -L*x # Form control law, t=0:0.1:5 @@ -34,57 +33,8 @@ x0 = [1,0] y, t, x, uout = lsim(sys,u,t,x0=x0) plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]") ``` -""" -function lqr(A, B, Q, R, args...; kwargs...) - S, _, K = arec(A, B, R, Q, args...; kwargs...) - return K -end - -""" - kalman(A, C, R1, R2) - kalman(sys, R1, R2) - -Calculate the optimal Kalman gain - -The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.arec/ared` for more help. - -See also `LQG` -""" -kalman(A, C, R1,R2, args...; kwargs...) = Matrix(lqr(A',C',R1,R2, args...; kwargs...)') - -function lqr(sys::AbstractStateSpace, Q, R, args...; kwargs...) - if iscontinuous(sys) - return lqr(sys.A, sys.B, Q, R, args...; kwargs...) - else - return dlqr(sys.A, sys.B, Q, R) - end -end - -function kalman(sys::AbstractStateSpace, R1, R2, args...; kwargs...) - if iscontinuous(sys) - return Matrix(lqr(sys.A', sys.C', R1,R2, args...; kwargs...)') - else - return Matrix(dlqr(sys.A', sys.C', R1,R2, args...; kwargs...)') - end -end - - -""" - dlqr(A, B, Q, R, args...; kwargs...) - dlqr(sys, Q, R, args...; kwargs...) -Calculate the optimal gain matrix `K` for the state-feedback law `u[k] = -K*x[k]` that -minimizes the cost function: - -J = sum(x'Qx + u'Ru, 0, inf). - -For the discrte time model `x[k+1] = Ax[k] + Bu[k]`. - -See also `lqg` - -The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.ared` for more help. - -Usage example: +Discrete time ```julia using LinearAlgebra # For identity matrix I using Plots @@ -92,10 +42,10 @@ Ts = 0.1 A = [1 Ts; 0 1] B = [0;1] C = [1 0] -sys = ss(A,B,C,0, Ts) +sys = ss(A, B, C, 0, Ts) Q = I R = I -L = dlqr(A,B,Q,R) # lqr(sys,Q,R) can also be used +L = lqr(Discrete, A,B,Q,R) # lqr(sys,Q,R) can also be used u(x,t) = -L*x # Form control law, t=0:Ts:5 @@ -104,25 +54,50 @@ y, t, x, uout = lsim(sys,u,t,x0=x0) plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]") ``` """ +lqr(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = clqr(args...; kwargs...) +lqr(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dlqr(args...; kwargs...) + +""" + clqr(A, B, Q, R, args...; kwargs...) + +This function exists for legacy reasons, users are encouraged to use the interface `lqr(Continuous, A, B, Q, R)` instead. +""" +function clqr(A, B, Q, R, args...; kwargs...) + S, _, K = arec(A, B, R, Q, args...; kwargs...) + return K +end + +""" + dlqr(A, B, Q, R, args...; kwargs...) + +This function exists for legacy reasons, users are encouraged to use the interface `lqr(Discrete, A, B, Q, R)` instead. +""" function dlqr(A, B, Q, R, args...; kwargs...) S, _, K = ared(A, B, R, Q, args...; kwargs...) return K end -function dlqr(sys::AbstractStateSpace, Q, R, args...; kwargs...) - !isdiscrete(sys) && throw(ArgumentError("Input argument sys must be discrete-time system")) - return dlqr(sys.A, sys.B, Q, R, args...; kwargs...) -end + """ - dkalman(A, C, R1, R2) - dkalman(sys, R1, R2) + kalman(Continuous, A, C, R1, R2) + kalman(Discrete, A, C, R1, R2) + kalman(sys, R1, R2) -Calculate the optimal Kalman gain for discrete time systems +Calculate the optimal Kalman gain -The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.ared` for more help. +The `args...; kwargs...` are sent to the Riccati solver, allowing specification of cross-covariance etc. See `?MatrixEquations.arec/ared` for more help. """ -dkalman(A, C, R1,R2, args...; kwargs...) = Matrix(dlqr(A',C',R1,R2, args...; kwargs...)') +kalman(te, A, C, R1,R2, args...; kwargs...) = Matrix(lqr(te, A',C',R1,R2, args...; kwargs...)') + +function lqr(sys::AbstractStateSpace, Q, R, args...; kwargs...) + return lqr(sys.timeevol, sys.A, sys.B, Q, R, args...; kwargs...) +end + +function kalman(sys::AbstractStateSpace, R1, R2, args...; kwargs...) + return Matrix(lqr(sys.timeevol, sys.A', sys.C', R1,R2, args...; kwargs...)') +end + """ place(A, B, p, opt=:c) diff --git a/src/types/Lti.jl b/src/types/Lti.jl index aaef22e35..88ae5c881 100644 --- a/src/types/Lti.jl +++ b/src/types/Lti.jl @@ -80,21 +80,12 @@ Base.propertynames(sys::LTISystem, private::Bool=false) = common_timeevol(systems::LTISystem...) = common_timeevol(timeevol(sys) for sys in systems) -"""`isstable(sys)` +""" + isstable(sys) Returns `true` if `sys` is stable, else returns `false`.""" -function isstable(sys::LTISystem) - if iscontinuous(sys) - if any(real.(poles(sys)).>=0) - return false - end - else - if any(abs.(poles(sys)).>=1) - return false - end - end - return true -end +isstable(sys::LTISystem{Continuous}) = all(real.(poles(sys)) .< 0) +isstable(sys::LTISystem{<:Discrete}) = all(abs.(poles(sys)) .< 1) # Fallback since LTISystem not AbstractArray Base.size(sys::LTISystem, i::Integer) = size(sys)[i] diff --git a/test/test_linalg.jl b/test/test_linalg.jl index 484511c7e..32238bcd4 100644 --- a/test/test_linalg.jl +++ b/test/test_linalg.jl @@ -4,15 +4,15 @@ b = [0 1]' c = [1 -1] r = 3 -@test care(a, b, c'*c, r) ≈ [0.5895174372762604 1.8215747248860816; 1.8215747248860823 8.818839806923107] -@test dare(a, b, c'*c, r) ≈ [240.73344504496302 -131.09928700089387; -131.0992870008943 75.93413176750603] +@test are(Continuous, a, b, c'*c, r) ≈ [0.5895174372762604 1.8215747248860816; 1.8215747248860823 8.818839806923107] +@test are(Discrete, a, b, c'*c, r) ≈ [240.73344504496302 -131.09928700089387; -131.0992870008943 75.93413176750603] ## Test dare method for non invertible matrices A = [0 1; 0 0]; B0 = [0; 1]; Q = Matrix{Float64}(I, 2, 2); R0 = 1 -X = dare(A, B0, Q, R0); +X = are(Discrete, A, B0, Q, R0); # Reshape for matrix expression B = reshape(B0, 2, 1) R = fill(R0, 1, 1) @@ -22,16 +22,16 @@ A = 1.0; B = 1.0; Q = 1.0; R = 1.0; -X0 = dare(A, B, Q, R); +X0 = are(Discrete, A, B, Q, R); X = X0[1] @test norm(A'X*A - X - (A'X*B)*((B'X*B + R)\(B'X*A)) + Q) < 1e-14 # Test for complex matrices I2 = Matrix{Float64}(I, 2, 2) -@test dare([1.0 im; im 1.0], I2, I2, I2) ≈ [1 + sqrt(2) 0; 0 1 + sqrt(2)] +@test are(Discrete, [1.0 im; im 1.0], I2, I2, I2) ≈ [1 + sqrt(2) 0; 0 1 + sqrt(2)] # And complex scalars -@test dare(1.0, 1, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) -@test dare(1.0im, 1, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) -@test dare(1.0, 1im, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) +@test are(Discrete, 1.0, 1, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) +@test are(Discrete, 1.0im, 1, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) +@test are(Discrete, 1.0, 1im, 1, 1) ≈ fill((1 + sqrt(5))/2, 1, 1) ## Test gram, ctrb, obsv a_2 = [-5 -3; 2 -9] diff --git a/test/test_plots.jl b/test/test_plots.jl index c84123220..98bcaeecc 100644 --- a/test/test_plots.jl +++ b/test/test_plots.jl @@ -22,7 +22,7 @@ function getexamples() stepgen() = plot(step(sys, ts[end]), l=(:dash, 4)) impulsegen() = plot(impulse(sys, ts[end]), l=:blue) - L = lqr(sysss.A, sysss.B, [1 0; 0 1], [1 0; 0 1]) + L = lqr(sysss, [1 0; 0 1], [1 0; 0 1]) lsimgen() = plot(lsim(sysss, (x,i)->-L*x, ts; x0=[1;2]), plotu=true) plot(lsim.([sysss, sysss], (x,i)->-L*x, Ref(ts); x0=[1;2]), plotu=true) diff --git a/test/test_synthesis.jl b/test/test_synthesis.jl index bc669454f..54f8f9810 100644 --- a/test/test_synthesis.jl +++ b/test/test_synthesis.jl @@ -108,28 +108,28 @@ end C = [1 0] Q = I R = I - L = dlqr(A,B,Q,R) + L = lqr(Discrete, A,B,Q,R) @test L ≈ [0.5890881713787511 0.7118839434795103] sys = ss(A,B,C,0,Ts) L = lqr(sys, Q, R) @test L ≈ [0.5890881713787511 0.7118839434795103] - L = dlqr(sys, Q, R) + L = lqr(sys, Q, R) @test L ≈ [0.5890881713787511 0.7118839434795103] B = reshape(B,2,1) # Note B is matrix, B'B is compatible with I - L = dlqr(A,B,Q,R) + L = lqr(Discrete, A,B,Q,R) @test L ≈ [0.5890881713787511 0.7118839434795103] Q = eye_(2) R = eye_(1) - L = dlqr(A,B,Q,R) + L = lqr(Discrete, A,B,Q,R) @test L ≈ [0.5890881713787511 0.7118839434795103] B = [0;1] # Note B is vector, B'B is scalar Q = eye_(2) R = eye_(1) - L ≈ dlqr(A,B,Q,R) + L ≈ lqr(Discrete, A,B,Q,R) #L ≈ [0.5890881713787511 0.7118839434795103] end From b792828bb88c456bdbcf141b68195e32b4477133 Mon Sep 17 00:00:00 2001 From: Fredrik Bagge Carlson Date: Tue, 15 Feb 2022 14:59:05 +0100 Subject: [PATCH 2/3] use formal deprecation --- src/matrix_comps.jl | 30 +++++++++++++++--------------- src/synthesis.jl | 20 +++++--------------- src/types/TimeEvolution.jl | 4 ++++ 3 files changed, 24 insertions(+), 30 deletions(-) diff --git a/src/matrix_comps.jl b/src/matrix_comps.jl index 11c3958d6..e82fe20bc 100644 --- a/src/matrix_comps.jl +++ b/src/matrix_comps.jl @@ -1,5 +1,5 @@ """ - care(A, B, Q, R) + are(::Continuous, A, B, Q, R) Compute 'X', the solution to the continuous-time algebraic Riccati equation, defined as A'X + XA - (XB)R^-1(B'X) + Q = 0, where R is non-singular. @@ -7,14 +7,12 @@ defined as A'X + XA - (XB)R^-1(B'X) + Q = 0, where R is non-singular. Uses `MatrixEquations.arec`. This function exists for legacy reasons, users are encouraged to use the interface `are(Continuous, A, B, Q, R)` instead. """ -function care(A, B, Q, R) +function are(::ContinuousType, A::AbstractMatrix, B, Q, R) arec(A, B, R, Q)[1] end -care(A::Number, B::Number, Q::Number, R::Number) = care(fill(A,1,1),fill(B,1,1),fill(Q,1,1),fill(R,1,1)) - """ - dare(A, B, Q, R; kwargs...) + are(::Discrete, A, B, Q, R; kwargs...) Compute `X`, the solution to the discrete-time algebraic Riccati equation, defined as A'XA - X - (A'XB)(B'XB + R)^-1(B'XA) + Q = 0, where Q>=0 and R>0 @@ -22,15 +20,14 @@ defined as A'XA - X - (A'XB)(B'XB + R)^-1(B'XA) + Q = 0, where Q>=0 and R>0 Uses `MatrixEquations.ared`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.ared` This function exists for legacy reasons, users are encouraged to use the interface `are(Discrete, A, B, Q, R)` instead. """ -function dare(A, B, Q, R; kwargs...) +function are(::DiscreteType, A::AbstractMatrix, B, Q, R; kwargs...) ared(A, B, R, Q; kwargs...)[1] end -dare(A::Number, B::Number, Q::Number, R::Number) = dare(fill(A,1,1),fill(B,1,1),fill(Q,1,1),fill(R,1,1)) - +are(t::TimeEvolType, A::Number, B::Number, Q::Number, R::Number) = are(t, fill(A,1,1),fill(B,1,1),fill(Q,1,1),fill(R,1,1)) -are(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = care(args...; kwargs...) -are(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dare(args...; kwargs...) +@deprecate care(args...; kwargs...) are(Continuous, args...; kwargs...) +@deprecate dare(args...; kwargs...) are(Discrete, args...; kwargs...) """ dlyap(A, Q; kwargs...) @@ -41,15 +38,18 @@ Compute the solution `X` to the discrete Lyapunov equation Uses `MatrixEquations.lyapd`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.lyapd` This function exists for legacy reasons, users are encouraged to use the interface `lyap(Discrete, A, B, Q, R)` instead. """ -function dlyap(A::AbstractMatrix, Q; kwargs...) +function lyap(::DiscreteType, A::AbstractMatrix, Q; kwargs...) lyapd(A, Q; kwargs...) end -LinearAlgebra.lyap(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = lyap(args...; kwargs...) -LinearAlgebra.lyap(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dlyap(args...; kwargs...) +LinearAlgebra.lyap(::ContinuousType, args...; kwargs...) = lyap(args...; kwargs...) +LinearAlgebra.lyap(::DiscreteType, args...; kwargs...) = dlyap(args...; kwargs...) + +plyap(::ContinuousType, args...; kwargs...) = MatrixEquations.plyapc(args...; kwargs...) +plyap(::DiscreteType, args...; kwargs...) = MatrixEquations.plyapd(args...; kwargs...) + +@deprecate dlyap(args...; kwargs...) lyap(Discrete, args...; kwargs...) -plyap(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = MatrixEquations.plyapc(args...; kwargs...) -plyap(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = MatrixEquations.plyapd(args...; kwargs...) """ U = grampd(sys, opt; kwargs...) diff --git a/src/synthesis.jl b/src/synthesis.jl index 21df52c05..ee72af4f5 100644 --- a/src/synthesis.jl +++ b/src/synthesis.jl @@ -54,29 +54,19 @@ y, t, x, uout = lsim(sys,u,t,x0=x0) plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]") ``` """ -lqr(::Union{Continuous, Type{Continuous}}, args...; kwargs...) = clqr(args...; kwargs...) -lqr(::Union{Discrete, Type{Discrete}}, args...; kwargs...) = dlqr(args...; kwargs...) - -""" - clqr(A, B, Q, R, args...; kwargs...) - -This function exists for legacy reasons, users are encouraged to use the interface `lqr(Continuous, A, B, Q, R)` instead. -""" -function clqr(A, B, Q, R, args...; kwargs...) +function lqr(::ContinuousType, A, B, Q, R, args...; kwargs...) S, _, K = arec(A, B, R, Q, args...; kwargs...) return K end -""" - dlqr(A, B, Q, R, args...; kwargs...) - -This function exists for legacy reasons, users are encouraged to use the interface `lqr(Discrete, A, B, Q, R)` instead. -""" -function dlqr(A, B, Q, R, args...; kwargs...) +function lqr(::DiscreteType, A, B, Q, R, args...; kwargs...) S, _, K = ared(A, B, R, Q, args...; kwargs...) return K end +@deprecate lqr(A::AbstractMatrix, args...; kwargs...) lqr(Continuous, A, args...; kwargs...) +@deprecate dlqr(args...; kwargs...) lqr(Discrete, args...; kwargs...) + """ diff --git a/src/types/TimeEvolution.jl b/src/types/TimeEvolution.jl index 928fc3f06..1f6454ff1 100644 --- a/src/types/TimeEvolution.jl +++ b/src/types/TimeEvolution.jl @@ -61,3 +61,7 @@ common_timeevol(x::Continuous, ys::Continuous...) = Continuous() isapprox(x::TimeEvolution, y::TimeEvolution, args...; kwargs...) = false isapprox(x::Discrete, y::Discrete, args...; kwargs...) = isapprox(x.Ts, y.Ts, args...; kwargs...) isapprox(::Continuous, ::Continuous, args...; kwargs...) = true + +const TimeEvolType = Union{<:TimeEvolution, Type{<:TimeEvolution}} +const DiscreteType = Union{Discrete, Type{Discrete}} +const ContinuousType = Union{Continuous, Type{Continuous}} \ No newline at end of file From dd6a35c6adaa41ed33d5837a0a173ce9b9634c22 Mon Sep 17 00:00:00 2001 From: Fredrik Bagge Carlson Date: Wed, 16 Feb 2022 08:00:04 +0100 Subject: [PATCH 3/3] fix docstrings --- src/matrix_comps.jl | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/matrix_comps.jl b/src/matrix_comps.jl index e82fe20bc..a3f14050a 100644 --- a/src/matrix_comps.jl +++ b/src/matrix_comps.jl @@ -5,7 +5,6 @@ Compute 'X', the solution to the continuous-time algebraic Riccati equation, defined as A'X + XA - (XB)R^-1(B'X) + Q = 0, where R is non-singular. Uses `MatrixEquations.arec`. -This function exists for legacy reasons, users are encouraged to use the interface `are(Continuous, A, B, Q, R)` instead. """ function are(::ContinuousType, A::AbstractMatrix, B, Q, R) arec(A, B, R, Q)[1] @@ -18,7 +17,6 @@ Compute `X`, the solution to the discrete-time algebraic Riccati equation, defined as A'XA - X - (A'XB)(B'XB + R)^-1(B'XA) + Q = 0, where Q>=0 and R>0 Uses `MatrixEquations.ared`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.ared` -This function exists for legacy reasons, users are encouraged to use the interface `are(Discrete, A, B, Q, R)` instead. """ function are(::DiscreteType, A::AbstractMatrix, B, Q, R; kwargs...) ared(A, B, R, Q; kwargs...)[1] @@ -30,13 +28,12 @@ are(t::TimeEvolType, A::Number, B::Number, Q::Number, R::Number) = are(t, fill(A @deprecate dare(args...; kwargs...) are(Discrete, args...; kwargs...) """ - dlyap(A, Q; kwargs...) + lyap(A, Q; kwargs...) Compute the solution `X` to the discrete Lyapunov equation `AXA' - X + Q = 0`. Uses `MatrixEquations.lyapd`. For keyword arguments, see the docstring of `ControlSystems.MatrixEquations.lyapd` -This function exists for legacy reasons, users are encouraged to use the interface `lyap(Discrete, A, B, Q, R)` instead. """ function lyap(::DiscreteType, A::AbstractMatrix, Q; kwargs...) lyapd(A, Q; kwargs...)