|
From: <mur...@us...> - 2010-11-06 13:04:03
|
Revision: 29
http://python-control.svn.sourceforge.net/python-control/?rev=29&view=rev
Author: murrayrm
Date: 2010-11-06 13:03:55 +0000 (Sat, 06 Nov 2010)
Log Message:
-----------
2010-11-05 Richard Murray <mu...@su...>
* external/yottalab.py: New file containing Roberto Bucher's control
library functions. OK to start pulling these into the main library,
with attribution, but note that they use modifications of the
default library => some rewrites will be needed.
2010-09-11 Richard Murray <mu...@su...>
* src/matlab.py (step): Added local step response function that uses
lsim2() instead of signal.step (which can't handle integrators).
This function may not be needed when new scipy step2() function is
available.
(impulse): Added local impulse response function that sets the
initial condition based on the input matrix and then uses the
lsim2() function to compute the response.
* examples/test-response.py: Added test script for making sure that
time repsonse functions are working as desired
* src/matlab.py (lsim): Added local version of lsim that calls
signal.lsim2 (actual ODE integrator)
Modified Paths:
--------------
trunk/ChangeLog
trunk/Pending
trunk/src/__init__.py
trunk/src/matlab.py
trunk/src/rlocus.py
trunk/src/statefbk.py
Added Paths:
-----------
trunk/external/yottalab.py
trunk/src/delay.py
Modified: trunk/ChangeLog
===================================================================
--- trunk/ChangeLog 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/ChangeLog 2010-11-06 13:03:55 UTC (rev 29)
@@ -1,3 +1,45 @@
+2010-11-05 Richard Murray <mu...@su...>
+
+ * external/yottalab.py: New file containing Roberto Bucher's control
+ library functions. OK to start pulling these into the main library,
+ with attribution, but note that they use modifications of the
+ default library => some rewrites will be needed.
+
+2010-09-11 Richard Murray <mu...@su...>
+
+ * src/matlab.py (step): Added local step response function that uses
+ lsim2() instead of signal.step (which can't handle integrators).
+ This function may not be needed when new scipy step2() function is
+ available.
+ (impulse): Added local impulse response function that sets the
+ initial condition based on the input matrix and then uses the
+ lsim2() function to compute the response.
+
+ * examples/test-response.py: Added test script for making sure that
+ time repsonse functions are working as desired
+
+ * src/matlab.py (lsim): Added local version of lsim that calls
+ signal.lsim2 (actual ODE integrator)
+
+2010-09-06 Richard Murray <mu...@su...>
+
+ * src/statefbk.py (ctrb): new function for testing controllability
+ * src/statefbk.py (obsv): new function for testing observabiilty
+
+2010-09-02 Richard Murray <mu...@su...>
+
+ * src/statefbk.py (place): Use np.size() instead of len() for
+ finding length of placed_eigs for better compatability with
+ different python versions [courtesy of Roberto Bucher]
+
+ * src/delay.py (pade): New file for delay-based computations +
+ initial implementation of pade() [courtesy Sawyer Fuller]
+
+2010-06-17 Richard Murray <mu...@su...>
+
+ * src/rlocus.py: changed num, den to nump, denp for clarity
+ * src/rlocus.py: new file with Ryan Krauss's root locus code
+
2010-06-06 Richard Murray <mu...@su...>
* examples/pvtol-lqr.py: Added example to test out LQR routines
Modified: trunk/Pending
===================================================================
--- trunk/Pending 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/Pending 2010-11-06 13:03:55 UTC (rev 29)
@@ -1,8 +1,42 @@
List of Pending changes for control-python
RMM, 5 Sep 09
+This file contains brief notes on features that need to be added to
+the python control library. Mainly intended to keep track of "bigger
+picture" things that need to be done.
+
+--> See src/matlab.py for a list of MATLAB functions that eventually need
+ to be implemented.
+
+OPEN BUGS
+ * step() doesn't handle systems with a pole at the origin (use lsim2)
+
+Transfer code from Roberto Bucher's yottalab to python-control
+ acker - pole placement using Ackermann method
+ c2d - contimous to discrete time conversion
+ 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
+
+Transfer code from Ryan Krauss's control.py to python-control
+ * phase margin computations (as part of margin command)
+ * step reponse
+ * c2d, c2d_tustin (compare to Bucher version first)
+
Examples and test cases
+ * Put together unit tests for all functions (after deciding on framework)
* Figure out how to import 'figure' command properly (version issue?)
+ * Figure out source of BadCoefficients warning messages (pvtol-lqr and others)
TransferFunction class fixes
* evalfr is not working (num, den stored as ndarrays, not poly1ds)
@@ -16,12 +50,11 @@
* Implement pzmap for state space systems
LTI updates
- * Try to get control.matlab.step semantics to be closer to MATLAB
+ * Implement control.matlab.step (with semantics similar to MATLAB)
Basic functions to be added
* margin - compute gain and phase margin (no plot)
* lqr - compute optimal feedback gains (use SLICOT SB02ND.f)
- * lqe - compute optimal feedback gains (use SLICOT SB02ND.f)
* lyap - solve Lyapunov equation (use SLICOT SB03MD.f)
* See http://www.slicot.org/shared/libindex.html for list of functions
Added: trunk/external/yottalab.py
===================================================================
--- trunk/external/yottalab.py (rev 0)
+++ trunk/external/yottalab.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -0,0 +1,652 @@
+"""
+This is a procedural interface to the yttalab library
+
+rob...@su...
+
+The following commands are provided:
+
+Design and plot commands
+ acker - pole placement using Ackermann method
+ c2d - contimous to discrete time conversion
+ 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
+
+"""
+from matplotlib.pylab import *
+from control.matlab 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
+import numpy as np
+import scipy as sp
+from slycot import sb02od, tb03ad
+
+def acker(A,B,poles):
+ """Pole placemenmt using Ackermann method
+
+ Call:
+ k=acker(A,B,poles)
+
+ Parameters
+ ----------
+ A, B : State and input matrix of the system
+ poles: desired poles
+
+ Returns
+ -------
+ k: matrix
+ State feedback gains
+
+ """
+ a=mat(A)
+ b=mat(B)
+ p=real(poly(poles))
+ ct=ctrb(A,B)
+ if det(ct)==0:
+ k=0
+ print "Pole placement invalid"
+ 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
+
+def c2d(sys,Ts):
+ """Continous to discrete conversion with ZOH method
+
+ Call:
+ sysd=c2d(sys,Ts)
+
+ Parameters
+ ----------
+ sys : System in statespace or Tf form
+ Ts: Sampling Time
+
+ Returns
+ -------
+ sysd: ss or Tf system
+ Discrete system
+
+ """
+ flag = 0
+ if type(sys).__name__=='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]
+ 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)
+ if flag==1:
+ sysd=ss2tf(sysd)
+ return sysd
+
+def full_obs(sys,poles):
+ """Full order observer of the system sys
+
+ Call:
+ obs=full_obs(sys,poles)
+
+ Parameters
+ ----------
+ sys : System in State Space form
+ poles: desired observer poles
+
+ Returns
+ -------
+ obs: ss
+ Observer
+
+ """
+ if type(sys).__name__=='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
+ Bo=hstack((b-L*d,L))
+ n=shape(Ao)
+ m=shape(Bo)
+ Co=eye(n[0],n[1])
+ Do=zeros((n[0],m[1]))
+ obs=ss(Ao,Bo,Co,Do,sys.Tsamp)
+ return obs
+
+def red_obs(sys,T,poles):
+ """Reduced order observer of the system sys
+
+ Call:
+ obs=red_obs(sys,T,poles)
+
+ Parameters
+ ----------
+ sys : System in State Space form
+ T: Complement matrix
+ poles: desired observer poles
+
+ Returns
+ -------
+ obs: ss
+ Reduced order Observer
+
+ """
+ if type(sys).__name__=='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)
+ T=mat(T)
+ P=mat(vstack((c,T)))
+ poles=mat(poles)
+ invP=inv(P)
+ AA=P*a*invP
+ ny=shape(c)[0]
+ nx=shape(a)[0]
+ nu=shape(b)[1]
+
+ A11=AA[0:ny,0:ny]
+ A12=AA[0:ny,ny:nx]
+ A21=AA[ny:nx,0:ny]
+ A22=AA[ny:nx,ny:nx]
+
+ L1=place(A22.T,A12.T,poles)
+ L1=mat(L1).T
+
+ nn=nx-ny
+
+ tmp1=mat(hstack((-L1,eye(nn,nn))))
+ tmp2=mat(vstack((zeros((ny,nn)),eye(nn,nn))))
+ Ar=tmp1*P*a*invP*tmp2
+
+ tmp3=vstack((eye(ny,ny),L1))
+ tmp3=mat(hstack((P*b,P*a*invP*tmp3)))
+ tmp4=hstack((eye(nu,nu),zeros((nu,ny))))
+ tmp5=hstack((-d,eye(ny,ny)))
+ tmp4=mat(vstack((tmp4,tmp5)))
+
+ Br=tmp1*tmp3*tmp4
+
+ Cr=invP*tmp2
+
+ tmp5=hstack((zeros((ny,nu)),eye(ny,ny)))
+ tmp6=hstack((zeros((nn,nu)),L1))
+ tmp5=mat(vstack((tmp5,tmp6)))
+ Dr=invP*tmp5*tmp4
+
+ obs=ss(Ar,Br,Cr,Dr,sys.Tsamp)
+ return obs
+
+def comp_form(sys,obs,K):
+ """Compact form Conroller+Observer
+
+ Call:
+ contr=comp_form(sys,obs,K)
+
+ Parameters
+ ----------
+ sys : System in State Space form
+ obs : Observer in State Space form
+ K: State feedback gains
+
+ Returns
+ -------
+ contr: ss
+ Controller
+
+ """
+ nx=shape(sys.A)[0]
+ ny=shape(sys.C)[0]
+ nu=shape(sys.B)[1]
+ no=shape(obs.A)[0]
+
+ Bu=mat(obs.B[:,0:nu])
+ By=mat(obs.B[:,nu:])
+ Du=mat(obs.D[:,0:nu])
+ Dy=mat(obs.D[:,nu:])
+
+ X=inv(eye(nu,nu)+K*Du)
+
+ Ac = mat(obs.A)-Bu*X*K*mat(obs.C);
+ 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)
+ return contr
+
+def comp_form_i(sys,obs,K,Ts,Cy=[[1]]):
+ """Compact form Conroller+Observer+Integral part
+ Only for discrete systems!!!
+
+ Call:
+ contr=comp_form_i(sys,obs,K,Ts[,Cy])
+
+ Parameters
+ ----------
+ sys : System in State Space form
+ obs : Observer in State Space form
+ K: State feedback gains
+ Ts: Sampling time
+ Cy: feedback matric to choose the output for integral part
+
+ Returns
+ -------
+ contr: ss
+ Controller
+
+ """
+ if sys.Tsamp==0.0:
+ print "contr_form_i works only with discrete systems!"
+ return
+
+ ny=shape(sys.C)[0]
+ nu=shape(sys.B)[1]
+ nx=shape(sys.A)[0]
+ no=shape(obs.A)[0]
+ ni=shape(Cy)[0]
+
+ B_obsu = mat(obs.B[:,0:nu])
+ B_obsy = mat(obs.B[:,nu:nu+ny])
+ D_obsu = mat(obs.D[:,0:nu])
+ D_obsy = mat(obs.D[:,nu:nu+ny])
+
+ k=mat(K)
+ nk=shape(k)[1]
+ Ke=k[:,nk-ni:]
+ K=k[:,0:nk-ni]
+ X = inv(eye(nu,nu)+K*D_obsu);
+
+ a=mat(obs.A)
+ c=mat(obs.C)
+ Cy=mat(Cy)
+
+ tmp1=hstack((a-B_obsu*X*K*c,-B_obsu*X*Ke))
+
+ tmp2=hstack((zeros((ni,no)),eye(ni,ni)))
+ A_ctr=vstack((tmp1,tmp2))
+
+ tmp1=hstack((zeros((no,ni)),-B_obsu*X*K*D_obsy+B_obsy))
+ tmp2=hstack((eye(ni,ni)*Ts,-Cy*Ts))
+ B_ctr=vstack((tmp1,tmp2))
+
+ 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)
+ 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
+
+ Call:
+ syscontr=sysctr(sys,contr)
+
+ Parameters
+ ----------
+ sys : Continous System in State Space form
+ contr: Controller (with observer if required)
+
+ Returns
+ -------
+ sysc: ss system
+ The system with reference as input and outputs of plants
+ as output
+
+ """
+ if contr.Tsamp!=sys.Tsamp:
+ print "Systems with different sampling time!!!"
+ return
+ sysf=contr*sys
+
+ nu=shape(sysf.B)[1]
+ b1=mat(sysf.B[:,0])
+ b2=mat(sysf.B[:,1:nu])
+ d1=mat(sysf.D[:,0])
+ d2=mat(sysf.D[:,1:nu])
+
+ n2=shape(d2)[0]
+
+ Id=mat(eye(n2,n2))
+ X=inv(Id-d2)
+
+ Af=mat(sysf.A)+b2*X*mat(sysf.C)
+ Bf=b1+b2*X*d1
+ Cf=X*mat(sysf.C)
+ Df=X*d1
+
+ sysc=ss(Af,Bf,Cf,Df,sys.Tsamp)
+ return sysc
+
+def care(A,B,Q,R):
+ """Solve Riccati equation for discrete time systems
+
+ Usage
+ =====
+ [K, S, E] = care(A, B, Q, R)
+
+ 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
+
+ Outputs
+ -------
+ X: solution of the Riccati eq.
+ """
+
+ # 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):
+ """Solve Riccati equation for discrete time systems
+
+ Usage
+ =====
+ [K, S, E] = care(A, B, Q, R)
+
+ 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
+
+ Outputs
+ -------
+ X: solution of the Riccati eq.
+ """
+
+ # 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, 'D');
+
+ return X
+
+
+def dlqr(*args, **keywords):
+ """Linear quadratic regulator design for discrete systems
+
+ Usage
+ =====
+ [K, S, E] = dlqr(A, B, Q, R, [N])
+ [K, S, E] = dlqr(sys, Q, R, [N])
+
+ The dlqr() function computes the optimal state feedback controller
+ that minimizes the quadratic cost
+
+ J = \sum_0^\infty x' Q x + u' R u + 2 x' N u
+
+ 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
+ N: optional 2-d array with cross weight matrix
+
+ Outputs
+ -------
+ K: 2-d array with state feedback gains
+ S: 2-d array with solution to Riccati equation
+ E: 1-d array with eigenvalues of the closed loop system
+ """
+
+ #
+ # Process the arguments and figure out what inputs we received
+ #
+
+ # Get the system description
+ if (len(args) < 3):
+ raise ControlArgument("not enough input arguments")
+
+ elif (ctrlutil.issys(args[0])):
+ # We were passed a system as the first argument; extract A and B
+ 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:
+ print "dlqr works only for discrete systems!"
+ return
+ else:
+ # Arguments should be A and B matrices
+ A = array(args[0], ndmin=2, dtype=float);
+ B = array(args[1], ndmin=2, dtype=float);
+ index = 2;
+
+ # Get the weighting matrices (converting to matrices, if needed)
+ Q = array(args[index], ndmin=2, dtype=float);
+ R = array(args[index+1], ndmin=2, dtype=float);
+ if (len(args) > index + 2):
+ N = array(args[index+2], ndmin=2, dtype=float);
+ else:
+ N = 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")
+
+ #Solve the riccati equation
+ X = dare(A,B,Q,R)
+
+ # Now compute the return value
+ Phi=mat(A)
+ H=mat(B)
+ K=inv(H.T*X*H+R)*(H.T*X*Phi)
+ L=eig(Phi-H*K)
+ return K,X,L
+
+def minreal(sys):
+ """Minimal representation for state space systems
+
+ Usage
+ =====
+ [sysmin]=minreal[sys]
+
+ Inputs
+ ------
+
+ sys: system in ss or tf form
+
+ Outputs
+ -------
+ sysfin: system in state space form
+ """
+ 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
+
Modified: trunk/src/__init__.py
===================================================================
--- trunk/src/__init__.py 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/src/__init__.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -61,3 +61,4 @@
from freqplot import *
from bdalg import *
from statefbk import *
+from delay import *
Added: trunk/src/delay.py
===================================================================
--- trunk/src/delay.py (rev 0)
+++ trunk/src/delay.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -0,0 +1,68 @@
+# delay.py - functions involving time delays
+#
+# Author: Sawyer Fuller
+# Date: 26 Aug 2010
+#
+# This file contains functions for implementing time delays (currently
+# only the pade() function).
+#
+# Copyright (c) 2010 by California Institute of Technology
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+#
+# 3. Neither the name of the California Institute of Technology nor
+# the names of its contributors may be used to endorse or promote
+# products derived from this software without specific prior
+# written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL CALTECH
+# OR THE CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+# USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+# ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
+# OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+# SUCH DAMAGE.
+#
+# $Id: pade.py 17 2010-05-29 23:50:52Z murrayrm $
+
+def pade(T, n=1):
+ """
+ Return the numerator and denominator coefficients of the Pade approximation.
+
+ Inputs:
+ T --> time delay
+ n --> order of approximation
+
+ Outputs:
+ num, den --> arrays in descending powers of s.
+
+ Based on an algorithm in Golub and van Loan, "Matrix Computation" 3rd.
+ Ed. pp. 572-574.
+ """
+ num = [0. for i in range(n+1)]
+ num[-1] = 1.
+ den = [0. for i in range(n+1)]
+ den[-1] = 1.
+ c = 1.
+ for k in range(1, n+1):
+ c = T * c * (n - k + 1)/(2 * n - k + 1)/k
+ num[n - k] = c * (-1)**k
+ den[n - k] = c
+ num = [coeff/den[0] for coeff in num]
+ den = [coeff/den[0] for coeff in den]
+ return num, den
Modified: trunk/src/matlab.py
===================================================================
--- trunk/src/matlab.py 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/src/matlab.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -55,7 +55,6 @@
# Import MATLAB-like functions that are defined in other packages
from scipy.signal import zpk2ss, ss2zpk, tf2zpk, zpk2tf
-from scipy.signal import lsim, impulse, step
from scipy import linspace, logspace
# Control system library
@@ -70,7 +69,8 @@
from freqplot import nyquist, gangof4
from bdalg import series, parallel, negate, feedback
from pzmap import pzmap
-from statefbk import place, lqr
+from statefbk import ctrb, obsv, place, lqr
+from delay import pade
__doc__ = """
The control.matlab module defines functions that are roughly the
@@ -191,8 +191,8 @@
drss - random stable discrete-time state-space models
ss2ss - state coordinate transformation
canon - canonical forms of state-space models
- ctrb - controllability matrix
- obsv - observability matrix
+* ctrb - controllability matrix
+* obsv - observability matrix
gram - controllability and observability gramians
ss/prescale - optimal scaling of state-space models.
balreal - gramian-based input/output balancing
@@ -214,7 +214,7 @@
lti/hasdelay - true for models with time delays
lti/totaldelay - total delay between each input/output pair
lti/delay2z - replace delays by poles at z=0 or FRD phase shift
- pade - pade approximation of time delays
+* pade - pade approximation of time delays
Model dimensions and characteristics
class - model type ('tf', 'zpk', 'ss', or 'frd')
@@ -370,3 +370,89 @@
# Call the bode command
return freqplot.bode(syslist, omega, **keywords)
+
+#
+# Modifications to scipy.signal functions
+#
+
+# Redefine lsim to use lsim2
+def lsim(*args, **keywords):
+ """Simulate the output of a linear system
+
+ Usage
+ =====
+ (T, yout, xout) = lsim(sys, u, T, X0)
+
+ Inputs:
+ sys LTI system
+ u input array giving input at each time T
+ T time steps at which the input is defined
+ X0 initial condition (optional, default = 0)
+
+ Outputs:
+ T time values of the output
+ yout response of the system
+ xout time evolution of the state vector
+ """
+ return sp.signal.lsim2(*args, **keywords)
+
+#! Redefine step to use lsim2
+#! Not yet implemented
+def step(*args, **keywords):
+ """Step response of a linear system
+
+ Usage
+ =====
+ (T, yout) = step(sys, T, X0)
+
+ Inputs:
+ sys LTI system
+ T time steps (optional; autocomputed if not gien)
+ X0 initial condition (optional, default = 0)
+
+ Outputs:
+ T time values of the output
+ yout response of the system
+ """
+ return sp.signal.step(*args, **keywords)
+
+# Redefine initial to use lsim2
+#! Not yet implemented (uses step for now)
+def initial(*args, **keywords):
+ """Initial condition response of a linear system
+
+ Usage
+ =====
+ (T, yout) = initial(sys, T, X0)
+
+ Inputs:
+ sys LTI system
+ T time steps (optional; autocomputed if not gien)
+ X0 initial condition (optional, default = 0)
+
+ Outputs:
+ T time values of the output
+ yout response of the system
+ """
+ return sp.signal.initial(*args, **keywords)
+
+# Redefine impulse to use initial()
+#! Not yet implemented (uses impulse for now)
+def impulse(*args, **keywords):
+ """Step response of a linear system
+
+ Usage
+ =====
+ (T, yout) = impulse(sys, T, X0)
+
+ Inputs:
+ sys LTI system
+ T time steps (optional; autocomputed if not gien)
+ X0 initial condition (optional, default = 0)
+
+ Outputs:
+ T time values of the output
+ yout response of the system
+ """
+ return sp.signal.impulse(*args, **keywords)
+
Modified: trunk/src/rlocus.py
===================================================================
--- trunk/src/rlocus.py 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/src/rlocus.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -53,7 +53,7 @@
of kvect."""
# Convert numerator and denominator to polynomials if they aren't
- (num, den) = _systopoly1d(sys);
+ (nump, denp) = _systopoly1d(sys);
# Set up the figure
if fig is None:
@@ -68,11 +68,11 @@
mymat = _RLSortRoots(sys, mymat)
# plot open loop poles
- poles = array(den.r)
+ poles = array(denp.r)
ax.plot(real(poles), imag(poles), 'x')
# plot open loop zeros
- zeros = array(num.r)
+ zeros = array(nump.r)
if zeros.any():
ax.plot(real(zeros), imag(zeros), 'o')
@@ -94,23 +94,23 @@
"""Extract numerator and denominator polynomails for a system"""
# Start by extracting the numerator and denominator from system object
- num = sys.num; den = sys.den;
+ nump = sys.num; denp = sys.den;
# Check to see if num, den are already polynomials; otherwise convert
- if (not isinstance(num, poly1d)): num = poly1d(num)
- if (not isinstance(den, poly1d)): den = poly1d(den)
+ if (not isinstance(nump, poly1d)): nump = poly1d(nump)
+ if (not isinstance(denp, poly1d)): denp = poly1d(denp)
- return (num, den)
+ return (nump, denp)
def _RLFindRoots(sys, kvect):
"""Find the roots for the root locus."""
# Convert numerator and denominator to polynomials if they aren't
- (num, den) = _systopoly1d(sys);
+ (nump, denp) = _systopoly1d(sys);
roots = []
for k in kvect:
- curpoly = den + k * num
+ curpoly = denp + k * nump
curroots = curpoly.r
curroots.sort()
roots.append(curroots)
Modified: trunk/src/statefbk.py
===================================================================
--- trunk/src/statefbk.py 2010-06-18 05:10:26 UTC (rev 28)
+++ trunk/src/statefbk.py 2010-11-06 13:03:55 UTC (rev 29)
@@ -1,6 +1,6 @@
# statefbk.py - tools for state feedback control
#
-# Author: Richard M. Murray
+# Author: Richard M. Murray, Roberto Bucher
# Date: 31 May 2010
#
# This file contains routines for designing state space controllers
@@ -92,7 +92,7 @@
# Call SLICOT routine to place the eigenvalues
A_z,w,nfp,nap,nup,F,Z = \
- sb01bd(B_mat.shape[0], B_mat.shape[1], len(placed_eigs), alpha,
+ sb01bd(B_mat.shape[0], B_mat.shape[1], np.size(placed_eigs), alpha,
A_mat, B_mat, placed_eigs, 'C');
# Return the gain matrix, with MATLAB gain convention
@@ -184,3 +184,57 @@
E = w[0:nstates];
return K, S, E
+
+def ctrb(A,B):
+ """Controllabilty matrix
+
+ Usage
+ =====
+ Wc = ctrb(A, B)
+
+ Inputs
+ ------
+ A, B: Dynamics and input matrix of the system
+
+ Outputs
+ -------
+ Wc: Controllability matrix
+ """
+
+ # Convert input parameters to matrices (if they aren't already)
+ amat = np.mat(A)
+ bmat = np.mat(B)
+ n = np.shape(amat)[0]
+
+ # Construct the controllability matrix
+ ctrb = bmat
+ for i in range(1, n):
+ ctrb = np.vstack((ctrb, amat**i*bmat))
+ return ctrb
+
+def obsv(A, C):
+ """Observability matrix
+
+ Usage
+ =====
+ Wc = obsv(A, C)
+
+ Inputs
+ ------
+ A, C: Dynamics and output matrix of the system
+
+ Outputs
+ -------
+ Wc: Observability matrix
+ """
+
+ # Convert input parameters to matrices (if they aren't already)
+ amat = np.mat(A)
+ cmat = np.mat(C)
+ n = np.shape(amat)[0]
+
+ # Construct the controllability matrix
+ obsv = cmat
+ for i in range(1, n):
+ obsv = np.hstack((obsv, cmat*amat**i))
+ return obsv
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|