|
From: <mur...@us...> - 2011-04-03 04:55:59
|
Revision: 152
http://python-control.svn.sourceforge.net/python-control/?rev=152&view=rev
Author: murrayrm
Date: 2011-04-03 04:55:51 +0000 (Sun, 03 Apr 2011)
Log Message:
-----------
Small fixes based on testing + re-added root locus
* Implemented syntax checks for MATLAB functions
* Fixed root locus plots to work with new SF, TF classes
* Transfer functions with integer coeffs now convered to floats
* More detailed list of changes in ChangeLog
Modified Paths:
--------------
trunk/ChangeLog
trunk/Pending
trunk/examples/secord-matlab.py
trunk/src/__init__.py
trunk/src/exception.py
trunk/src/freqplot.py
trunk/src/matlab.py
trunk/src/rlocus.py
trunk/src/xferfcn.py
trunk/tests/matlab_test.py
Modified: trunk/ChangeLog
===================================================================
--- trunk/ChangeLog 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/ChangeLog 2011-04-03 04:55:51 UTC (rev 152)
@@ -1,5 +1,38 @@
2011-04-02 Richard Murray <mu...@ma...>
+ * src/xferfcn.py (TransferFunction.__add__): fixed bug when adding a
+ transfer function to state space system; _convertToTransferFunction
+ was being called with input/output keywords. Picked up in unit test.
+
+ * tests/matlab_test.py: added calls to all of the functions that are
+ currently implemented in the library, to make sure there are no
+ hidden issues. These calls do *not* test functionality, they just
+ make sure that MATLAB compatibility functions accept the right types
+ of arguments.
+
+ * examples/secord-matlab.py: added root locus plot to list of
+ figures that are produced
+
+ * src/__init__.py: added rlocus to list of modules that are imported
+ by control module
+
+ * src/exception.py (ControlMIMONotImplemented): added exception for
+ functions that are not yet implemented for MIMO systems
+
+ * src/xferfcn.py (TransferFunction.__init__): convert integer
+ numerator and denominator objects to floats to eliminate errors when
+ creating common denominator (also used on pole command). This fixes
+ and error were tf([1], [1, 2, 1]).pole() would generate an error.
+
+ * src/freqplot.py (bode): Tweaked documentation string to remove 'h'
+ from mag and phase return arguments
+
+ * src/rlocus.py (RootLocus): removed commands that set figure number
+ inside of RootLocus command, for consistency with other frequency
+ plot routines. Added Plot=True argument and updated documentation.
+
+ * src/matlab.py: added rlocus() command (calls RootLocus)
+
* MANIFEST.in: Added MANIFEST.in file to include examples and tests
in source distribution
Modified: trunk/Pending
===================================================================
--- trunk/Pending 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/Pending 2011-04-03 04:55:51 UTC (rev 152)
@@ -12,7 +12,7 @@
* matlab.step() doesn't handle systems with a pole at the origin (use lsim2)
* TF <-> SS transformations are buggy; see tests/convert_test.py
* hsvd returns different value than MATLAB (2010a); see modelsimp_test.py
- * MIMO common denominator fails unit test; see convert_test.py
+ * lsim doesn't work for StateSpace systems (signal.lsim2 bug??)
Transfer code from Roberto Bucher's yottalab to python-control
acker - pole placement using Ackermann method
@@ -44,23 +44,15 @@
* tests/freqresp.py needs to be converted to unit test
* Convert examples/test-{response,statefbk}.py to unit tests
-TransferFunction class fixes
- * evalfr is not working (num, den stored as ndarrays, not poly1ds)
+Root locus plot improvements
+ * Make sure that scipy.signal.lti objects still work
+ * Update calling syntax to be consistent with other plotting commands
-Block diagram algebra fixes
- * Implement state space block diagram algebra
- * Produce minimal realizations to avoid later errors
-
State space class fixes
- * Convert pvtol to state space systems and rerun example
* Implement pzmap for state space systems
-LTI updates
- * 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)
* lyap - solve Lyapunov equation (use SLICOT SB03MD.f)
* See http://www.slicot.org/shared/libindex.html for list of functions
Modified: trunk/examples/secord-matlab.py
===================================================================
--- trunk/examples/secord-matlab.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/examples/secord-matlab.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -27,3 +27,7 @@
# Nyquist plot for the system
figure(3)
nyquist(sys, logspace(-2, 2))
+
+# Root lcous plut for the system
+figure(4)
+rlocus(sys)
Modified: trunk/src/__init__.py
===================================================================
--- trunk/src/__init__.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/__init__.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -64,3 +64,4 @@
from statefbk import *
from delay import *
from modelsimp import *
+from rlocus import *
Modified: trunk/src/exception.py
===================================================================
--- trunk/src/exception.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/exception.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -52,6 +52,10 @@
"""Raised when arguments to a function are not correct"""
pass
+class ControlMIMONotImplemented(Exception):
+ """Function is not currently implemented for MIMO systems"""
+ pass
+
class ControlNotImplemented(Exception):
"""Functionality is not yet implemented"""
pass
Modified: trunk/src/freqplot.py
===================================================================
--- trunk/src/freqplot.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/freqplot.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -60,7 +60,7 @@
Usage
=====
- (magh, phaseh, omega) = bode(syslist, omega=None, dB=False, Hz=False, color=None, Plot=True)
+ (mag, phase, omega) = bode(syslist, omega=None, dB=False, Hz=False, color=None, Plot=True)
Plots a Bode plot for the system over a (optional) frequency range.
@@ -79,8 +79,8 @@
Return values
-------------
- magh : magnitude array
- phaseh : phase array
+ mag : magnitude array
+ phase : phase array
omega : frequency array
Notes
Modified: trunk/src/matlab.py
===================================================================
--- trunk/src/matlab.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/matlab.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -179,7 +179,7 @@
\* ss/modred - model order reduction
Compensator design
- rlocus - evans root locus
+\* rlocus - evans root locus
\* place - pole placement
estim - form estimator given estimator gain
reg - form regulator given state-feedback and estimator gains
@@ -187,7 +187,7 @@
LQR/LQG design
ss/lqg - single-step LQG design
\* lqr - linear-Quadratic (LQ) state-feedback regulator
-\* dlqr - discrete-time LQ state-feedback regulator
+ dlqr - discrete-time LQ state-feedback regulator
lqry - lq regulator with output weighting
lqrd - discrete LQ regulator for continuous plant
ss/lqi - linear-Quadratic-Integral (LQI) controller
@@ -243,8 +243,8 @@
Overloaded arithmetic operations
\* + and - - add and subtract systems (parallel connection)
\* \* - multiply systems (series connection)
-\* / - left divide -- sys1\sys2 means inv(sys1)\*sys2
-\* / - right divide -- sys1/sys2 means sys1\*inv(sys2)
+ / - left divide -- sys1\sys2 means inv(sys1)\*sys2
+- \ - right divide -- sys1/sys2 means sys1\*inv(sys2)
^ - powers of a given system
' - pertransposition
.' - transposition of input/output map
@@ -758,12 +758,35 @@
from nichols import nichols_grid
nichols_grid()
+# Root locus plot
+def rlocus(sys, klist = None, **keywords):
+ """Root locus plot
+
+ Parameters
+ ----------
+ sys: StateSpace or TransferFunction object
+ klist: optional list of gains
+
+ Returns
+ -------
+ rlist: list of roots for each gain
+ klist: list of gains used to compute roots
+ """
+ from rlocus import RootLocus
+ if (klist == None):
+ #! TODO: update with a smart cacluation of the gains
+ klist = logspace(-3, 3)
+
+ rlist = RootLocus(sys, klist, **keywords)
+ return rlist, klist
+
+
#
# Modifications to scipy.signal functions
#
# Redefine lsim to use lsim2
-def lsim(*args, **keywords):
+def lsim(sys, U=None, T=None, X0=None, **keywords):
"""Simulate the output of a linear system
Examples
@@ -784,12 +807,13 @@
yout: response of the system
xout: time evolution of the state vector
"""
- sys = args[0]
+ # Convert the system to an signal.lti for simulation
+ #! This should send a warning for MIMO systems
ltiobjs = sys.returnScipySignalLti()
ltiobj = ltiobjs[0][0]
-
- return sp.signal.lsim2(ltiobj, **keywords)
+ return sp.signal.lsim2(ltiobj, U, T, X0, **keywords)
+
#! Redefine step to use lsim2
#! Not yet implemented
def step(*args, **keywords):
Modified: trunk/src/rlocus.py
===================================================================
--- trunk/src/rlocus.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/rlocus.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -37,65 +37,93 @@
# * Added BSD copyright info to file (per Ryan)
# * Added code to convert (num, den) to poly1d's if they aren't already.
# This allows Ryan's code to run on a standard signal.ltisys object
-# or a controls.TransferFunction object.
+# or a control.TransferFunction object.
# * Added some comments to make sure I understand the code
+#
+# RMM, 2 April 2011: modified to work with new Lti structure (see ChangeLog)
+# * Not tested: should still work on signal.ltisys objects
#
# $Id$
# Packages used by this module
from scipy import *
+import scipy.signal # signal processing toolbox
+import pylab # plotting routines
+import xferfcn # transfer function manipulation
# Main function: compute a root locus diagram
-def RootLocus(sys, kvect, fig=None, fignum=1, \
- clear=True, xlim=None, ylim=None, plotstr='-'):
+def RootLocus(sys, kvect, xlim=None, ylim=None, plotstr='-', Plot=True):
"""Calculate the root locus by finding the roots of 1+k*TF(s)
where TF is self.num(s)/self.den(s) and each k is an element
- of kvect."""
+ of kvect.
+ Parameters
+ ----------
+ sys : linsys
+ Linear input/output systems (SISO only, for now)
+ klist : gain_range (default = None)
+ List of gains to use in computing diagram
+ Plot : boolean (default = True)
+ If True, plot magnitude and phase
+
+ Return values
+ -------------
+ rlist : list of computed root locations
+ klist : list of gains
+ """
+
# Convert numerator and denominator to polynomials if they aren't
(nump, denp) = _systopoly1d(sys);
- # Set up the figure
- if fig is None:
- import pylab
- fig = pylab.figure(fignum)
- if clear:
- fig.clf()
- ax = fig.add_subplot(111)
-
# Compute out the loci
mymat = _RLFindRoots(sys, kvect)
mymat = _RLSortRoots(sys, mymat)
- # plot open loop poles
- poles = array(denp.r)
- ax.plot(real(poles), imag(poles), 'x')
+ # Create the plot
+ if (Plot):
+ ax = pylab.axes();
- # plot open loop zeros
- zeros = array(nump.r)
- if zeros.any():
- ax.plot(real(zeros), imag(zeros), 'o')
+ # plot open loop poles
+ poles = array(denp.r)
+ ax.plot(real(poles), imag(poles), 'x')
- # Now plot the loci
- for col in mymat.T:
- ax.plot(real(col), imag(col), plotstr)
+ # plot open loop zeros
+ zeros = array(nump.r)
+ if zeros.any():
+ ax.plot(real(zeros), imag(zeros), 'o')
- # Set up plot axes and labels
- if xlim:
- ax.set_xlim(xlim)
- if ylim:
- ax.set_ylim(ylim)
- ax.set_xlabel('Real')
- ax.set_ylabel('Imaginary')
+ # Now plot the loci
+ for col in mymat.T:
+ ax.plot(real(col), imag(col), plotstr)
+
+ # Set up plot axes and labels
+ if xlim:
+ ax.set_xlim(xlim)
+ if ylim:
+ ax.set_ylim(ylim)
+ ax.set_xlabel('Real')
+ ax.set_ylabel('Imaginary')
+
return mymat
# Utility function to extract numerator and denominator polynomials
def _systopoly1d(sys):
"""Extract numerator and denominator polynomails for a system"""
+ # Allow inputs from the signal processing toolbox
+ if (isinstance(sys, scipy.signal.lti)):
+ nump = sys.num; denp = sys.den;
- # Start by extracting the numerator and denominator from system object
- nump = sys.num; denp = sys.den;
+ else:
+ # Convert to a transfer function, if needed
+ sys = xferfcn._convertToTransferFunction(sys)
+ # Make sure we have a SISO system
+ if (sys.inputs > 1 or sys.outputs > 1):
+ raise ControlMIMONotImplemented()
+
+ # Start by extracting the numerator and denominator from system object
+ nump = sys.num[0][0]; denp = sys.den[0][0];
+
# Check to see if num, den are already polynomials; otherwise convert
if (not isinstance(nump, poly1d)): nump = poly1d(nump)
if (not isinstance(denp, poly1d)): denp = poly1d(denp)
Modified: trunk/src/xferfcn.py
===================================================================
--- trunk/src/xferfcn.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/src/xferfcn.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -129,11 +129,20 @@
for i in range(len(data)):
if isinstance(data[i], (int, float, long, complex)):
# Convert scalar to list of list of array.
- data[i] = [[array([data[i]])]]
+ if (isinstance(data[i], int)):
+ # Convert integers to floats at this point
+ data[i] = [[array([data[i]], dtype=float)]]
+ else:
+ data[i] = [[array([data[i]])]]
elif (isinstance(data[i], (list, tuple, ndarray)) and
isinstance(data[i][0], (int, float, long, complex))):
# Convert array to list of list of array.
- data[i] = [[array(data[i])]]
+ if (isinstance(data[i][0], int)):
+ # Convert integers to floats at this point
+ #! Not sure this covers all cases correctly
+ data[i] = [[array(data[i], dtype=float)]]
+ else:
+ data[i] = [[array(data[i])]]
elif (isinstance(data[i], list) and
isinstance(data[i][0], list) and
isinstance(data[i][0][0], (list, tuple, ndarray)) and
@@ -142,7 +151,10 @@
# coefficient vectors to arrays, if necessary.
for j in range(len(data[i])):
for k in range(len(data[i][j])):
- data[i][j][k] = array(data[i][j][k])
+ if (isinstance(data[i][j][k], int)):
+ data[i][j][k] = array(data[i][j][k], dtype=float)
+ else:
+ data[i][j][k] = array(data[i][j][k])
else:
# If the user passed in anything else, then it's unclear what
# the meaning is.
@@ -274,7 +286,9 @@
"""Add two LTI objects (parallel connection)."""
# Convert the second argument to a transfer function.
- if not isinstance(other, TransferFunction):
+ if (isinstance(other, statesp.StateSpace)):
+ other = _convertToTransferFunction(other)
+ elif not isinstance(other, TransferFunction):
other = _convertToTransferFunction(other, inputs=self.inputs,
outputs=self.outputs)
@@ -513,6 +527,7 @@
# A sorted list to keep track of cumulative poles found as we scan
# self.den.
poles = []
+
# A 3-D list to keep track of common denominator poles not present in
# the self.den[i][j].
missingpoles = [[[] for j in range(self.inputs)] for i in
Modified: trunk/tests/matlab_test.py
===================================================================
--- trunk/tests/matlab_test.py 2011-04-02 19:32:33 UTC (rev 151)
+++ trunk/tests/matlab_test.py 2011-04-03 04:55:51 UTC (rev 152)
@@ -2,47 +2,229 @@
#
# matlab_test.py - test MATLAB compatibility
# RMM, 30 Mar 2011 (based on TestMatlab from v0.4a)
+#
+# This test suite just goes through and calls all of the MATLAB
+# functions using different systems and arguments to make sure that
+# nothing crashes. It doesn't test actual functionality; the module
+# specific unit tests will do that.
import unittest
import numpy as np
from control.matlab import *
class TestMatlab(unittest.TestCase):
- def testStep(self):
+ def setUp(self):
+ """Set up some systems for testing out MATLAB functions"""
A = np.matrix("1. -2.; 3. -4.")
B = np.matrix("5.; 7.")
C = np.matrix("6. 8.")
D = np.matrix("9.")
- sys = ss(A,B,C,D)
+ self.siso_ss1 = ss(A,B,C,D)
+
+ # Create some transfer functions
+ self.siso_tf1 = tf([1], [1, 2, 1]);
+ self.siso_tf2 = tf([1, 1], [1, 2, 3, 1]);
+
+ # Conversions
+ self.siso_tf3 = tf(self.siso_ss1);
+ self.siso_ss2 = ss(self.siso_tf2);
+ self.siso_ss3 = tf2ss(self.siso_tf3);
+ self.siso_tf4 = ss2tf(self.siso_ss2);
+
+ def testParallel(self):
+ sys1 = parallel(self.siso_ss1, self.siso_ss2)
+ sys1 = parallel(self.siso_ss1, self.siso_tf2)
+ sys1 = parallel(self.siso_tf1, self.siso_ss2)
+ sys1 = parallel(1, self.siso_ss2)
+ sys1 = parallel(1, self.siso_tf2)
+ sys1 = parallel(self.siso_ss1, 1)
+ sys1 = parallel(self.siso_tf1, 1)
+
+ def testSeries(self):
+ sys1 = series(self.siso_ss1, self.siso_ss2)
+ sys1 = series(self.siso_ss1, self.siso_tf2)
+ sys1 = series(self.siso_tf1, self.siso_ss2)
+ sys1 = series(1, self.siso_ss2)
+ sys1 = series(1, self.siso_tf2)
+ sys1 = series(self.siso_ss1, 1)
+ sys1 = series(self.siso_tf1, 1)
+
+ def testFeedback(self):
+ sys1 = feedback(self.siso_ss1, self.siso_ss2)
+ sys1 = feedback(self.siso_ss1, self.siso_tf2)
+ sys1 = feedback(self.siso_tf1, self.siso_ss2)
+ sys1 = feedback(1, self.siso_ss2)
+ sys1 = feedback(1, self.siso_tf2)
+ sys1 = feedback(self.siso_ss1, 1)
+ sys1 = feedback(self.siso_tf1, 1)
+
+ def testPoleZero(self):
+ pole(self.siso_ss1);
+ pole(self.siso_tf1);
+ pole(self.siso_tf2);
+ zero(self.siso_ss1);
+ zero(self.siso_tf1);
+ zero(self.siso_tf2);
+
+ def testPZmap(self):
+ # pzmap(self.siso_ss1); not implemented
+ # pzmap(self.siso_ss2); not implemented
+ pzmap(self.siso_tf1);
+ pzmap(self.siso_tf2);
+ pzmap(self.siso_tf2, Plot=False);
+
+ def testStep(self):
+ sys = self.siso_ss1
t = np.linspace(0, 1, 10)
t, yout = step(sys, T=t)
youttrue = np.matrix("9. 17.6457 24.7072 30.4855 35.2234 39.1165 42.3227 44.9694 47.1599 48.9776")
np.testing.assert_array_almost_equal(yout, youttrue,decimal=4)
def testImpulse(self):
- A = np.matrix("1. -2.; 3. -4.")
- B = np.matrix("5.; 7.")
- C = np.matrix("6. 8.")
- D = np.matrix("9.")
- sys = ss(A,B,C,D)
+ sys = self.siso_ss1
t = np.linspace(0, 1, 10)
t, yout = impulse(sys, T=t)
youttrue = np.matrix("86. 70.1808 57.3753 46.9975 38.5766 31.7344 26.1668 21.6292 17.9245 14.8945")
np.testing.assert_array_almost_equal(yout, youttrue,decimal=4)
# def testInitial(self):
-# A = np.matrix("1. -2.; 3. -4.")
-# B = np.matrix("5.; 7.")
-# C = np.matrix("6. 8.")
-# D = np.matrix("9.")
-# sys = ss(A,B,C,D)
+ sys = self.siso_ss1
# t = np.linspace(0, 1, 10)
# x0 = np.matrix(".5; 1.")
# t, yout = initial(sys, T=t, X0=x0)
# youttrue = np.matrix("11. 8.1494 5.9361 4.2258 2.9118 1.9092 1.1508 0.5833 0.1645 -0.1391")
# np.testing.assert_array_almost_equal(yout, youttrue,decimal=4)
+ def testLsim(self):
+ T = range(1, 100)
+ u = np.sin(T)
+ lsim(self.siso_tf1, u, T)
+ # lsim(self.siso_ss1, u, T) # generates error??
+ # lsim(self.siso_ss1, u, T, self.siso_ss1.B)
+ def testBode(self):
+ bode(self.siso_ss1)
+ bode(self.siso_tf1)
+ bode(self.siso_tf2)
+ (mag, phase, freq) = bode(self.siso_tf2, Plot=False)
+ bode(self.siso_tf1, self.siso_tf2)
+ w = logspace(-3, 3);
+ bode(self.siso_ss1, w)
+ bode(self.siso_ss1, self.siso_tf2, w)
+ bode(self.siso_ss1, '-', self.siso_tf1, 'b--', self.siso_tf2, 'k.')
+
+ def testRlocus(self):
+ rlocus(self.siso_ss1)
+ rlocus(self.siso_tf1)
+ rlocus(self.siso_tf2)
+ rlist, klist = rlocus(self.siso_tf2, klist=[1, 10, 100], Plot=False)
+
+ def testNyquist(self):
+ nyquist(self.siso_ss1)
+ nyquist(self.siso_tf1)
+ nyquist(self.siso_tf2)
+ w = logspace(-3, 3);
+ nyquist(self.siso_tf2, w)
+ (real, imag, freq) = nyquist(self.siso_tf2, w, Plot=False)
+
+ def testNichols(self):
+ nichols(self.siso_ss1)
+ nichols(self.siso_tf1)
+ nichols(self.siso_tf2)
+ w = logspace(-3, 3);
+ nichols(self.siso_tf2, w)
+ nichols(self.siso_tf2, grid=False)
+
+ def testFreqresp(self):
+ w = logspace(-3, 3)
+ freqresp(self.siso_ss1, w)
+ freqresp(self.siso_ss2, w)
+ freqresp(self.siso_ss3, w)
+ freqresp(self.siso_tf1, w)
+ freqresp(self.siso_tf2, w)
+ freqresp(self.siso_tf3, w)
+
+ def testEvalfr(self):
+ w = 1
+ evalfr(self.siso_ss1, w)
+ evalfr(self.siso_ss2, w)
+ evalfr(self.siso_ss3, w)
+ evalfr(self.siso_tf1, w)
+ evalfr(self.siso_tf2, w)
+ evalfr(self.siso_tf3, w)
+
+ def testHsvd(self):
+ hsvd(self.siso_ss1)
+ hsvd(self.siso_ss2)
+ hsvd(self.siso_ss3)
+
+ def testBalred(self):
+ balred(self.siso_ss1, 1)
+ balred(self.siso_ss2, 2)
+ balred(self.siso_ss3, [2, 2])
+
+ def testModred(self):
+ modred(self.siso_ss1, [1])
+ modred(self.siso_ss2 * self.siso_ss3, [1, 2])
+ modred(self.siso_ss3, [1], 'matchdc')
+ modred(self.siso_ss3, [1], 'truncate')
+
+ def testPlace(self):
+ place(self.siso_ss1.A, self.siso_ss1.B, [-2, -2])
+
+ def testLQR(self):
+ (K, S, E) = lqr(self.siso_ss1.A, self.siso_ss1.B, np.eye(2), np.eye(1))
+ (K, S, E) = lqr(self.siso_ss2.A, self.siso_ss2.B, np.eye(3), \
+ np.eye(1), [[1], [1], [2]])
+
+ def testRss(self):
+ rss(1)
+ rss(2)
+ rss(2, 3, 1)
+
+ def testDrss(self):
+ drss(1)
+ drss(2)
+ drss(2, 3, 1)
+
+ def testCtrb(self):
+ ctrb(self.siso_ss1.A, self.siso_ss1.B)
+ ctrb(self.siso_ss2.A, self.siso_ss2.B)
+
+ def testObsv(self):
+ obsv(self.siso_ss1.A, self.siso_ss1.C)
+ obsv(self.siso_ss2.A, self.siso_ss2.C)
+
+ def testGram(self):
+ gram(self.siso_ss1, 'c')
+ gram(self.siso_ss2, 'c')
+ gram(self.siso_ss1, 'o')
+ gram(self.siso_ss2, 'o')
+
+ def testPade(self):
+ pade(1, 1)
+ pade(1, 2)
+ pade(5, 4)
+
+ def testOpers(self):
+ self.siso_ss1 + self.siso_ss2
+ self.siso_tf1 + self.siso_tf2
+ self.siso_ss1 + self.siso_tf2
+ self.siso_tf1 + self.siso_ss2
+ self.siso_ss1 * self.siso_ss2
+ self.siso_tf1 * self.siso_tf2
+ self.siso_ss1 * self.siso_tf2
+ self.siso_tf1 * self.siso_ss2
+ # self.siso_ss1 / self.siso_ss2 not implemented yet
+ # self.siso_tf1 / self.siso_tf2
+ # self.siso_ss1 / self.siso_tf2
+ # self.siso_tf1 / self.siso_ss2
+
+ def testUnwrap(self):
+ phase = np.array(range(1, 100)) / 10.;
+ wrapped = phase % (2 * np.pi)
+ unwrapped = unwrap(wrapped)
+
def suite():
return unittest.TestLoader().loadTestsFromTestCase(TestMatlab)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|