From: <mur...@us...> - 2014-03-22 19:31:47
|
Revision: 296 http://sourceforge.net/p/python-control/code/296 Author: murrayrm Date: 2014-03-22 19:31:36 +0000 (Sat, 22 Mar 2014) Log Message: ----------- allow 5 arguments for matlab.ss() command to create discrete time system Modified Paths: -------------- trunk/ChangeLog trunk/external/yottalab.py trunk/src/matlab.py Modified: trunk/ChangeLog =================================================================== --- trunk/ChangeLog 2014-03-22 18:30:41 UTC (rev 295) +++ trunk/ChangeLog 2014-03-22 19:31:36 UTC (rev 296) @@ -1,5 +1,10 @@ 2014-03-22 Richard Murray <murray@sidamo.local> + * src/matlab.py (ss): allow five arguments to create a discrete time + system. From Roberto Bucher, 12 Jan 2014 + +2014-03-22 Richard Murray <murray@sidamo.local> + * src/bdalg.py (feedback): allow FRD for feedback() 2014-03-22 Richard Murray <murray@sidamo.local> Modified: trunk/external/yottalab.py =================================================================== --- trunk/external/yottalab.py 2014-03-22 18:30:41 UTC (rev 295) +++ trunk/external/yottalab.py 2014-03-22 19:31:36 UTC (rev 296) @@ -1,5 +1,3 @@ -# yottalab.py - Roberto Bucher's yottalab library - """ This is a procedural interface to the yttalab library @@ -8,104 +6,314 @@ The following commands are provided: Design and plot commands - acker - pole placement using Ackermann method - c2d - contimous to discrete time conversion + bb_c2d - contimous to discrete time conversion + d2c - discrete to continous time conversion + bb_dare - Solve Riccati equation for discrete time systems + bb_dlqr - discrete linear quadratic regulator + dsimul - simulate discrete time systems + dstep - step response (plot) of discrete time systems + dimpulse - imoulse response (plot) of discrete time systems + bb_step - step response (plot) of continous time systems + full_obs - full order observer red_obs - reduced order observer comp_form - state feedback controller+observer in compact form comp_form_i - state feedback controller+observer+integ in compact form - dsimul - simulate discrete time systems - dstep - step response (plot) of discrete time systems - dimpulse - imoulse response (plot) of discrete time systems - bb_step - step response (plot) of continous time systems sysctr - system+controller+observer+feedback - care - Solve Riccati equation for contimous time systems - dare - Solve Riccati equation for discrete time systems - dlqr - discrete linear quadratic regulator - minreal - minimal state space representation - + set_aw - introduce anti-windup into controller + bb_dcgain - return the steady state value of the step response + """ from matplotlib.pylab import * -from control.matlab import * +from control import * from numpy import hstack,vstack,pi from scipy import zeros,ones,eye,mat,shape,size,size, \ arange,real,poly,array,diag -from scipy.linalg import det,inv,expm,eig,eigvals +from scipy.linalg import det,inv,expm,eig,eigvals,logm import numpy as np import scipy as sp -from slycot import sb02od, tb03ad +from slycot import sb02od +# from scipy.signal import BadCoefficients +# import warnings +# warnings.filterwarnings('ignore',category=BadCoefficients) -def acker(A,B,poles): - """Pole placemenmt using Ackermann method +def bb_c2d(sys,Ts,method='zoh'): + """Continous to discrete conversion with ZOH method Call: - k=acker(A,B,poles) + sysd=c2d(sys,Ts,method='zoh') Parameters ---------- - A, B : State and input matrix of the system - poles: desired poles + sys : System in statespace or Tf form + Ts: Sampling Time + method: 'zoh', 'bi' or 'matched' Returns ------- - k: matrix - State feedback gains + sysd: ss or Tf system + Discrete system """ - a=mat(A) - b=mat(B) - p=real(poly(poles)) - ct=ctrb(A,B) - if det(ct)==0: - k=0 - print "Pole placement invalid" + flag = 0 + if isinstance(sys, TransferFunction): + sys=tf2ss(sys) + flag=1 + + a=sys.A + b=sys.B + c=sys.C + d=sys.D + n=shape(a)[0] + nb=shape(b)[1] + nc=shape(c)[0] + + if method=='zoh': + ztmp=zeros((nb,n+nb)) + tmp=hstack((a,b)) + tmp=vstack((tmp,ztmp)) + tmp=expm(tmp*Ts) + A=tmp[0:n,0:n] + B=tmp[0:n,n:n+nb] + C=c + D=d + elif method=='bi': + a=mat(a) + b=mat(b) + c=mat(c) + d=mat(d) + IT=mat(2/Ts*eye(n,n)) + A=(IT+a)*inv(IT-a) + iab=inv(IT-a)*b + tk=2/sqrt(Ts) + B=tk*iab + C=tk*(c*inv(IT-a)) + D=d+c*iab + elif method=='matched': + if nb!=1 and nc!=1: + print "System is not SISO" + return + p=exp(sys.poles*Ts) + z=exp(sys.zeros*Ts) + infinite_zeros = len(sys.poles) - len(sys.zeros) - 1 + for i in range(0,infinite_zeros): + z=hstack((z,-1)) + [A,B,C,D]=zpk2ss(z,p,1) + sysd=StateSpace(A,B,C,D,Ts) + cg = dcgain(sys) + dg = dcgain(sysd) + [A,B,C,D]=zpk2ss(z,p,cg/dg) else: - n=size(p) - pmat=p[n-1]*a**0 - for i in arange(1,n): - pmat=pmat+p[n-i-1]*a**i - k=inv(ct)*pmat - k=k[-1][:] - return k + print "Method not supported" + return + + sysd=StateSpace(A,B,C,D,Ts) + if flag==1: + sysd=ss2tf(sysd) + return sysd -def c2d(sys,Ts): +def d2c(sys,method='zoh'): """Continous to discrete conversion with ZOH method Call: - sysd=c2d(sys,Ts) + sysc=c2d(sys,method='log') Parameters ---------- - sys : System in statespace or Tf form - Ts: Sampling Time + sys : System in statespace or Tf form + method: 'zoh' or 'bi' Returns ------- - sysd: ss or Tf system - Discrete system + sysc: continous system ss or tf + """ flag = 0 - if type(sys).__name__=='TransferFunction': + if isinstance(sys, TransferFunction): sys=tf2ss(sys) flag=1 + a=sys.A b=sys.B c=sys.C d=sys.D + Ts=sys.dt n=shape(a)[0] nb=shape(b)[1] - ztmp=zeros((nb,n+nb)) - tmp=hstack((a,b)) - tmp=vstack((tmp,ztmp)) - tmp=expm(tmp*Ts) - a=tmp[0:n,0:n] - b=tmp[0:n,n:n+nb] - sysd=ss(a,b,c,d,Ts) + nc=shape(c)[0] + tol=1e-12 + + if method=='zoh': + if n==1: + if b[0,0]==1: + A=0 + B=b/sys.dt + C=c + D=d + else: + tmp1=hstack((a,b)) + tmp2=hstack((zeros((nb,n)),eye(nb))) + tmp=vstack((tmp1,tmp2)) + s=logm(tmp) + s=s/Ts + if norm(imag(s),inf) > sqrt(sp.finfo(float).eps): + print "Warning: accuracy may be poor" + s=real(s) + A=s[0:n,0:n] + B=s[0:n,n:n+nb] + C=c + D=d + elif method=='bi': + a=mat(a) + b=mat(b) + c=mat(c) + d=mat(d) + poles=eigvals(a) + if any(abs(poles-1)<200*sp.finfo(float).eps): + print "d2c: some poles very close to one. May get bad results." + + I=mat(eye(n,n)) + tk = 2 / sqrt (Ts) + A = (2/Ts)*(a-I)*inv(a+I) + iab = inv(I+a)*b + B = tk*iab + C = tk*(c*inv(I+a)) + D = d- (c*iab) + else: + print "Method not supported" + return + + sysc=StateSpace(A,B,C,D) if flag==1: - sysd=ss2tf(sysd) - return sysd + sysc=ss2tf(sysc) + return sysc +def dsimul(sys,u): + """Simulate the discrete system sys + Only for discrete systems!!! + + Call: + y=dsimul(sys,u) + + Parameters + ---------- + sys : Discrete System in State Space form + u : input vector + Returns + ------- + y: ndarray + Simulation results + + """ + a=mat(sys.A) + b=mat(sys.B) + c=mat(sys.C) + d=mat(sys.D) + nx=shape(a)[0] + ns=shape(u)[1] + xk=zeros((nx,1)) + for i in arange(0,ns): + uk=u[:,i] + xk_1=a*xk+b*uk + yk=c*xk+d*uk + xk=xk_1 + if i==0: + y=yk + else: + y=hstack((y,yk)) + y=array(y).T + return y + +def dstep(sys,Tf=10.0): + """Plot the step response of the discrete system sys + Only for discrete systems!!! + + Call: + y=dstep(sys, [,Tf=final time])) + + Parameters + ---------- + sys : Discrete System in State Space form + Tf : Final simulation time + + Returns + ------- + Nothing + + """ + Ts=sys.dt + if Ts==0.0: + "Only discrete systems allowed!" + return + + ns=int(Tf/Ts+1) + u=ones((1,ns)) + y=dsimul(sys,u) + T=arange(0,Tf+Ts/2,Ts) + plot(T,y) + grid() + show() + +def dimpulse(sys,Tf=10.0): + """Plot the impulse response of the discrete system sys + Only for discrete systems!!! + + Call: + y=dimpulse(sys,[,Tf=final time])) + + Parameters + ---------- + sys : Discrete System in State Space form + Tf : Final simulation time + + Returns + ------- + Nothing + + """ + Ts=sys.dt + if Ts==0.0: + "Only discrete systems allowed!" + return + + ns=int(Tf/Ts+1) + u=zeros((1,ns)) + u[0,0]=1/Ts + y=dsimul(sys,u) + T=arange(0,Tf+Ts/2,Ts) + plot(T,y) + grid() + show() + +# Step response (plot) +def bb_step(sys,X0=None,Tf=None,Ts=0.001): + """Plot the step response of the continous system sys + + Call: + y=bb_step(sys [,Tf=final time] [,Ts=time step]) + + Parameters + ---------- + sys : Continous System in State Space form + X0: Initial state vector (not used yet) + Ts : sympling time + Tf : Final simulation time + + Returns + ------- + Nothing + + """ + if Tf==None: + vals = eigvals(sys.A) + r = min(abs(real(vals))) + if r < 1e-10: + r = 0.1 + Tf = 7.0 / r + sysd=c2d(sys,Ts) + dstep(sysd,Tf=Tf) + def full_obs(sys,poles): """Full order observer of the system sys @@ -123,14 +331,13 @@ Observer """ - if type(sys).__name__=='TransferFunction': + if isinstance(sys, TransferFunction): "System must be in state space form" return a=mat(sys.A) b=mat(sys.B) c=mat(sys.C) d=mat(sys.D) - poles=mat(poles) L=place(a.T,c.T,poles) L=mat(L).T Ao=a-L*c @@ -139,7 +346,7 @@ m=shape(Bo) Co=eye(n[0],n[1]) Do=zeros((n[0],m[1])) - obs=ss(Ao,Bo,Co,Do,sys.Tsamp) + obs=StateSpace(Ao,Bo,Co,Do,sys.dt) return obs def red_obs(sys,T,poles): @@ -160,7 +367,7 @@ Reduced order Observer """ - if type(sys).__name__=='TransferFunction': + if isinstance(sys, TransferFunction): "System must be in state space form" return a=mat(sys.A) @@ -169,7 +376,7 @@ d=mat(sys.D) T=mat(T) P=mat(vstack((c,T))) - poles=mat(poles) + # poles=mat(poles) invP=inv(P) AA=P*a*invP ny=shape(c)[0] @@ -205,7 +412,7 @@ tmp5=mat(vstack((tmp5,tmp6))) Dr=invP*tmp5*tmp4 - obs=ss(Ar,Br,Cr,Dr,sys.Tsamp) + obs=StateSpace(Ar,Br,Cr,Dr,sys.dt) return obs def comp_form(sys,obs,K): @@ -242,7 +449,7 @@ Bc = hstack((Bu*X,By-Bu*X*K*Dy)) Cc = -X*K*mat(obs.C); Dc = hstack((X,-X*K*Dy)) - contr = ss(Ac,Bc,Cc,Dc,sys.Tsamp) + contr = StateSpace(Ac,Bc,Cc,Dc,sys.dt) return contr def comp_form_i(sys,obs,K,Ts,Cy=[[1]]): @@ -266,7 +473,7 @@ Controller """ - if sys.Tsamp==0.0: + if sys.dt==0.0: print "contr_form_i works only with discrete systems!" return @@ -274,7 +481,7 @@ nu=shape(sys.B)[1] nx=shape(sys.A)[0] no=shape(obs.A)[0] - ni=shape(Cy)[0] + ni=shape(mat(Cy))[0] B_obsu = mat(obs.B[:,0:nu]) B_obsy = mat(obs.B[:,nu:nu+ny]) @@ -303,134 +510,9 @@ C_ctr=hstack((-X*K*c,-X*Ke)) D_ctr=hstack((zeros((nu,ni)),-X*K*D_obsy)) - contr=ss(A_ctr,B_ctr,C_ctr,D_ctr,sys.Tsamp) + contr=StateSpace(A_ctr,B_ctr,C_ctr,D_ctr,sys.dt) return contr -def dsimul(sys,u): - """Simulate the discrete system sys - Only for discrete systems!!! - - Call: - y=dsimul(sys,u) - - Parameters - ---------- - sys : Discrete System in State Space form - u : input vector - Returns - ------- - y: ndarray - Simulation results - - """ - a=mat(sys.A) - b=mat(sys.B) - c=mat(sys.C) - d=mat(sys.D) - nx=shape(a)[0] - ns=shape(u)[1] - xk=zeros((nx,1)) - for i in arange(0,ns): - uk=u[:,i] - xk_1=a*xk+b*uk - yk=c*xk+d*uk - xk=xk_1 - if i==0: - y=yk - else: - y=hstack((y,yk)) - y=array(y).T - return y - -def dstep(sys,Tf=10.0): - """Plot the step response of the discrete system sys - Only for discrete systems!!! - - Call: - y=dstep(sys, [,Tf=final time])) - - Parameters - ---------- - sys : Discrete System in State Space form - Tf : Final simulation time - - Returns - ------- - Nothing - - """ - Ts=sys.Tsamp - if Ts==0.0: - "Only discrete systems allowed!" - return - - ns=int(Tf/Ts+1) - u=ones((1,ns)) - y=dsimul(sys,u) - T=arange(0,Tf+Ts/2,Ts) - plot(T,y) - grid() - show() - -def dimpulse(sys,Tf=10.0): - """Plot the impulse response of the discrete system sys - Only for discrete systems!!! - - Call: - y=dimpulse(sys,[,Tf=final time])) - - Parameters - ---------- - sys : Discrete System in State Space form - Tf : Final simulation time - - Returns - ------- - Nothing - - """ - Ts=sys.Tsamp - if Ts==0.0: - "Only discrete systems allowed!" - return - - ns=int(Tf/Ts+1) - u=zeros((1,ns)) - u[0,0]=1/Ts - y=dsimul(sys,u) - T=arange(0,Tf+Ts/2,Ts) - plot(T,y) - grid() - show() - -# Step response (plot) -def bb_step(sys,X0=None,Tf=None,Ts=0.001): - """Plot the step response of the continous system sys - - Call: - y=bb_step(sys [,Tf=final time] [,Ts=time step]) - - Parameters - ---------- - sys : Continous System in State Space form - X0: Initial state vector (not used yet) - Ts : sympling time - Tf : Final simulation time - - Returns - ------- - Nothing - - """ - if Tf==None: - vals = eigvals(sys.A) - r = min(abs(real(vals))) - if r == 0.0: - r = 1.0 - Tf = 7.0 / r - sysd=c2d(sys,Ts) - dstep(sysd,Tf=Tf) - def sysctr(sys,contr): """Build the discrete system controller+plant+output feedback @@ -449,10 +531,10 @@ as output """ - if contr.Tsamp!=sys.Tsamp: + if contr.dt!=sys.dt: print "Systems with different sampling time!!!" return - sysf=contr*sys + sysf=sys*contr nu=shape(sysf.B)[1] b1=mat(sysf.B[:,0]) @@ -470,44 +552,42 @@ Cf=X*mat(sysf.C) Df=X*d1 - sysc=ss(Af,Bf,Cf,Df,sys.Tsamp) + sysc=StateSpace(Af,Bf,Cf,Df,sys.dt) return sysc -def care(A,B,Q,R): - """Solve Riccati equation for discrete time systems +def set_aw(sys,poles): + """Divide in controller in input and feedback part + for anti-windup Usage ===== - [K, S, E] = care(A, B, Q, R) + [sys_in,sys_fbk]=set_aw(sys,poles) Inputs ------ - A, B: 2-d arrays with dynamics and input matrices - sys: linear I/O system - Q, R: 2-d array with state and input weight matrices + sys: controller + poles : poles for the anti-windup filter + Outputs ------- - X: solution of the Riccati eq. + sys_in, sys_fbk: controller in input and feedback part """ +# sys=StateSpace(sys); + sys=ss(sys); + den_old=poly(eigvals(sys.A)) + den = poly(poles) + tmp= tf(den_old,den,sys.dt) + tmpss=tf2ss(tmp) +# sys_in=StateSpace(tmp*sys) + sys_in=ss(tmp*sys) + sys_in.dt=sys.dt +# sys_fbk=StateSpace(1-tmp) + sys_fbk=ss(1-tmp) + sys_fbk.dt=sys.dt + return sys_in, sys_fbk - # Check dimensions for consistency - nstates = B.shape[0]; - ninputs = B.shape[1]; - if (A.shape[0] != nstates or A.shape[1] != nstates): - raise ControlDimension("inconsistent system dimensions") - - elif (Q.shape[0] != nstates or Q.shape[1] != nstates or - R.shape[0] != ninputs or R.shape[1] != ninputs) : - raise ControlDimension("incorrect weighting matrix dimensions") - - rcond,X,w,S,T = \ - sb02od(nstates, ninputs, A, B, Q, R, 'C'); - - return X - - -def dare(A,B,Q,R): +def bb_dare(A,B,Q,R): """Solve Riccati equation for discrete time systems Usage @@ -535,13 +615,13 @@ R.shape[0] != ninputs or R.shape[1] != ninputs) : raise ControlDimension("incorrect weighting matrix dimensions") - rcond,X,w,S,T = \ + X,rcond,w,S,T = \ sb02od(nstates, ninputs, A, B, Q, R, 'D'); return X -def dlqr(*args, **keywords): +def bb_dlqr(*args, **keywords): """Linear quadratic regulator design for discrete systems Usage @@ -581,7 +661,7 @@ A = array(args[0].A, ndmin=2, dtype=float); B = array(args[0].B, ndmin=2, dtype=float); index = 1; - if args[0].Tsamp==0.0: + if args[0].dt==0.0: print "dlqr works only for discrete systems!" return else: @@ -595,8 +675,10 @@ R = array(args[index+1], ndmin=2, dtype=float); if (len(args) > index + 2): N = array(args[index+2], ndmin=2, dtype=float); + Nflag = 1; else: N = zeros((Q.shape[0], R.shape[1])); + Nflag = 0; # Check dimensions for consistency nstates = B.shape[0]; @@ -609,46 +691,154 @@ N.shape[0] != nstates or N.shape[1] != ninputs): raise ControlDimension("incorrect weighting matrix dimensions") + if Nflag==1: + Ao=A-B*inv(R)*N.T + Qo=Q-N*inv(R)*N.T + else: + Ao=A + Qo=Q + #Solve the riccati equation - X = dare(A,B,Q,R) + # (X,L,G) = dare(Ao,B,Qo,R) + X = bb_dare(Ao,B,Qo,R) # Now compute the return value Phi=mat(A) H=mat(B) - K=inv(H.T*X*H+R)*(H.T*X*Phi) + K=inv(H.T*X*H+R)*(H.T*X*Phi+N.T) L=eig(Phi-H*K) return K,X,L -def minreal(sys): - """Minimal representation for state space systems +def dlqr(*args, **keywords): + """Linear quadratic regulator design + + The lqr() function computes the optimal state feedback controller + that minimizes the quadratic cost + + .. math:: J = \int_0^\infty x' Q x + u' R u + 2 x' N u + + The function can be called with either 3, 4, or 5 arguments: + + * ``lqr(sys, Q, R)`` + * ``lqr(sys, Q, R, N)`` + * ``lqr(A, B, Q, R)`` + * ``lqr(A, B, Q, R, N)`` + + Parameters + ---------- + A, B: 2-d array + Dynamics and input matrices + sys: Lti (StateSpace or TransferFunction) + Linear I/O system + Q, R: 2-d array + State and input weight matrices + N: 2-d array, optional + Cross weight matrix + + Returns + ------- + K: 2-d array + State feedback gains + S: 2-d array + Solution to Riccati equation + E: 1-d array + Eigenvalues of the closed loop system + + Examples + -------- + >>> K, S, E = lqr(sys, Q, R, [N]) + >>> K, S, E = lqr(A, B, Q, R, [N]) + + """ + + # Make sure that SLICOT is installed + try: + from slycot import sb02md + from slycot import sb02mt + except ImportError: + raise ControlSlycot("can't find slycot module 'sb02md' or 'sb02nt'") + + # + # Process the arguments and figure out what inputs we received + # + + # Get the system description + if (len(args) < 4): + raise ControlArgument("not enough input arguments") + + elif (ctrlutil.issys(args[0])): + # We were passed a system as the first argument; extract A and B + #! TODO: really just need to check for A and B attributes + A = np.array(args[0].A, ndmin=2, dtype=float); + B = np.array(args[0].B, ndmin=2, dtype=float); + index = 1; + else: + # Arguments should be A and B matrices + A = np.array(args[0], ndmin=2, dtype=float); + B = np.array(args[1], ndmin=2, dtype=float); + index = 2; + + # Get the weighting matrices (converting to matrices, if needed) + Q = np.array(args[index], ndmin=2, dtype=float); + R = np.array(args[index+1], ndmin=2, dtype=float); + if (len(args) > index + 2): + N = np.array(args[index+2], ndmin=2, dtype=float); + else: + N = np.zeros((Q.shape[0], R.shape[1])); + + # Check dimensions for consistency + nstates = B.shape[0]; + ninputs = B.shape[1]; + if (A.shape[0] != nstates or A.shape[1] != nstates): + raise ControlDimension("inconsistent system dimensions") + + elif (Q.shape[0] != nstates or Q.shape[1] != nstates or + R.shape[0] != ninputs or R.shape[1] != ninputs or + N.shape[0] != nstates or N.shape[1] != ninputs): + raise ControlDimension("incorrect weighting matrix dimensions") + + # Compute the G matrix required by SB02MD + A_b,B_b,Q_b,R_b,L_b,ipiv,oufact,G = \ + sb02mt(nstates, ninputs, B, R, A, Q, N, jobl='N'); + + # Call the SLICOT function + X,rcond,w,S,U,A_inv = sb02md(nstates, A_b, G, Q_b, 'D') + + # Now compute the return value + K = np.dot(np.linalg.inv(R), (np.dot(B.T, X) + N.T)); + S = X; + E = w[0:nstates]; + + return K, S, E + +def bb_dcgain(sys): + """Return the steady state value of the step response os sys + Usage ===== - [sysmin]=minreal[sys] + dcgain=dcgain(sys) Inputs ------ - sys: system in ss or tf form + sys: system Outputs ------- - sysfin: system in state space form + dcgain : steady state value """ + a=mat(sys.A) b=mat(sys.B) c=mat(sys.C) d=mat(sys.D) nx=shape(a)[0] - ni=shape(b)[1] - no=shape(c)[0] - - out=tb03ad(nx,no,ni,a,b,c,d,'R') - - nr=out[3] - A=out[0][:nr,:nr] - B=out[1][:nr,:ni] - C=out[2][:no,:nr] - sysf=ss(A,B,C,sys.D,sys.Tsamp) - return sysf - + if sys.dt!=0.0: + a=a-eye(nx,nx) + r=rank(a) + if r<nx: + gm=[] + else: + gm=-c*inv(a)*b+d + return array(gm) Modified: trunk/src/matlab.py =================================================================== --- trunk/src/matlab.py 2014-03-22 18:30:41 UTC (rev 295) +++ trunk/src/matlab.py 2014-03-22 19:31:36 UTC (rev 296) @@ -398,7 +398,7 @@ """ Create a state space system. - The function accepts either 1 or 4 parameters: + The function accepts either 1, 4 or 5 parameters: ``ss(sys)`` Convert a linear system into space system form. Always creates a @@ -412,7 +412,16 @@ \dot x = A \cdot x + B \cdot u y = C \cdot x + D \cdot u + + ``ss(A, B, C, D, dt)`` + Create a discrete-time state space system from the matrices of + its state and output equations: + + .. math:: + x[k+1] = A \cdot x[k] + B \cdot u[k] + y[k] = C \cdot x[k] + D \cdot u[ki] + The matrices can be given as *array like* data types or strings. Everything that the constructor of :class:`numpy.matrix` accepts is permissible here too. @@ -429,6 +438,8 @@ Output matrix D: array_like or string Feed forward matrix + dt: If present, specifies the sampling period and a discrete time + system is created Returns ------- @@ -457,8 +468,8 @@ """ - if len(args) == 4: - return StateSpace(args[0], args[1], args[2], args[3]) + if len(args) == 4 or len(args) == 5: + return StateSpace(*args) elif len(args) == 1: sys = args[0] if isinstance(sys, StateSpace): @@ -635,7 +646,7 @@ C: array_like or string Output matrix D: array_like or string - Feed forward matrix + Feedthrough matrix Returns ------- |