You can subscribe to this list here.
2010 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
(19) |
Jul
|
Aug
|
Sep
|
Oct
|
Nov
(11) |
Dec
(5) |
---|---|---|---|---|---|---|---|---|---|---|---|---|
2011 |
Jan
|
Feb
(113) |
Mar
(12) |
Apr
(27) |
May
(2) |
Jun
(16) |
Jul
(6) |
Aug
(6) |
Sep
|
Oct
(3) |
Nov
(9) |
Dec
(2) |
2012 |
Jan
(5) |
Feb
(11) |
Mar
|
Apr
(3) |
May
|
Jun
|
Jul
|
Aug
(3) |
Sep
(7) |
Oct
(18) |
Nov
(18) |
Dec
|
2013 |
Jan
(4) |
Feb
(1) |
Mar
(3) |
Apr
(1) |
May
|
Jun
(33) |
Jul
(2) |
Aug
(5) |
Sep
|
Oct
|
Nov
|
Dec
(1) |
2014 |
Jan
(1) |
Feb
|
Mar
(8) |
Apr
|
May
(3) |
Jun
(3) |
Jul
(9) |
Aug
(5) |
Sep
(6) |
Oct
|
Nov
|
Dec
|
2015 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
(4) |
2017 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
(5) |
Nov
|
Dec
|
2018 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
(1) |
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
2019 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
(6) |
Sep
|
Oct
|
Nov
(2) |
Dec
|
2020 |
Jan
(1) |
Feb
(1) |
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
2021 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
(4) |
Oct
|
Nov
|
Dec
|
From: <mur...@us...> - 2011-06-18 19:13:17
|
Revision: 161 http://python-control.svn.sourceforge.net/python-control/?rev=161&view=rev Author: murrayrm Date: 2011-06-18 19:13:09 +0000 (Sat, 18 Jun 2011) Log Message: ----------- Added Eike's Welk's time response functions, including MIMO capability. To maintain MATLAB compatibility, the underlying functions have been moved to a new module, timeresp, and renamed ForcedResponse (lsim), InitialResponse (initial), ImpulseResponse (impulse), StepResponse (step). MATLAB version of the functions (with the usual names: lsim, impulse, initial, step) use MATLAB conventions for time vectors. See ChangeLog for detailed list of changes. Modified Paths: -------------- trunk/ChangeLog trunk/doc/conf.py trunk/examples/pvtol-lqr.py trunk/examples/pvtol-nested-ss.py trunk/examples/pvtol-nested.py trunk/src/__init__.py trunk/src/matlab.py trunk/src/statesp.py trunk/tests/matlab_test.py Added Paths: ----------- trunk/src/timeresp.py trunk/tests/test_control_matlab.py trunk/tests/timeresp_test.py Modified: trunk/ChangeLog =================================================================== --- trunk/ChangeLog 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/ChangeLog 2011-06-18 19:13:09 UTC (rev 161) @@ -1,3 +1,66 @@ +2011-06-18 Richard Murray <murray@malabar.local> + + * src/timeresp.py, src/matlab.py: moved documentation about time + series convention from matlab.py to timeresp.py + + * examples/pvtol-nested-ss.py: Fixed bug in call to step (wrong + second argument) + + * tests/matlab_test.py: Updated tests to use MATLAB time response + conventions. + + * tests/timeresp_test.py: Created unit tests for timeresp module, + based on matlab_test.py + +2011-06-17 Richard Murray <murray@malabar.local> + + * src/timeresp.py (ForcedResponse): swapped order of input and time + arguments for linear response, following Eike's comment "T must + always be supplied by the user, but U has a useful default value of + 0." + + * src/matlab.py: moved code for lsim, initial, step, and impulse to + timeresp.py and put in new routes that call timeresp.* versions of + the functions with transposeData set to True. + + * src/timesim.py (_check_convert_array): added transpose argument + that will transpose input data before processing it. + + * src/timesim.py: renamed lsim, initial, step, and impulse functions + to ForcedResponse, InitialResponse, StepResponse and + ImpulseResponse. These versions use Eike Welk's input ordering. + + * examples/pvtol-nested.py: calls to step() had screwed up inputs. + Fixed. + +2011-06-17 Richard Murray <murray@malabar.local> + + * src/matlab.py: added MIMO extensions from Eike Welk on 12 Jun + 2011: adds MIMO capabilities for ``lsim``, ``step``, ``impulse``, + ``initial`` + + * src/matlab.py: added changes from Eike Welk on 12 May 2011: + + - An implementation of the four simulation functions ``lsim``, + ``step``, ``initial``, and ``impulse`` of the module ``matlab``. + + - Adds a function ``dcgain`` to the ``matlab`` module, which + computes the gain of a linear system for steady state and + constant input. + + - The patch contains a bug fix for class ``StateSpace``, which + enables it to work properly together with Scipy's ``signal`` + module. + + - The simulation functions' return values are changed (back?) to + arrays, because matrices confuse Matplotlib. + + - New times series convention: see _time-series-convention section + of matlab documentation + + - SISO simulation data are squeezed on output. To turn this off, + pass the option squeeze=False + ---- control-0.4c released ----- 2011-06-17 Richard Murray <mu...@dh...> Modified: trunk/doc/conf.py =================================================================== --- trunk/doc/conf.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/doc/conf.py 2011-06-18 19:13:09 UTC (rev 161) @@ -26,7 +26,8 @@ # Add any Sphinx extension module names here, as strings. They can be extensions # coming with Sphinx (named 'sphinx.ext.*') or your custom ones. -extensions = ['sphinx.ext.autodoc','numpydoc'] +extensions = ['sphinx.ext.autodoc', 'numpydoc', 'sphinx.ext.pngmath', + 'sphinx.ext.intersphinx'] # Add any paths that contain templates here, relative to this directory. templates_path = ['_templates'] @@ -87,7 +88,11 @@ # A list of ignored prefixes for module index sorting. #modindex_common_prefix = [] +#This config value contains the locations and names of other projects that +#should be linked to in this documentation. +intersphinx_mapping = {'scipy':('http://docs.scipy.org/doc/scipy/reference/', None)} + # -- Options for HTML output --------------------------------------------------- # The theme to use for HTML and HTML Help pages. See the documentation for Modified: trunk/examples/pvtol-lqr.py =================================================================== --- trunk/examples/pvtol-lqr.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/examples/pvtol-lqr.py 2011-06-18 19:13:09 UTC (rev 161) @@ -119,7 +119,7 @@ subplot(221); title("Identity weights") # plot(T, Y[:,1, 1], '-', T, Y[:,2, 2], '--'); hold(True); -plot(Tx.T, Yx[0,:].T, '-', Ty.T, Yy[0,:].T, '--'); hold(True); +plot(Tx.T, Yx.T, '-', Ty.T, Yy.T, '--'); hold(True); plot([0, 10], [1, 1], 'k-'); hold(True); axis([0, 10, -0.1, 1.4]); @@ -141,9 +141,9 @@ [T3, Y3] = step(H1cx, T=linspace(0,10,100)); subplot(222); title("Effect of input weights") -plot(T1.T, Y1[0,:].T, 'b-'); hold(True); -plot(T2.T, Y2[0,:].T, 'b-'); hold(True); -plot(T3.T, Y3[0,:].T, 'b-'); hold(True); +plot(T1.T, Y1.T, 'b-'); hold(True); +plot(T2.T, Y2.T, 'b-'); hold(True); +plot(T3.T, Y3.T, 'b-'); hold(True); plot([0 ,10], [1, 1], 'k-'); hold(True); axis([0, 10, -0.1, 1.4]); @@ -162,7 +162,7 @@ subplot(223); title("Output weighting") [T2x, Y2x] = step(H2x, T=linspace(0,10,100)); [T2y, Y2y] = step(H2y, T=linspace(0,10,100)); -plot(T2x.T, Y2x[0,:].T, T2y.T, Y2y[0,:].T) +plot(T2x.T, Y2x.T, T2y.T, Y2y.T) ylabel('position'); xlabel('time'); ylabel('position'); legend(('x', 'y'), loc='lower right'); @@ -185,7 +185,7 @@ # step(H3x, H3y, 10); [T3x, Y3x] = step(H3x, T=linspace(0,10,100)); [T3y, Y3y] = step(H3y, T=linspace(0,10,100)); -plot(T3x.T, Y3x[0,:].T, T3y.T, Y3y[0,:].T) +plot(T3x.T, Y3x.T, T3y.T, Y3y.T) title("Physically motivated weights") xlabel('time'); legend(('x', 'y'), loc='lower right'); Modified: trunk/examples/pvtol-nested-ss.py =================================================================== --- trunk/examples/pvtol-nested-ss.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/examples/pvtol-nested-ss.py 2011-06-18 19:13:09 UTC (rev 161) @@ -144,10 +144,10 @@ # 'EdgeColor', color, 'FaceColor', color); figure(9); -(Tvec, Yvec) = step(T, None, linspace(1, 20)); +(Tvec, Yvec) = step(T, linspace(1, 20)); plot(Tvec.T, Yvec.T); hold(True); -(Tvec, Yvec) = step(Co*S, None, linspace(1, 20)); +(Tvec, Yvec) = step(Co*S, linspace(1, 20)); plot(Tvec.T, Yvec.T); #TODO: PZmap for statespace systems has not yet been implemented. Modified: trunk/examples/pvtol-nested.py =================================================================== --- trunk/examples/pvtol-nested.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/examples/pvtol-nested.py 2011-06-18 19:13:09 UTC (rev 161) @@ -134,10 +134,10 @@ # 'EdgeColor', color, 'FaceColor', color); figure(9); -(Tvec, Yvec) = step(T, None, linspace(1, 20)); +(Tvec, Yvec) = step(T, linspace(1, 20)); plot(Tvec.T, Yvec.T); hold(True); -(Tvec, Yvec) = step(Co*S, None, linspace(1, 20)); +(Tvec, Yvec) = step(Co*S, linspace(1, 20)); plot(Tvec.T, Yvec.T); figure(10); clf(); Modified: trunk/src/__init__.py =================================================================== --- trunk/src/__init__.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/src/__init__.py 2011-06-18 19:13:09 UTC (rev 161) @@ -66,3 +66,5 @@ from modelsimp import * from rlocus import * from mateqn import * +from timeresp import ForcedResponse, InitialResponse, StepResponse, \ + ImpulseResponse Modified: trunk/src/matlab.py =================================================================== --- trunk/src/matlab.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/src/matlab.py 2011-06-18 19:13:09 UTC (rev 161) @@ -1,3 +1,4 @@ +# -*- coding: utf-8 -*- """matlab.py MATLAB emulation functions. @@ -18,6 +19,8 @@ """Copyright (c) 2009 by California Institute of Technology All rights reserved. +Copyright (c) 2011 by Eike Welk + Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: @@ -58,8 +61,9 @@ # Libraries that we make use of import scipy as sp # SciPy library (used all over) import numpy as np # NumPy library -import scipy.signal as signal # Signal processing library +from scipy.signal.ltisys import _default_response_times from copy import deepcopy +import warnings # Import MATLAB-like functions that are defined in other packages from scipy.signal import zpk2ss, ss2zpk, tf2zpk, zpk2tf @@ -68,8 +72,10 @@ # Control system library import ctrlutil import freqplot +import timeresp from statesp import StateSpace, _rss_generate, _convertToStateSpace from xferfcn import TransferFunction, _convertToTransferFunction +from lti import Lti #base class of StateSpace, TransferFunction from exception import ControlArgument # Import MATLAB-like functions that can be used as-is @@ -86,188 +92,216 @@ __doc__ += """ The control.matlab module defines functions that are roughly the equivalents of those in the MATLAB Control Toolbox. Items marked by a -\* are currently implemented; those marked with a ``-`` are not planned +``*`` are currently implemented; those marked with a ``-`` are not planned for implementation. -Creating linear models. -\* tf - create transfer function (TF) models - zpk - create zero/pole/gain (ZPK) models. -\* ss - create state-space (SS) models - dss - create descriptor state-space models - delayss - create state-space models with delayed terms - frd - create frequency response data (FRD) models - lti/exp - create pure continuous-time delays (TF and ZPK only) - filt - specify digital filters -- lti/set - set/modify properties of LTI models -- setdelaymodel - specify internal delay model (state space only) - -Data extraction - lti/tfdata - extract numerators and denominators - lti/zpkdata - extract zero/pole/gain data - lti/ssdata - extract state-space matrices - lti/dssdata - descriptor version of SSDATA - frd/frdata - extract frequency response data - lti/get - access values of LTI model properties - ss/getDelayModel - access internal delay model (state space only) - -Conversions -\* tf - conversion to transfer function - zpk - conversion to zero/pole/gain -\* ss - conversion to state space - frd - conversion to frequency data - c2d - continuous to discrete conversion - d2c - discrete to continuous conversion - d2d - resample discrete-time model - upsample - upsample discrete-time LTI systems -\* ss2tf - state space to transfer function - ss2zpk - transfer function to zero-pole-gain -\* tf2ss - transfer function to state space - tf2zpk - transfer function to zero-pole-gain - zpk2ss - zero-pole-gain to state space - zpk2tf - zero-pole-gain to transfer function - -System interconnections - append - group LTI models by appending inputs and outputs -\* parallel - connect LTI models in parallel (see also overloaded +) -\* series - connect LTI models in series (see also overloaded \*) -\* feedback - connect lti models with a feedback loop - lti/lft - generalized feedback interconnection - lti/connect - arbitrary interconnection of lti models - sumblk - specify summing junction (for use with connect) - strseq - builds sequence of indexed strings (for I/O naming) - -System gain and dynamics - dcgain - steady-state (D.C.) gain - lti/bandwidth - system bandwidth - lti/norm - h2 and Hinfinity norms of LTI models -\* lti/pole - system poles -\* lti/zero - system (transmission) zeros - lti/order - model order (number of states) -\* pzmap - pole-zero map (TF only) - lti/iopzmap - input/output pole-zero map - damp - natural frequency and damping of system poles - esort - sort continuous poles by real part - dsort - sort discrete poles by magnitude - lti/stabsep - stable/unstable decomposition - lti/modsep - region-based modal decomposition - -Time-domain analysis -\* step - step response - stepinfo - step response characteristics (rise time, ...) -\* impulse - impulse response - initial - free response with initial conditions -\* lsim - response to user-defined input signal - lsiminfo - linear response characteristics - gensig - generate input signal for LSIM - covar - covariance of response to white noise - -Frequency-domain analysis -\* bode - Bode plot of the frequency response - lti/bodemag - Bode magnitude diagram only - sigma - singular value frequency plot -\* nyquist - Nyquist plot -\* nichols - Nichols plot - margin - gain and phase margins - lti/allmargin - all crossover frequencies and related gain/phase margins -\* lti/freqresp - frequency response over a frequency grid -\* lti/evalfr - evaluate frequency response at given frequency - -Model simplification - minreal - minimal realization and pole/zero cancellation - ss/sminreal - structurally minimal realization (state space) -\* lti/hsvd - hankel singular values (state contributions) -\* lti/balred - reduced-order approximations of LTI models -\* ss/modred - model order reduction - -Compensator design -\* rlocus - evans root locus -\* place - pole placement - estim - form estimator given estimator gain - reg - form regulator given state-feedback and estimator gains - -LQR/LQG design - ss/lqg - single-step LQG design -\* lqr - linear-Quadratic (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 - ss/kalman - Kalman state estimator - ss/kalmd - discrete Kalman estimator for continuous plant - ss/lqgreg - build LQG regulator from LQ gain and Kalman estimator - ss/lqgtrack - build LQG servo-controller - augstate - augment output by appending states - -State-space (SS) models -\* rss - random stable continuous-time state-space models -\* 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 -\* gram - controllability and observability gramians - ss/prescale - optimal scaling of state-space models. - balreal - gramian-based input/output balancing - ss/xperm - reorder states. - -Frequency response data (FRD) models - frd/chgunits - change frequency vector units - frd/fcat - merge frequency responses - frd/fselect - select frequency range or subgrid - frd/fnorm - peak gain as a function of frequency - frd/abs - entrywise magnitude of the frequency response - frd/real - real part of the frequency response - frd/imag - imaginary part of the frequency response - frd/interp - interpolate frequency response data - mag2db - convert magnitude to decibels (dB) - db2mag - convert decibels (dB) to magnitude - -Time delays - 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 - -Model dimensions and characteristics - class - model type ('tf', 'zpk', 'ss', or 'frd') - isa - test if model is of given type - tf/size - model sizes - lti/ndims - number of dimensions - lti/isempty - true for empty models - lti/isct - true for continuous-time models - lti/isdt - true for discrete-time models - lti/isproper - true for proper models - lti/issiso - true for single-input/single-output models - lti/isstable - true for models with stable dynamics - lti/reshape - reshape array of linear models - -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) - ^ - powers of a given system - ' - pertransposition - .' - transposition of input/output map - .\* - element-by-element multiplication - [..] - concatenate models along inputs or outputs - lti/stack - stack models/arrays along some array dimension - lti/inv - inverse of an LTI system - lti/conj - complex conjugation of model coefficients - -Matrix equation solvers and linear algebra -\* lyap, dlyap - solve Lyapunov equations - lyapchol, dlyapchol - square-root Lyapunov solvers -\* care, dare - solve algebraic Riccati equations - gcare, gdare - generalized Riccati solvers - bdschur - block diagonalization of a square matrix - -Additional functions -\* gangof4 - generate the Gang of 4 sensitivity plots -\* linspace - generate a set of numbers that are linearly spaced -\* logspace - generate a set of numbers that are logarithmically spaced -\* unwrap - unwrap a phase angle to give a continuous curve - +== ========================== ================================================ +**Creating linear models.** +-------------------------------------------------------------------------------- +\* :func:`tf` create transfer function (TF) models +\ zpk create zero/pole/gain (ZPK) models. +\* :func:`ss` create state-space (SS) models +\ dss create descriptor state-space models +\ delayss create state-space models with delayed terms +\ frd create frequency response data (FRD) models +\ lti/exp create pure continuous-time delays (TF and ZPK + only) +\ filt specify digital filters +\- lti/set set/modify properties of LTI models +\- setdelaymodel specify internal delay model (state space only) +\ +**Data extraction** +-------------------------------------------------------------------------------- +\ lti/tfdata extract numerators and denominators +\ lti/zpkdata extract zero/pole/gain data +\ lti/ssdata extract state-space matrices +\ lti/dssdata descriptor version of SSDATA +\ frd/frdata extract frequency response data +\ lti/get access values of LTI model properties +\ ss/getDelayModel access internal delay model (state space only) +\ +**Conversions** +-------------------------------------------------------------------------------- +\* :func:`tf` conversion to transfer function +\ zpk conversion to zero/pole/gain +\* :func:`ss` conversion to state space +\ frd conversion to frequency data +\ c2d continuous to discrete conversion +\ d2c discrete to continuous conversion +\ d2d resample discrete-time model +\ upsample upsample discrete-time LTI systems +\* :func:`ss2tf` state space to transfer function +\ ss2zpk transfer function to zero-pole-gain +\* :func:`tf2ss` transfer function to state space +\ tf2zpk transfer function to zero-pole-gain +\ zpk2ss zero-pole-gain to state space +\ zpk2tf zero-pole-gain to transfer function +\ +**System interconnections** +-------------------------------------------------------------------------------- +\ append group LTI models by appending inputs and outputs +\* :func:`parallel` connect LTI models in parallel + (see also overloaded +) +\* :func:`series` connect LTI models in series + (see also overloaded \*) +\* :func:`feedback` connect lti models with a feedback loop +\ lti/lft generalized feedback interconnection +\ lti/connect arbitrary interconnection of lti models +\ sumblk specify summing junction (for use with connect) +\ strseq builds sequence of indexed strings + (for I/O naming) +\ +**System gain and dynamics** +-------------------------------------------------------------------------------- +\* :func:`dcgain` steady-state (D.C.) gain +\ lti/bandwidth system bandwidth +\ lti/norm h2 and Hinfinity norms of LTI models +\* :func:`pole` system poles +\* :func:`zero` system (transmission) zeros +\ lti/order model order (number of states) +\* :func:`pzmap` pole-zero map (TF only) +\ lti/iopzmap input/output pole-zero map +\ damp natural frequency and damping of system poles +\ esort sort continuous poles by real part +\ dsort sort discrete poles by magnitude +\ lti/stabsep stable/unstable decomposition +\ lti/modsep region-based modal decomposition +\ +**Time-domain analysis** +-------------------------------------------------------------------------------- +\* :func:`step` step response +\ stepinfo step response characteristics (rise time, ...) +\* :func:`impulse` impulse response +\* :func:`initial` free response with initial conditions +\* :func:`lsim` response to user-defined input signal +\ lsiminfo linear response characteristics +\ gensig generate input signal for LSIM +\ covar covariance of response to white noise +\ +**Frequency-domain analysis** +-------------------------------------------------------------------------------- +\* :func:`bode` Bode plot of the frequency response +\ lti/bodemag Bode magnitude diagram only +\ sigma singular value frequency plot +\* :func:`nyquist` Nyquist plot +\* :func:`nichols` Nichols plot +\* :func:`margin` gain and phase margins +\ lti/allmargin all crossover frequencies and related gain/phase + margins +\* :func:`freqresp` frequency response over a frequency grid +\* :func:`evalfr` evaluate frequency response at given frequency +\ +**Model simplification** +-------------------------------------------------------------------------------- +\ minreal minimal realization and pole/zero cancellation +\ ss/sminreal structurally minimal realization (state space) +\* :func:`lti/hsvd` hankel singular values (state contributions) +\* :func:`lti/balred` reduced-order approximations of LTI models +\* :func:`ss/modred` model order reduction +\ +**Compensator design** +-------------------------------------------------------------------------------- +\* :func:`rlocus` evans root locus +\* :func:`place` pole placement +\ estim form estimator given estimator gain +\ reg form regulator given state-feedback and + estimator gains +\ +**LQR/LQG design** +-------------------------------------------------------------------------------- +\ ss/lqg single-step LQG design +\* :func:`lqr` linear-Quadratic (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 +\ ss/kalman Kalman state estimator +\ ss/kalmd discrete Kalman estimator for continuous plant +\ ss/lqgreg build LQG regulator from LQ gain and Kalman + estimator +\ ss/lqgtrack build LQG servo-controller +\ augstate augment output by appending states +\ +**State-space (SS) models** +-------------------------------------------------------------------------------- +\* :func:`rss` random stable continuous-time state-space models +\* :func:`drss` random stable discrete-time state-space models +\ ss2ss state coordinate transformation +\ canon canonical forms of state-space models +\* :func:`ctrb` controllability matrix +\* :func:`obsv` observability matrix +\* :func:`gram` controllability and observability gramians +\ ss/prescale optimal scaling of state-space models. +\ balreal gramian-based input/output balancing +\ ss/xperm reorder states. +\ +**Frequency response data (FRD) models** +-------------------------------------------------------------------------------- +\ frd/chgunits change frequency vector units +\ frd/fcat merge frequency responses +\ frd/fselect select frequency range or subgrid +\ frd/fnorm peak gain as a function of frequency +\ frd/abs entrywise magnitude of the frequency response +\ frd/real real part of the frequency response +\ frd/imag imaginary part of the frequency response +\ frd/interp interpolate frequency response data +\ mag2db convert magnitude to decibels (dB) +\ db2mag convert decibels (dB) to magnitude +\ +**Time delays** +-------------------------------------------------------------------------------- +\ 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 +\* :func:`pade` pade approximation of time delays +\ +**Model dimensions and characteristics** +-------------------------------------------------------------------------------- +\ class model type ('tf', 'zpk', 'ss', or 'frd') +\ isa test if model is of given type +\ tf/size model sizes +\ lti/ndims number of dimensions +\ lti/isempty true for empty models +\ lti/isct true for continuous-time models +\ lti/isdt true for discrete-time models +\ lti/isproper true for proper models +\ lti/issiso true for single-input/single-output models +\ lti/isstable true for models with stable dynamics +\ lti/reshape reshape array of linear models +\ +**Overloaded arithmetic operations** +-------------------------------------------------------------------------------- +\* \+ and - add and subtract systems (parallel connection) +\* \* multiply systems (series connection) +\ / right divide -- sys1/sys2 means sys1\*inv(sys2) +\- \\ left divide -- sys1\\sys2 means inv(sys1)\*sys2 +\ ^ powers of a given system +\ ' pertransposition +\ .' transposition of input/output map +\ .\* element-by-element multiplication +\ [..] concatenate models along inputs or outputs +\ lti/stack stack models/arrays along some array dimension +\ lti/inv inverse of an LTI system +\ lti/conj complex conjugation of model coefficients +\ +**Matrix equation solvers and linear algebra** +-------------------------------------------------------------------------------- +\* lyap, dlyap solve Lyapunov equations +\ lyapchol, dlyapchol square-root Lyapunov solvers +\* care, dare solve algebraic Riccati equations +\ gcare, gdare generalized Riccati solvers +\ bdschur block diagonalization of a square matrix +\ +**Additional functions** +-------------------------------------------------------------------------------- +\* :func:`gangof4` generate the Gang of 4 sensitivity plots +\* :func:`linspace` generate a set of numbers that are linearly + spaced +\* :func:`logspace` generate a set of numbers that are + logarithmically spaced +\* :func:`unwrap` unwrap a phase angle to give a continuous curve +== ========================== ================================================ """ def ss(*args): @@ -752,9 +786,9 @@ def ngrid(): """Nichols chart grid. - Usage - ===== - ngrid() + Examples + -------- + >>> ngrid() """ from nichols import nichols_grid nichols_grid() @@ -815,134 +849,81 @@ % len(args)) return margins[0], margins[1], margins[3], margins[4] -# -# Modifications to scipy.signal functions -# -# Redefine lsim to use lsim2 -def lsim(sys, U=None, T=None, X0=None, **keywords): - """Simulate the output of a linear system - Examples - -------- - >>> T, yout, xout = lsim(sys, u, T, X0) +def dcgain(*args): + ''' + Compute the gain of the system in steady state. - Parameters - ---------- - sys: StateSpace, or TransferFunction - LTI system to simulate - u: input array giving input at each time T - T: time steps at which the input is defined - X0: initial condition (optional, default = 0) + The function takes either 1, 2, 3, or 4 parameters: - Returns - ------- - T: time values of the output - yout: response of the system - xout: time evolution of the state vector - """ - # 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, U, T, X0, **keywords) - -#! Redefine step to use lsim2 -#! Not yet implemented -def step(*args, **keywords): - """Step response of a linear system - - Examples - -------- - >>> T, yout = step(sys, T, X0) - Parameters ---------- - sys: StateSpace, or TransferFunction - T: array - T is the time vector (optional; autocomputed if not given) - X0: array - X0 is the initial condition (optional; default = 0) + A, B, C, D: array-like + A linear system in state space form. + Z, P, k: array-like, array-like, number + A linear system in zero, pole, gain form. + num, den: array-like + A linear system in transfer function form. + sys: Lti (StateSpace or TransferFunction) + A linear system object. Returns ------- - T: array - Time values of the output - yout: array - response of the system - """ - sys = args[0] - ltiobjs = sys.returnScipySignalLti() - ltiobj = ltiobjs[0][0] + gain: matrix + The gain of each output versus each input: + :math:`y = gain \cdot u` + + Notes + ----- + This function is only useful for systems with invertible system + matrix ``A``. + + All systems are first converted to state space form. The function then + computes: + + .. math:: gain = - C \cdot A^{-1} \cdot B + D + ''' + #Convert the parameters to state space form + if len(args) == 4: + A, B, C, D = args + sys = ss(A, B, C, D) + elif len(args) == 3: + Z, P, k = args + A, B, C, D = zpk2ss(Z, P, k) + sys = ss(A, B, C, D) + elif len(args) == 2: + num, den = args + sys = tf2ss(num, den) + elif len(args) == 1: + sys, = args + sys = ss(sys) + else: + raise ValueError("Function ``dcgain`` needs either 1, 2, 3 or 4 " + "arguments.") + #gain = - C * A**-1 * B + D + gain = sys.D - sys.C * sys.A.I * sys.B + return gain - out = sp.signal.step(ltiobj, **keywords) - yout = [] - yout.append(np.mat(out[0])) - yout.append(out[1]) - yout = tuple(yout) - return yout +# Simulation routines +# Call corresponding functions in timeresp, with arguments transposed -# Redefine initial to use lsim2 -#! Not yet implemented (uses step for now) -def initial(*args, **keywords): - """Initial condition response of a linear system +def step(sys, T=None, X0=0., input=0, output=0, **keywords): + T, yout = timeresp.StepResponse(sys, T, X0, input, output, + transpose = True, **keywords) + return T, yout - Examples - -------- - >>> T, yout = initial(sys, T, X0) +def impulse(sys, T=None, X0=0., input=0, output=0, **keywords): + T, yout = timeresp.ImpulseResponse(sys, T, X0, input, output, + transpose = True, **keywords) + return T, yout - Parameters - ---------- - sys: StateSpace, or TransferFunction - T: array - T is the time vector (optional; autocomputed if not given) - X0: array - X0 is the initial condition (optional; default = 0) +def initial(sys, T=None, X0=0., input=0, output=0, **keywords): + T, yout = timeresp.InitialResponse(sys, T, X0, input, output, + transpose = True, **keywords) + return T, yout - Returns - ------- - T: array - Time values of the output - yout: array - response of the system - - """ - sys = args[0] - ltiobjs = sys.returnScipySignalLti() - ltiobj = ltiobjs[0][0] - - yout = sp.signal.initial(ltiobj, **keywords) - return np.mat(yout) - -# Redefine impulse to use initial() -#! Not yet implemented (uses impulse for now) -def impulse(*args, **keywords): - """Impulse response of a linear system - - Examples - -------- - >>> T, yout = impulse(sys, T, X0) - - Parameters - ---------- - sys: StateSpace, or TransferFunction - T: array - T is the time vector (optional; autocomputed if not given) - X0: array - X0 is the initial condition (optional; default = 0) - - Returns - ------- - T: array - Time values of the output - yout: array - response of the system - - """ - sys = args[0] - ltiobjs = sys.returnScipySignalLti() - ltiobj = ltiobjs[0][0] - - yout = sp.signal.impulse(ltiobj, **keywords) - return np.mat(yout) +def lsim(sys, U=0., T=None, X0=0., **keywords): + T, yout, xout = timeresp.ForcedResponse(sys, T, U, X0, + transpose = True, **keywords) + return T, yout, xout Modified: trunk/src/statesp.py =================================================================== --- trunk/src/statesp.py 2011-06-18 00:20:49 UTC (rev 160) +++ trunk/src/statesp.py 2011-06-18 19:13:09 UTC (rev 161) @@ -1,3 +1,4 @@ +# -*- coding: utf-8 -*- """stateSpace.py State space representation and functions. @@ -72,8 +73,9 @@ """ -from numpy import all, angle, any, array, concatenate, cos, delete, dot, \ - empty, exp, eye, matrix, ones, pi, poly, poly1d, roots, shape, sin, zeros +from numpy import all, angle, any, array, asarray, concatenate, cos, delete, \ + dot, empty, exp, eye, matrix, ones, pi, poly, poly1d, roots, shape, sin, \ + zeros from numpy.random import rand, randn from numpy.linalg import inv, det, solve from numpy.linalg.linalg import LinAlgError @@ -427,8 +429,8 @@ for i in range(self.outputs): for j in range(self.inputs): - out[i][j] = lti(self.A, self.B[:, j], self.C[i, :], - self.D[i, j]) + out[i][j] = lti(asarray(self.A), asarray(self.B[:, j]), + asarray(self.C[i, :]), asarray(self.D[i, j])) return out Added: trunk/src/timeresp.py =================================================================== --- trunk/src/timeresp.py (rev 0) +++ trunk/src/timeresp.py 2011-06-18 19:13:09 UTC (rev 161) @@ -0,0 +1,652 @@ +# timesim.py - time-domain simulation routes +"""timesim.py + +Time domain simulation. + +Copyright (c) 2010 by SciPy Developers + +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. + +Author: Eike Welk +Date: 12 May 2011 +$Id: matlab.py 157 2011-06-17 23:51:46Z murrayrm $ + +.. _time-series-convention: + +Convention for Time Series +-------------------------- + +This is a convention for function arguments and return values that +represent time series: sequences of values that change over time. It is used +throughout the library, for example in the functions :func:`lsim`, :func:`step`, +:func:`impulse`, and :func:`initial`. + +.. note:: + This convention is different from the convention used in the library + :mod:`scipy.signal`. In Scipy's convention the meaning of rows and columns + is interchanged. All 2D values must be transposed when they are used with + functions from :mod:`scipy.signal`. + +Types: + + * **Arguments** can be **arrays**, **matrices**, or **nested lists**. + * **Return values** are **arrays** (not matrices). + +The time vector is either 1D, or 2D with shape (1, n):: + + T = [[t1, t2, t3, ..., tn ]] + +Input, state, and output all follow the same convention. Columns are different +points in time, rows are different components. When there is only one row, a +1D object is accepted or returned, which adds convenience for SISO systems:: + + U = [[u1(t1), u1(t2), u1(t3), ..., u1(tn)] + [u2(t1), u2(t2), u2(t3), ..., u2(tn)] + ... + ... + [ui(t1), ui(t2), ui(t3), ..., ui(tn)]] + + Same for X, Y + +The initial conditions are either 1D, or 2D with shape (j, 1):: + + X0 = [[x1] + [x2] + ... + ... + [xj]] + +So, U[:,2] is the system's input at the third point in time; and U[1] or U[1,:] +is the sequence of values for the system's second input. + +As all simulation functions return *arrays*, plotting is convenient:: + + t, y = step(sys) + plot(t, y) + +The output of a MIMO system can be plotted like this:: + + t, y, x = lsim(sys, u, t) + plot(t, y[0], label='y_0') + plot(t, y[1], label='y_1') + +The convention also works well with the state space form of linear systems. If +``D`` is the feedthrough *matrix* of a linear system, and ``U`` is its input +(*matrix* or *array*), then the feedthrough part of the system's response, +can be computed like this:: + + ft = D * U + +---------------------------------------------------------------- + +""" + +# Libraries that we make use of +import scipy as sp # SciPy library (used all over) +import numpy as np # NumPy library +from scipy.signal.ltisys import _default_response_times +from copy import deepcopy +import warnings +from statesp import StateSpace, _rss_generate, _convertToStateSpace +from lti import Lti # base class of StateSpace, TransferFunction + +# +# Solve the systems's differential equations +# + +def _check_convert_array(in_obj, legal_shapes, err_msg_start, squeeze=False, + transpose=False): + """ + Helper function for checking array-like parameters. + + * Check type and shape of ``in_obj``. + * Convert ``in_obj`` to an array if necessary. + * Change shape of ``in_obj`` according to parameter ``squeeze``. + * If ``in_obj`` is a scalar (number) it is converted to an array with + a legal shape, that is filled with the scalar value. + + The function raises an exception when it detects an error. + + Parameters: + + in_obj: array like object + The array or matrix which is checked. + + legal_shapes: list of tuple + A list of shapes that in_obj can legally have. + The special value "any" means that there can be any + number of elements in a certain dimension. + + * ``(2, 3)`` describes an array with 2 rows and 3 columns + * ``(2, "any")`` describes an array with 2 rows and any number of + columns + + err_msg_start: str + String that is prepended to the error messages, when this function + raises an exception. It should be used to identify the argument which + is currently checked. + + squeeze: bool + If True, all dimensions with only one element are removed from the + array. If False the array's shape is unmodified. + + For example: + ``array([[1,2,3]])`` is converted to ``array([1, 2, 3])`` + + transpose: bool + If True, assume that input arrays are transposed for the standard + format. Used to convert MATLAB-style inputs to our format. + + Returns: + + out_array: array + The checked and converted contents of ``in_obj``. + """ + #convert nearly everything to an array. + out_array = np.asarray(in_obj) + if (transpose): + out_array = np.transpose(out_array) + + #Test element data type, elements must be numbers + legal_kinds = set(("i", "f", "c")) #integer, float, complex + if out_array.dtype.kind not in legal_kinds: + err_msg = "Wrong element data type: '{d}'. Array elements " \ + "must be numbers.".format(d=str(out_array.dtype)) + raise TypeError(err_msg_start + err_msg) + + #If array is zero dimensional (in_obj is scalar): + #create array with legal shape filled with the original value. + if out_array.ndim == 0: + for s_legal in legal_shapes: + #search for shape that does not contain the special symbol any. + if "any" in s_legal: + continue + the_val = out_array[()] + out_array = np.empty(s_legal, 'd') + out_array.fill(the_val) + break + + #Test shape + def shape_matches(s_legal, s_actual): + """Test if two shape tuples match""" + #Array must have required number of dimensions + if len(s_legal) != len(s_actual): + return False + #All dimensions must contain required number of elements. Joker: "all" + for n_legal, n_actual in zip(s_legal, s_actual): + if n_legal == "any": + continue + if n_legal != n_actual: + return False + return True + + #Iterate over legal shapes, and see if any matches out_array's shape. + for s_legal in legal_shapes: + if shape_matches(s_legal, out_array.shape): + break + else: + legal_shape_str = " or ".join([str(s) for s in legal_shapes]) + err_msg = "Wrong shape (rows, columns): {a}. Expected: {e}." \ + .format(e=legal_shape_str, a=str(out_array.shape)) + raise ValueError(err_msg_start + err_msg) + + #Convert shape + if squeeze: + out_array = np.squeeze(out_array) + #We don't want zero dimensional arrays + if out_array.shape == tuple(): + out_array = out_array.reshape((1,)) + + return out_array + +# Forced response of a linear system +def ForcedResponse(sys, T=None, U=0., X0=0., transpose=False, **keywords): + """Simulate the output of a linear system. + + As a convenience for parameters `U`, `X0`: + Numbers (scalars) are converted to constant arrays with the correct shape. + The correct shape is inferred from arguments `sys` and `T`. + + For information on the **shape** of parameters `U`, `T`, `X0` and + return values `T`, `yout`, `xout` see: :ref:`time-series-convention` + + Parameters + ---------- + sys: Lti (StateSpace, or TransferFunction) + LTI system to simulate + + T: array-like + Time steps at which the input is defined, numbers must be (strictly + monotonic) increasing. + + U: array-like or number, optional + Input array giving input at each time `T` (default = 0). + + If `U` is ``None`` or ``0``, a special algorithm is used. This special + algorithm is faster than the general algorithm, which is used otherwise. + + X0: array-like or number, optional + Initial condition (default = 0). + + transpose: bool + If True, transpose all input and output arrays (for backward + compatibility with MATLAB and scipy.signal.lsim) + + **keywords: + Additional keyword arguments control the solution algorithm for the + differential equations. These arguments are passed on to the function + :func:`scipy.integrate.odeint`. See the documentation for + :func:`scipy.integrate.odeint` for information about these + arguments. + + Returns + ------- + T: array + Time values of the output. + yout: array + Response of the system. + xout: array + Time evolution of the state vector. + + See Also + -------- + StepResponse, InitialResponse, ImpulseResponse + + Examples + -------- + >>> T, yout, xout = ForcedResponse(sys, T, u, X0) + """ + if not isinstance(sys, Lti): + raise TypeError('Parameter ``sys``: must be a ``Lti`` object. ' + '(For example ``StateSpace`` or ``TransferFunction``)') + sys = _convertToStateSpace(sys) + A, B, C, D = np.asarray(sys.A), np.asarray(sys.B), np.asarray(sys.C), \ + np.asarray(sys.D) +# d_type = A.dtype + n_states = A.shape[0] + n_inputs = B.shape[1] + + #Test if T has shape (n,) or (1, n); + #T must be array-like and values must be increasing. + #The length of T determines the length of the input vector. + if T is None: + raise ValueError('Parameter ``T``: must be array-like, and contain ' + '(strictly monotonic) increasing numbers.') + T = _check_convert_array(T, [('any',), (1,'any')], + 'Parameter ``T``: ', squeeze=True, + transpose = transpose) + if not all(T[1:] - T[:-1] > 0): + raise ValueError('Parameter ``T``: time values must be ' + '(strictly monotonic) increasing numbers.') + n_steps = len(T) #number of simulation steps + + #create X0 if not given, test if X0 has correct shape + X0 = _check_convert_array(X0, [(n_states,), (n_states,1)], + 'Parameter ``X0``: ', squeeze=True) + + #Solve the differential equation, copied from scipy.signal.ltisys. + dot, squeeze, = np.dot, np.squeeze #Faster and shorter code + #Faster algorithm if U is zero + if U is None or (isinstance(U, (int, float)) and U == 0): + #Function that computes the time derivative of the linear system + def f_dot(x, _t): + return dot(A,x) + + xout = sp.integrate.odeint(f_dot, X0, T, **keywords) + yout = dot(C, xout.T) + #General algorithm that interpolates U in between output points + else: + #Test if U has correct shape and type + legal_shapes = [(n_steps,), (1,n_steps)] if n_inputs == 1 else \ + [(n_inputs, n_steps)] + U = _check_convert_array(U, legal_shapes, + 'Parameter ``U``: ', squeeze=False, + transpose=transpose) + #convert 1D array to D2 array with only one row + if len(U.shape) == 1: + U = U.reshape(1,-1) #pylint: disable=E1103 + + #Create a callable that uses linear interpolation to + #calculate the input at any time. + compute_u = sp.interpolate.interp1d(T, U, kind='linear', copy=False, + axis=-1, bounds_error=False, + fill_value=0) + + #Function that computes the time derivative of the linear system + def f_dot(x, t): + return dot(A,x) + squeeze(dot(B,compute_u([t]))) + + xout = sp.integrate.odeint(f_dot, X0, T, **keywords) + yout = dot(C, xout.T) + dot(D, U) + + yout = squeeze(yout) + xout = xout.T + + # See if we need to transpose the data back into MATLAB form + if (transpose): + T = np.transpose(T) + yout = np.transpose(yout) + xout = np.transpose(xout) + + return T, yout, xout + +def StepResponse(sys, T=None, X0=0., input=0, output=0, \ + transpose = False, **keywords): + #pylint: disable=W0622 + """Step response of a linear system + + If the system has multiple inputs or outputs (MIMO), one input and one + output have to be selected for the simulation. The parameters `input` + and `output` do this. All other inputs are set to 0, all other outputs + are ignored. + + For information on the **shape** of parameters `T`, `X0` and + return values `T`, `yout` see: :ref:`time-series-convention` + + Parameters + ---------- + sys: StateSpace, or TransferFunction + LTI system to simulate + + T: array-like object, optional + Time vector (argument is autocomputed if not given) + + X0: array-like or number, optional + Initial condition (default = 0) + + Numbers are converted to constant arrays with the correct shape. + + input: int + Index of the input that will be used in this simulation. + + output: int + Index of the output that will be used in this simulation. + + transpose: bool + If True, transpose all input and output arrays (for backward + compatibility with MATLAB and scipy.signal.lsim) + + **keywords: + Additional keyword arguments control the solution algorithm for the + differential equations. These arguments are passed on to the function + :func:`lsim`, which in turn passes them on to + :func:`scipy.integrate.odeint`. See the documentation for + :func:`scipy.integrate.odeint` for information about these + arguments. + + Returns + ------- + T: array + Time values of the output + + yout: array + Response of the system + + See Also + -------- + lsim, initial, impulse + + Examples + -------- + >>> T, yout = step(sys, T, X0) + """ + sys = _convertToStateSpace(sys) + sys = _mimo2siso(sys, input, output, warn_conversion=True) + if T is None: + T = _default_response_times(sys.A, 100) + U = np.ones_like(T) + + T, yout, _xout = ForcedResponse(sys, T, U, X0, + transpose = transpose, **keywords) + + return T, yout + + +def InitialResponse(sys, T=None, X0=0., input=0, output=0, transpose=False, + **keywords): + #pylint: disable=W0622 + """Initial condition response of a linear system + + If the system has multiple inputs or outputs (MIMO), one input and one + output have to be selected for the simulation. The parameters `input` + and `output` do this. All other inputs are set to 0, all other outputs + are ignored. + + For information on the **shape** of parameters `T`, `X0` and + return values `T`, `yout` see: :ref:`time-series-convention` + + Parameters + ---------- + sys: StateSpace, or TransferFunction + LTI system to simulate + + T: array-like object, optional + Time vector (argument is autocomputed if not given) + + X0: array-like object or number, optional + Initial condition (default = 0) + + Numbers are converted to constant arrays with the correct shape. + + input: int + Index of the input that will be used in this simulation. + + output: int + Index of the output that will be used in this simulation. + + transpose: bool + If True, transpose all input and output arrays (for backward + compatibility with MATLAB and scipy.signal.lsim) + + **keywords: + Additional keyword arguments control the solution algorithm for the + differential equations. These arguments are passed on to the function + :func:`lsim`, which in turn passes them on to + :func:`scipy.integrate.odeint`. See the documentation for + :func:`scipy.integrate.odeint` for information about these + arguments. + + + Returns + ------- + T: array + Time values of the output + yout: array + Response of the system + + See Also + -------- + lsim, step, impulse + + Examples + -------- + >>> T, yout = InitialResponsesys, T, X0) + """ + sys = _convertToStateSpace(sys) + sys = _mimo2siso(sys, input, output, warn_conversion=True) + #Create time and input vectors; checking is done in ForcedResponse(...) + #The initial vector X0 is created in ForcedResponse(...) if necessary + if T is None: + T = _default_response_times(sys.A, 100) + U = np.zeros_like(T) + + T, yout, _xout = ForcedResponse(sys, T, U, X0, **keywords) + return T, yout + + +def ImpulseResponse(sys, T=None, X0=0., input=0, output=0, + transpose=False, **keywords): + #pylint: disable=W0622 + """Impulse response of a linear system + + If the system has multiple inputs or outputs (MIMO), one input and one + output have to be selected for the simulation. The parameters `input` + and `output` do this. All other inputs are set to 0, all other outputs + are ignored. + + For information on the **shape** of parameters `T`, `X0` and + return values `T`, `yout` see: :ref:`time-series-convention` + + Parameters + ---------- + sys: StateSpace, TransferFunction + LTI system to simulate + + T: array-like object, optional + Time vector (argument is autocomputed if not given) + + X0: array-like object or number, optional + Initial condition (default = 0) + + Numbers are converted to constant arrays with the correct shape. + + input: int + Index of the input that will be used in this simulation. + + output: int + Index of the output that will be used in this simulation. + + transpose: bool + If True, transpose all input and output arrays (for backward + compatibility with MATLAB and scipy.signal.lsim) + + **keywords: + Additional keyword arguments control the solution algorithm for the + differential equations. These arguments are passed on to the function + :func:`lsim`, which in turn passes them on to + :func:`scipy.integrate.odeint`. See the documentation for + :func:`scipy.integrate.odeint` for information about these + arguments. + + + Returns + ------- + T: array + Time values of the output + yout: array + Response of the system + + See Also + -------- + lsim, step, initial + + Examples + -------- + >>> T, yout = ImpulseResponse(sys, T, X0) + """ + sys = _convertToStateSpace(sys) + sys = _mimo2siso(sys, input, output, warn_conversion=True) + + #System has direct feedthrough, can't simulate impulse response numerically. + if np.any(sys.D != 0): + warnings.warn('System has direct feedthrough: ``D != 0``. The infinite ' + 'impulse at ``t=0`` does not appear in the output. \n' + 'Results may be meaningless!') + + #create X0 if not given, test if X0 has correct shape. + #Must be done here because it is used for computations here. + n_states = sys.A.shape[0] + X0 = _check_convert_array(X0, [(n_states,), (n_states,1)], + 'Parameter ``X0``: \n', squeeze=True) + + #Compute new X0 that contains the impulse + #We can't put the impulse into U because there is no numerical + #representation for it (infinitesimally short, infinitely high). + #See also: http://www.mathworks.com/support/tech-notes/1900/1901.html + B = np.asarray(sys.B).squeeze() + new_X0 = B + X0 + + #Compute T and U, no checks necessary, they will be checked in lsim + if T is None: + T = _default_response_times(sys.A, 100) + U = np.zeros_like(T) + + T, yout, _xout = ForcedResponse(sys, T, U, new_X0, \ + transpose=transpose, **keywords) + return T, yout + +#! TODO: this function probably belongs in a different file +def _mimo2siso(sys, input, output, warn_conversion): + #pylint: disable=W0622 + """ + Convert a MIMO system to a SISO system. (Convert a system with multiple + inputs and/or outputs, to a system with a single input and output.) + + The input and output that are used in the SISO system can be selected + with the parameters ``input`` and ``output``. All other inputs are set + to 0, all other outputs are ignored. + + If ``sys`` is already a SISO system, it will be returned unaltered. + + Parameters: + + sys... [truncated message content] |
From: Richard M. <mu...@cd...> - 2011-06-18 01:02:15
|
Eike, I'm working on integrating some of the functionality that you contributed to the python-control package. Your new convention for simulation inputs and outputs has a lot of nice features, but it does "break" current code (eg, try running examples/pvtol-nested.py). In addition, it is not compatible with the way MATLAB or scipy.signal does things, which could be confusing. As a general principle, I think that if a user imports control.matlab, they should get as MATLAB like an environment as possible (since control.matlab is the MATLAB emulation module in the package). However, I see now reason why we need to maintain MATLAB compatibility within the underlying library itself, where we can do things in a more python-like way. But breaking the convention used by scipy.signal could get confusing... Here is one possible fix: * We move your current lsim, initial, step and impulse code into a separate module (timesim.py or something) in the control-python package. * We create version of the code in matlab.py that convert the arguments from MATLAB (and scipy.signal) form into the form you use, and back. * In addition, we could include a flag in all of the simulation routines that let them swap around the convention if the flag was turned out (eg, 'scipy-signal-convention = true' would make things work in the way that is compatible with the signal module). This approach has the advantage that we get a pretty clean interface for python users, but something that is consistent with MATLAB in the emulation library. On the other hand, it could be incredibly confusing for people who use both interfaces. Let me know what you think about this (others on the list as well). If we do decide to switch the way time series are represented from the current version, we would have to update the version number to something like 0.5a (instead of 0.4d) since we would be breaking existing code. -richard On 12 May 2011, at 16:11 , Eike Welk wrote: > Hello! > > I have written a patch for the Python Control Systems Library with the > following contents: > > * An implementation of the four simulation functions ``lsim``, ``step``, > ``initial``, and ``impulse`` of the module ``matlab``. > > * It also adds a function ``dcgain`` to the ``matlab`` module, which computes > the gain of a linear system for steady state and constant input. > > * The patch contains a bug fix for class ``StateSpace``, which enables it to > work properly together with Scipy's ``signal`` module. > > * The simulation functions' return values are changed (back?) to arrays, > because matrices confuse Matplotlib. > > http://sourceforge.net/tracker/?func=detail&aid=3301246&group_id=282523&atid=1198311 > > > Would you include my patch into the library? > > What do you think about the parameter convention below? IMHO a detailed > section that explains the used convention should be included in the module's > documentation. The documentation of the individual functions should link to > it. > > What is the proper communication channel for the library's developers? > > If you include my patch, my next step would be to extend ``lsim`` to MIMO > systems (by copying the code from ``scipy.signal.lsim2``); and to convert the > module's documentation to proper reStructuredText. > > > Implementation Notes > ------------------- > > The implementation is centered around ``lsim``, which checks the parameters > thoroughly, and generates useful error messages. It then calls > ``scipy.signal.lsim2`` to solve the differential equations. The other > simulation functions (``step``, ``initial``, ``impulse``) are small and call > ``lsim``. > > > Parameter Convention > -------------------- > > The new convention for parameters and return values harmonizes with the way > how the system equations are written. It can be generalized to MIMO systems, > and it also works well with Matplotlib: > > All parameters can be arrays, matrices, or nested lists. > > The time vector is either 1D, or 2D with shape (1, n):: > > T = [[t1, t2, t3, ..., tn ]] > > Input, state, and output all follow the same convention. Columns are different > points in time, rows are different components. When there is only one row, a > 1D object is accepted or returned, which adds convenience for SISO systems:: > > U = [[u1(t1), u1(t2), u1(t3), ..., u1(tn)] > [u2(t1), u2(t2), u2(t3), ..., u2(tn)] > ... > ... > [ui(t1), ui(t2), ui(t3), ..., ui(tn)]] > > Same for X, Y > > The initial conditions are either 1D, or 2D with shape (j, 1):: > > X0 = [[u1] > [u2] > ... > ... > [uj]] > > So, U[:,2] is the system's input at the third point in time; and U[1] or > U[1,:] is the sequence of values for the system's second input. > > As all simulation functions return array plotting is convenient:: > > t, y = step(sys) > plot(t, y) > > The output of a MIMO system would be plotted like this:: > > t, y, x = lsim(sys, u, t) > plot(t, y[0], label='y_0') > plot(t, y[1], label='y_1') > > > Yours, > Eike. > <make-matlab-work.patch> |
From: <mur...@us...> - 2011-06-18 00:20:55
|
Revision: 160 http://python-control.svn.sourceforge.net/python-control/?rev=160&view=rev Author: murrayrm Date: 2011-06-18 00:20:49 +0000 (Sat, 18 Jun 2011) Log Message: ----------- updated working version number to 0.4d Modified Paths: -------------- trunk/ChangeLog trunk/setup.py Modified: trunk/ChangeLog =================================================================== --- trunk/ChangeLog 2011-06-18 00:18:23 UTC (rev 159) +++ trunk/ChangeLog 2011-06-18 00:20:49 UTC (rev 160) @@ -1,3 +1,12 @@ +---- control-0.4c released ----- + +2011-06-17 Richard Murray <mu...@dh...> + + * examples/tfvis.py: Added tfvis, Simple GUI application for + visualizing how the poles/zeros of the transfer function effects the + bode, nyquist and step response of a SISO system. Contributed by + Vanessa Romero Segovia, Ola Johnsson, Jerker Nordh. + 2011-06-16 Richard Murray <murray@malabar.local> * src/matlab.py: import mateqn functions Modified: trunk/setup.py =================================================================== --- trunk/setup.py 2011-06-18 00:18:23 UTC (rev 159) +++ trunk/setup.py 2011-06-18 00:20:49 UTC (rev 160) @@ -4,7 +4,7 @@ from setuptools import setup setup(name = 'control', - version = '0.4c', + version = '0.4d', description = 'Python Control Systems Library', author = 'Richard Murray', author_email = 'mu...@cd...', This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <mur...@us...> - 2011-06-18 00:18:29
|
Revision: 159 http://python-control.svn.sourceforge.net/python-control/?rev=159&view=rev Author: murrayrm Date: 2011-06-18 00:18:23 +0000 (Sat, 18 Jun 2011) Log Message: ----------- Version 0.4c tag Added Paths: ----------- tags/control-0.4c/ This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <mur...@us...> - 2011-06-18 00:02:33
|
Revision: 158 http://python-control.svn.sourceforge.net/python-control/?rev=158&view=rev Author: murrayrm Date: 2011-06-18 00:02:27 +0000 (Sat, 18 Jun 2011) Log Message: ----------- Added tfvis.py, a simple GUI application for visualizing how the poles/zeros of the transfer function effects the bode, nyquist and step response of a SISO system. Contributed by Vanessa Romero Segovia, Ola Johnsson, Jerker Nordh. Changed logspace import to pull this from the control.matlab instead of numpy (not found in numpy 2.0.0 on python 2.6.1). Added Paths: ----------- trunk/examples/tfvis.py Added: trunk/examples/tfvis.py =================================================================== --- trunk/examples/tfvis.py (rev 0) +++ trunk/examples/tfvis.py 2011-06-18 00:02:27 UTC (rev 158) @@ -0,0 +1,375 @@ +#!/usr/bin/python +""" Simple GUI application for visualizing how the poles/zeros of the transfer +function effects the bode, nyquist and step response of a SISO system """ + +"""Copyright (c) 2011, 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 project author 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. + +Author: Vanessa Romero Segovia +Author: Ola Johnsson +Author: Jerker Nordh +""" + +import control.matlab +import Tkinter +import sys +import Pmw +import matplotlib.pyplot as plt +from matplotlib.backends.backend_tkagg import FigureCanvasTkAgg +from numpy.lib.polynomial import polymul +from numpy.lib.type_check import real +from numpy.core.multiarray import array +from numpy.core.fromnumeric import size +# from numpy.lib.function_base import logspace +from control.matlab import logspace +from numpy import conj + +def make_poly(facts): + """ Create polynomial from factors """ + poly = [1] + for factor in facts: + poly = polymul(poly, [1, -factor]) + + return real(poly) + +def coeff_string_check(text): + """ Check so textfield entry is valid string of coeffs. """ + try: + [float(a) for a in text.split()] + except: + return Pmw.PARTIAL + + return Pmw.OK + +class TFInput: + """ Class for handling input of transfer function coeffs.""" + def __init__(self, parent): + self.master = parent + self.denominator = [] + self.numerator = [] + self.numerator_widget = Pmw.EntryField(self.master, + labelpos='w', + label_text='Numerator', + entry_width = 25, + validate=coeff_string_check, + value='1.0 -6.0 12.0') + self.denominator_widget = Pmw.EntryField(self.master, + labelpos='w', + label_text='Denominator', + entry_width = 25, + validate=coeff_string_check, + value='1.0 5.0 14.0 27.0') + self.balloon = Pmw.Balloon(self.master) + + try: + self.balloon.bind(self.numerator_widget, + "Numerator coefficients, e.g: 1.0 2.0") + except: + pass + + try: + self.balloon.bind(self.denominator_widget, + "Denominator coefficients, e.g: 1.0 3.0 2.0") + except: + pass + + widgets = (self.numerator_widget, self.denominator_widget) + for i in xrange(len(widgets)): + widgets[i].grid(row=i+1, column=0, padx=20, pady=3) + Pmw.alignlabels(widgets) + + self.numerator_widget.component('entry').focus_set() + + def get_tf(self): + """ Return transfer functions object created from coeffs""" + try: + numerator = ( + [float(a) for a in self.numerator_widget.get().split()]) + except: + numerator = None + + try: + denominator = ( + [float(a) for a in self.denominator_widget.get().split()]) + except: + denominator = None + + try: + if (numerator != None and denominator != None): + tfcn = control.matlab.tf(numerator, denominator) + else: + tfcn = None + except: + tfcn = None + + return tfcn + + + + def set_poles(self, poles): + """ Set the poles to the new positions""" + self.denominator = make_poly(poles) + self.denominator_widget.setentry( + ' '.join([format(i,'.3g') for i in self.denominator])) + + def set_zeros(self, zeros): + """ Set the zeros to the new positions""" + self.numerator = make_poly(zeros) + self.numerator_widget.setentry( + ' '.join([format(i,'.3g') for i in self.numerator])) + +class Analysis: + """ Main class for GUI visualising transfer functions """ + def __init__(self, parent): + """Creates all widgets""" + self.master = parent + self.move_zero = None + self.index1 = None + self.index2 = None + self.zeros = [] + self.poles = [] + + self.topframe = Tkinter.Frame(self.master) + self.topframe.pack(expand=True, fill='both') + + self.entries = Tkinter.Frame(self.topframe) + self.entries.pack(expand=True, fill='both') + + self.figure = Tkinter.Frame(self.topframe) + self.figure.pack(expand=True, fill='both') + + header = Tkinter.Label(self.entries, + text='Define the transfer function:') + header.grid(row=0, column=0, padx=20, pady=7) + + + self.tfi = TFInput(self.entries) + self.sys = self.tfi.get_tf() + + Tkinter.Button(self.entries, text='Apply', command=self.apply, + width=9).grid(row=0, column=1, rowspan=3, padx=10, pady=5) + + self.f_bode = plt.figure(figsize=(4, 4)) + self.f_nyquist = plt.figure(figsize=(4, 4)) + self.f_pzmap = plt.figure(figsize=(4, 4)) + self.f_step = plt.figure(figsize=(4, 4)) + + self.canvas_pzmap = FigureCanvasTkAgg(self.f_pzmap, + master=self.figure) + self.canvas_pzmap.show() + self.canvas_pzmap.get_tk_widget().grid(row=0, column=0, + padx=0, pady=0) + + self.canvas_bode = FigureCanvasTkAgg(self.f_bode, + master=self.figure) + self.canvas_bode.show() + self.canvas_bode.get_tk_widget().grid(row=0, column=1, + padx=0, pady=0) + + self.canvas_step = FigureCanvasTkAgg(self.f_step, + master=self.figure) + self.canvas_step.show() + self.canvas_step.get_tk_widget().grid(row=1, column=0, + padx=0, pady=0) + + self.canvas_nyquist = FigureCanvasTkAgg(self.f_nyquist, + master=self.figure) + self.canvas_nyquist.show() + self.canvas_nyquist.get_tk_widget().grid(row=1, column=1, + padx=0, pady=0) + + self.canvas_pzmap.mpl_connect('button_press_event', + self.button_press) + self.canvas_pzmap.mpl_connect('button_release_event', + self.button_release) + self.canvas_pzmap.mpl_connect('motion_notify_event', + self.mouse_move) + + self.apply() + + def button_press(self, event): + """ Handle button presses, detect if we are going to move + any poles/zeros""" + # find closest pole/zero + if (event.xdata != None and event.ydata != None): + + new = event.xdata + 1.0j*event.ydata + + tzeros = list(abs(self.zeros-new)) + tpoles = list(abs(self.poles-new)) + + if (size(tzeros) > 0): + minz = min(tzeros) + else: + minz = float('inf') + if (size(tpoles) > 0): + minp = min(tpoles) + else: + minp = float('inf') + + if (minz < 2 or minp < 2): + if (minz < minp): + # Moving zero(s) + self.index1 = tzeros.index(minz) + self.index2 = list(self.zeros).index( + conj(self.zeros[self.index1])) + self.move_zero = True + else: + # Moving pole(s) + self.index1 = tpoles.index(minp) + self.index2 = list(self.poles).index( + conj(self.poles[self.index1])) + self.move_zero = False + + def button_release(self, event): + """ Handle button release, update pole/zero positions, + if the were moved""" + if (self.move_zero == True): + self.tfi.set_zeros(self.zeros) + elif (self.move_zero == False): + self.tfi.set_poles(self.poles) + else: + return + + self.move_zero = None + self.index1 = None + self.index2 = None + + tfcn = self.tfi.get_tf() + if (tfcn): + self.zeros = tfcn.zero() + self.poles = tfcn.pole() + self.sys = tfcn + self.redraw() + + def mouse_move(self, event): + """ Handle mouse movement, redraw pzmap while drag/dropping """ + if (self.move_zero != None and + event.xdata != None and + event.ydata != None): + + if (self.index1 == self.index2): + # Real pole/zero + new = event.xdata + if (self.move_zero == True): + self.zeros[self.index1] = new + elif (self.move_zero == False): + self.poles[self.index1] = new + else: + # Complex poles/zeros + new = event.xdata + 1.0j*event.ydata + if (self.move_zero == True): + self.zeros[self.index1] = new + self.zeros[self.index2] = conj(new) + elif (self.move_zero == False): + self.poles[self.index1] = new + self.poles[self.index2] = conj(new) + tfcn = None + if (self.move_zero == True): + self.tfi.set_zeros(self.zeros) + tfcn = self.tfi.get_tf() + elif (self.move_zero == False): + self.tfi.set_poles(self.poles) + tfcn = self.tfi.get_tf() + if (tfcn != None): + self.draw_pz(tfcn) + self.canvas_pzmap.show() + + def apply(self): + """Evaluates the transfer function and produces different plots for + analysis""" + tfcn = self.tfi.get_tf() + + if (tfcn): + self.zeros = tfcn.zero() + self.poles = tfcn.pole() + self.sys = tfcn + self.redraw() + + def draw_pz(self, tfcn): + """Draw pzmap""" + self.f_pzmap.clf() + # Make adaptive window size, with min [-10, 10] in range, + # always atleast 25% extra space outside poles/zeros + tmp = list(self.zeros)+list(self.poles)+[8] + val = 1.25*max(abs(array(tmp))) + plt.figure(self.f_pzmap.number) + control.matlab.pzmap(tfcn) + plt.suptitle('Pole-Zero Diagram') + + plt.axis([-val, val, -val, val]) + + def redraw(self): + """ Redraw all diagrams """ + self.draw_pz(self.sys) + + self.f_bode.clf() + plt.figure(self.f_bode.number) + control.matlab.bode(self.sys, logspace(-2, 2)) + plt.suptitle('Bode Diagram') + + self.f_nyquist.clf() + plt.figure(self.f_nyquist.number) + control.matlab.nyquist(self.sys, logspace(-2, 2)) + plt.suptitle('Nyquist Diagram') + + self.f_step.clf() + plt.figure(self.f_step.number) + try: + # Step seems to get intro trouble + # with purely imaginary poles + tvec, yvec = control.matlab.step(self.sys) + plt.plot(tvec.T, yvec) + except: + print "Error plotting step response" + plt.suptitle('Step Response') + + self.canvas_pzmap.show() + self.canvas_bode.show() + self.canvas_step.show() + self.canvas_nyquist.show() + +def create_analysis(): + """ Create main object """ + def handler(): + """ Handles WM_DELETE_WINDOW messages """ + root.destroy() + sys.exit() + + # Launch a GUI for the Analysis module + root = Tkinter.Tk() + root.protocol("WM_DELETE_WINDOW", handler) + Pmw.initialise(root) + root.title('Analysis of Linear Systems') + Analysis(root) + root.mainloop() + +if __name__ == '__main__': + create_analysis() This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <mur...@us...> - 2011-06-17 23:51:53
|
Revision: 157 http://python-control.svn.sourceforge.net/python-control/?rev=157&view=rev Author: murrayrm Date: 2011-06-17 23:51:46 +0000 (Fri, 17 Jun 2011) Log Message: ----------- Added in matrix equation solver routes (lyap, dlyap, care, dare) from Johnsson, Nordh, Olofsson, Romero). Converted test code to standard format. Modified Paths: -------------- trunk/ChangeLog trunk/src/__init__.py trunk/src/matlab.py Added Paths: ----------- trunk/src/mateqn.py trunk/tests/mateqn_test.py Modified: trunk/ChangeLog =================================================================== --- trunk/ChangeLog 2011-04-17 18:45:29 UTC (rev 156) +++ trunk/ChangeLog 2011-06-17 23:51:46 UTC (rev 157) @@ -1,3 +1,20 @@ +2011-06-16 Richard Murray <murray@malabar.local> + + * src/matlab.py: import mateqn functions + + * src/__init__.py: import mateqn functions + + * tests/test_all.py: added unit tests for matrix solvers, converting + to standard format along the way. Seems to work even if slycot + routines are not in place, but I'm not sure if this is for the right + reasons... + + * src/mateqn.py: added matrix solvers from LTH (Ola Johnsson, Jerker + Nordh, Bjorn Olofsson, Vanessa Romero). Moved slycot function + checks to the portion of the code where they are used, so that + missing slycot doesn't mess up initialization if proper version of + slycot is not available. + 2011-04-02 Richard Murray <murray@malabar.local> * src/xferfcn.py (TransferFunction.__add__): fixed bug when adding a Modified: trunk/src/__init__.py =================================================================== --- trunk/src/__init__.py 2011-04-17 18:45:29 UTC (rev 156) +++ trunk/src/__init__.py 2011-06-17 23:51:46 UTC (rev 157) @@ -65,3 +65,4 @@ from delay import * from modelsimp import * from rlocus import * +from mateqn import * Added: trunk/src/mateqn.py =================================================================== --- trunk/src/mateqn.py (rev 0) +++ trunk/src/mateqn.py 2011-06-17 23:51:46 UTC (rev 157) @@ -0,0 +1,928 @@ +# mateqn.py - matrix equation solvers (Lyapunov, Riccati) +from __future__ import division + +""" Implementation of the functions lyap, dlyap, care and dare +for solution of Lyapunov and Riccati equations. """ + +"""Copyright (c) 2011, 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 project author 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. + +Author: Bjorn Olofsson +""" + +from numpy.linalg import inv +from scipy import shape,size,asarray,copy,zeros,eye,dot + +from control.exception import ControlSlycot,ControlArgument + +#### Lyapunov equation solvers lyap and dlyap + +def lyap(A,Q,C=None,E=None): + """ X = lyap(A,Q) solves the continuous-time Lyapunov equation + + A X + X A^T + Q = 0 + + where A and Q are square matrices of the same dimension. + Further, Q must be symmetric. + + X = lyap(A,Q,C) solves the Sylvester equation + + A X + X Q + C = 0 + + where A and Q are square matrices. + + X = lyap(A,Q,None,E) solves the generalized continuous-time + Lyapunov equation + + A X E^T + E X A^T + Q = 0 + + where Q is a symmetric matrix and A, Q and E are square matrices + of the same dimension. """ + + # Make sure we have access to the right slycot routines + try: + from slycot import sb03md + except ImportError: + raise ControlSlycot("can't find slycot module 'sb03md'") + + try: + from slycot import sb04md + except ImportError: + raise ControlSlycot("can't find slycot module 'sb04md'") + + # Reshape 1-d arrays + if len(shape(A)) == 1: + A = A.reshape(1,A.size) + + if len(shape(Q)) == 1: + Q = Q.reshape(1,Q.size) + + if C != None and len(shape(C)) == 1: + C = C.reshape(1,C.size) + + if E != None and len(shape(E)) == 1: + E = E.reshape(1,E.size) + + # Determine main dimensions + if size(A) == 1: + n = 1 + else: + n = size(A,0) + + if size(Q) == 1: + m = 1 + else: + m = size(Q,0) + + # Solve standard Lyapunov equation + if C==None and E==None: + # Check input data for consistency + if shape(A) != shape(Q): + raise ControlArgument("A and Q must be matrices of identical \ + sizes.") + + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if size(Q) > 1 and shape(Q)[0] != shape(Q)[1]: + raise ControlArgument("Q must be a quadratic matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + # Solve the Lyapunov equation by calling Slycot function sb03md + try: + X,scale,sep,ferr,w = sb03md(n,-Q,A,eye(n,n),'C',trana='T') + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == n+1: + e = ValueError("The matrix A and -A have common or very \ + close eigenvalues.") + e.info = ve.info + else: + e = ValueError("The QR algorithm failed to compute all \ + the eigenvalues (see LAPACK Library routine DGEES).") + e.info = ve.info + raise e + + # Solve the Sylvester equation + elif C != None and E==None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if size(Q) > 1 and shape(Q)[0] != shape(Q)[1]: + raise ControlArgument("Q must be a quadratic matrix.") + + if (size(C) > 1 and shape(C)[0] != n) or \ + (size(C) > 1 and shape(C)[1] != m) or \ + (size(C) == 1 and size(A) != 1) or (size(C) == 1 and size(Q) != 1): + raise ControlArgument("C matrix has incompatible dimensions.") + + # Solve the Sylvester equation by calling the Slycot function sb04md + try: + X = sb04md(n,m,A,Q,-C) + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info > m: + e = ValueError("A singular matrix was encountered whilst \ + solving for the %i-th column of matrix X." % ve.info-m) + e.info = ve.info + else: + e = ValueError("The QR algorithm failed to compute all the \ + eigenvalues (see LAPACK Library routine DGEES).") + e.info = ve.info + raise e + + # Solve the generalized Lyapunov equation + elif C == None and E != None: + # Check input data for consistency + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + (size(Q) == 1 and n > 1): + raise ControlArgument("Q must be a square matrix with the same \ + dimension as A.") + + if (size(E) > 1 and shape(E)[0] != shape(E)[1]) or \ + (size(E) > 1 and shape(E)[0] != n) or \ + (size(E) == 1 and n > 1): + raise ControlArgument("E must be a square matrix with the same \ + dimension as A.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + # Make sure we have access to the write slicot routine + try: + from slycot import sg03ad + except ImportError: + raise ControlSlycot("can't find slycot module 'sg03ad'") + + # Solve the generalized Lyapunov equation by calling Slycot + # function sg03ad + try: + A,E,Q,Z,X,scale,sep,ferr,alphar,alphai,beta = \ + sg03ad('C','B','N','T','L',n,A,E,eye(n,n),eye(n,n),-Q) + except ValueError, ve: + if ve.info < 0 or ve.info > 4: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The matrix contained in the upper \ + Hessenberg part of the array A is not in \ + upper quasitriangular form") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The pencil A - lambda * E cannot be \ + reduced to generalized Schur form: LAPACK \ + routine DGEGS has failed to converge") + e.info = ve.info + elif ve.info == 4: + e = ValueError("The pencil A - lambda * E has a \ + degenerate pair of eigenvalues. That is, \ + lambda_i = lambda_j for some i and j, where \ + lambda_i and lambda_j are eigenvalues of \ + A - lambda * E. Hence, the equation is \ + singular; perturbed values were \ + used to solve the equation (but the matrices \ + A and E are unchanged)") + e.info = ve.info + raise e + # Invalid set of input parameters + else: + raise ControlArgument("Invalid set of input parameters") + + return X + + +def dlyap(A,Q,C=None,E=None): + """ dlyap(A,Q) solves the discrete-time Lyapunov equation + + A X A^T - X + Q = 0 + + where A and Q are square matrices of the same dimension. Further + Q must be symmetric. + + dlyap(A,Q,C) solves the Sylvester equation + + A X Q^T - X + C = 0 + + where A and Q are square matrices. + + dlyap(A,Q,None,E) solves the generalized discrete-time Lyapunov + equation + + A X A^T - E X E^T + Q = 0 + + where Q is a symmetric matrix and A, Q and E are square matrices + of the same dimension. """ + + # Make sure we have access to the right slycot routines + try: + from slycot import sb03md + except ImportError: + raise ControlSlycot("can't find slycot module 'sb03md'") + + try: + from slycot import sb04qd + except ImportError: + raise ControlSlycot("can't find slycot module 'sb04qd'") + + try: + from slycot import sg03ad + except ImportError: + raise ControlSlycot("can't find slycot module 'sg03ad'") + + # Reshape 1-d arrays + if len(shape(A)) == 1: + A = A.reshape(1,A.size) + + if len(shape(Q)) == 1: + Q = Q.reshape(1,Q.size) + + if C != None and len(shape(C)) == 1: + C = C.reshape(1,C.size) + + if E != None and len(shape(E)) == 1: + E = E.reshape(1,E.size) + + # Determine main dimensions + if size(A) == 1: + n = 1 + else: + n = size(A,0) + + if size(Q) == 1: + m = 1 + else: + m = size(Q,0) + + # Solve standard Lyapunov equation + if C==None and E==None: + # Check input data for consistency + if shape(A) != shape(Q): + raise ControlArgument("A and Q must be matrices of identical \ + sizes.") + + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if size(Q) > 1 and shape(Q)[0] != shape(Q)[1]: + raise ControlArgument("Q must be a quadratic matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + # Solve the Lyapunov equation by calling the Slycot function sb03md + try: + X,scale,sep,ferr,w = sb03md(n,-Q,A,eye(n,n),'D',trana='T') + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + else: + e = ValueError("The QR algorithm failed to compute all the \ + eigenvalues (see LAPACK Library routine DGEES).") + e.info = ve.info + raise e + + # Solve the Sylvester equation + elif C != None and E==None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix") + + if size(Q) > 1 and shape(Q)[0] != shape(Q)[1]: + raise ControlArgument("Q must be a quadratic matrix") + + if (size(C) > 1 and shape(C)[0] != n) or \ + (size(C) > 1 and shape(C)[1] != m) or \ + (size(C) == 1 and size(A) != 1) or (size(C) == 1 and size(Q) != 1): + raise ControlArgument("C matrix has incompatible dimensions") + + # Solve the Sylvester equation by calling Slycot function sb04qd + try: + X = sb04qd(n,m,-A,asarray(Q).T,C) + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info > m: + e = ValueError("A singular matrix was encountered whilst \ + solving for the %i-th column of matrix X." % ve.info-m) + e.info = ve.info + else: + e = ValueError("The QR algorithm failed to compute all the \ + eigenvalues (see LAPACK Library routine DGEES)") + e.info = ve.info + raise e + + # Solve the generalized Lyapunov equation + elif C == None and E != None: + # Check input data for consistency + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + (size(Q) == 1 and n > 1): + raise ControlArgument("Q must be a square matrix with the same \ + dimension as A.") + + if (size(E) > 1 and shape(E)[0] != shape(E)[1]) or \ + (size(E) > 1 and shape(E)[0] != n) or \ + (size(E) == 1 and n > 1): + raise ControlArgument("E must be a square matrix with the same \ + dimension as A.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + # Solve the generalized Lyapunov equation by calling Slycot + # function sg03ad + try: + A,E,Q,Z,X,scale,sep,ferr,alphar,alphai,beta = \ + sg03ad('D','B','N','T','L',n,A,E,eye(n,n),eye(n,n),-Q) + except ValueError, ve: + if ve.info < 0 or ve.info > 4: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The matrix contained in the upper \ + Hessenberg part of the array A is not in \ + upper quasitriangular form") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The pencil A - lambda * E cannot be \ + reduced to generalized Schur form: LAPACK \ + routine DGEGS has failed to converge") + e.info = ve.info + elif ve.info == 3: + e = ValueError("The pencil A - lambda * E has a \ + pair of reciprocal eigenvalues. That is, \ + lambda_i = 1/lambda_j for some i and j, \ + where lambda_i and lambda_j are eigenvalues \ + of A - lambda * E. Hence, the equation is \ + singular; perturbed values were \ + used to solve the equation (but the \ + matrices A and E are unchanged)") + e.info = ve.info + raise e + # Invalid set of input parameters + else: + raise ControlArgument("Invalid set of input parameters") + + return X + + + +#### Riccati equation solvers care and dare + +def care(A,B,Q,R=None,S=None,E=None): + """ (X,L,G) = care(A,B,Q) solves the continuous-time algebraic Riccati + equation + + A^T X + X A - X B B^T X + Q = 0 + + where A and Q are square matrices of the same dimension. Further, Q + is a symmetric matrix. The function returns the solution X, the gain + matrix G = B^T X and the closed loop eigenvalues L, i.e., the eigenvalues + of A - B G. + + (X,L,G) = care(A,B,Q,R,S,E) solves the generalized continuous-time + algebraic Riccati equation + + A^T X E + E^T X A - (E^T X B + S) R^-1 (B^T X E + S^T) + Q = 0 + + where A, Q and E are square matrices of the same dimension. Further, Q and + R are symmetric matrices. The function returns the solution X, the gain + matrix G = R^-1 (B^T X E + S^T) and the closed loop eigenvalues L, i.e., + the eigenvalues of A - B G , E. """ + + # Make sure we can import required slycot routine + try: + from slycot import sb02md + except ImportError: + raise ControlSlycot("can't find slycot module 'sb02md'") + + try: + from slycot import sb02mt + except ImportError: + raise ControlSlycot("can't find slycot module 'sb02mt'") + + # Make sure we can find the required slycot routine + try: + from slycot import sg02ad + except ImportError: + raise ControlSlycot("can't find slycot module 'sg02ad'") + + # Reshape 1-d arrays + if len(shape(A)) == 1: + A = A.reshape(1,A.size) + + if len(shape(B)) == 1: + B = B.reshape(1,B.size) + + if len(shape(Q)) == 1: + Q = Q.reshape(1,Q.size) + + if R != None and len(shape(R)) == 1: + R = R.reshape(1,R.size) + + if S != None and len(shape(S)) == 1: + S = S.reshape(1,S.size) + + if E != None and len(shape(E)) == 1: + E = E.reshape(1,E.size) + + # Determine main dimensions + if size(A) == 1: + n = 1 + else: + n = size(A,0) + + if size(B) == 1: + m = 1 + else: + m = size(B,1) + if R==None: + R = eye(m,m) + + # Solve the standard algebraic Riccati equation + if S==None and E==None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + size(Q) == 1 and n > 1: + raise ControlArgument("Q must be a quadratic matrix of the same \ + dimension as A.") + + if (size(B) > 1 and shape(B)[0] != n) or \ + size(B) == 1 and n > 1: + raise ControlArgument("Incompatible dimensions of B matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + if not (asarray(R) == asarray(R).T).all(): + raise ControlArgument("R must be a symmetric matrix.") + + # Create back-up of arrays needed for later computations + R_ba = copy(R) + B_ba = copy(B) + + # Solve the standard algebraic Riccati equation by calling Slycot + # functions sb02mt and sb02md + try: + A_b,B_b,Q_b,R_b,L_b,ipiv,oufact,G = sb02mt(n,m,B,R) + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == m+1: + e = ValueError("The matrix R is numerically singular.") + e.info = ve.info + else: + e = ValueError("The %i-th element of d in the UdU (LdL) \ + factorization is zero." % ve.info) + e.info = ve.info + raise e + + try: + X,rcond,w,S_o,U,A_inv = sb02md(n,A,G,Q,'C') + except ValueError, ve: + if ve.info < 0 or ve.info > 5: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The matrix A is (numerically) singular in \ + discrete-time case.") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The Hamiltonian or symplectic matrix H cannot \ + be reduced to real Schur form.") + e.info = ve.info + elif ve.info == 3: + e = ValueError("The real Schur form of the Hamiltonian or \ + symplectic matrix H cannot be appropriately ordered.") + e.info = ve.info + elif ve.info == 4: + e = ValueError("The Hamiltonian or symplectic matrix H has \ + less than n stable eigenvalues.") + e.info = ve.info + elif ve.info == 5: + e = ValueError("The N-th order system of linear algebraic \ + equations is singular to working precision.") + e.info = ve.info + raise e + + # Calculate the gain matrix G + if size(R_b) == 1: + G = dot(dot(1/(R_ba),asarray(B_ba).T) , X) + else: + G = dot(dot(inv(R_ba),asarray(B_ba).T) , X) + + # Return the solution X, the closed-loop eigenvalues L and + # the gain matrix G + return (X , w[:n] , G ) + + # Solve the generalized algebraic Riccati equation + elif S != None and E != None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + size(Q) == 1 and n > 1: + raise ControlArgument("Q must be a quadratic matrix of the same \ + dimension as A.") + + if (size(B) > 1 and shape(B)[0] != n) or \ + size(B) == 1 and n > 1: + raise ControlArgument("Incompatible dimensions of B matrix.") + + if (size(E) > 1 and shape(E)[0] != shape(E)[1]) or \ + (size(E) > 1 and shape(E)[0] != n) or \ + size(E) == 1 and n > 1: + raise ControlArgument("E must be a quadratic matrix of the same \ + dimension as A.") + + if (size(R) > 1 and shape(R)[0] != shape(R)[1]) or \ + (size(R) > 1 and shape(R)[0] != m) or \ + size(R) == 1 and m > 1: + raise ControlArgument("R must be a quadratic matrix of the same \ + dimension as the number of columns in the B matrix.") + + if (size(S) > 1 and shape(S)[0] != n) or \ + (size(S) > 1 and shape(S)[1] != m) or \ + size(S) == 1 and n > 1 or \ + size(S) == 1 and m > 1: + raise ControlArgument("Incompatible dimensions of S matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + if not (asarray(R) == asarray(R).T).all(): + raise ControlArgument("R must be a symmetric matrix.") + + # Create back-up of arrays needed for later computations + R_b = copy(R) + B_b = copy(B) + E_b = copy(E) + S_b = copy(S) + + # Solve the generalized algebraic Riccati equation by calling the + # Slycot function sg02ad + try: + rcondu,X,alfar,alfai,beta,S_o,T,U,iwarn = \ + sg02ad('C','B','N','U','N','N','S','R',n,m,0,A,E,B,Q,R,S) + except ValueError, ve: + if ve.info < 0 or ve.info > 7: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The computed extended matrix pencil is \ + singular, possibly due to rounding errors.") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The QZ algorithm failed.") + e.info = ve.info + elif ve.info == 3: + e = ValueError("Reordering of the generalized eigenvalues \ + failed.") + e.info = ve.info + elif ve.info == 4: + e = ValueError("After reordering, roundoff changed values of \ + some complex eigenvalues so that leading \ + eigenvalues in the generalized Schur form no \ + longer satisfy the stability condition; this \ + could also be caused due to scaling.") + e.info = ve.info + elif ve.info == 5: + e = ValueError("The computed dimension of the solution does \ + not equal N.") + e.info = ve.info + elif ve.info == 6: + e = ValueError("The spectrum is too close to the boundary of \ + the stability domain.") + e.info = ve.info + elif ve.info == 7: + e = ValueError("A singular matrix was encountered during the \ + computation of the solution matrix X.") + e.info = ve.info + raise e + + # Calculate the closed-loop eigenvalues L + L = zeros((n,1)) + L.dtype = 'complex64' + for i in range(n): + L[i] = (alfar[i] + alfai[i]*1j)/beta[i] + + # Calculate the gain matrix G + if size(R_b) == 1: + G = dot(1/(R_b),dot(asarray(B_b).T,dot(X,E_b))+asarray(S_b).T) + else: + G = dot(inv(R_b),dot(asarray(B_b).T,dot(X,E_b))+asarray(S_b).T) + + # Return the solution X, the closed-loop eigenvalues L and + # the gain matrix G + return (X , L , G) + + # Invalid set of input parameters + else: + raise ControlArgument("Invalid set of input parameters.") + + +def dare(A,B,Q,R,S=None,E=None): + """ (X,L,G) = dare(A,B,Q,R) solves the discrete-time algebraic Riccati + equation + + A^T X A - X - A^T X B (B^T X B + R)^-1 B^T X A + Q = 0 + + where A and Q are square matrices of the same dimension. Further, Q + is a symmetric matrix. The function returns the solution X, the gain + matrix G = (B^T X B + R)^-1 B^T X A and the closed loop eigenvalues L, + i.e., the eigenvalues of A - B G. + + (X,L,G) = dare(A,B,Q,R,S,E) solves the generalized discrete-time algebraic + Riccati equation + + A^T X A - E^T X E - (A^T X B + S) (B^T X B + R)^-1 (B^T X A + S^T) + + + Q = 0 + + where A, Q and E are square matrices of the same dimension. Further, Q and + R are symmetric matrices. The function returns the solution X, the gain + matrix G = (B^T X B + R)^-1 (B^T X A + S^T) and the closed loop + eigenvalues L, i.e., the eigenvalues of A - B G , E. """ + + # Make sure we can import required slycot routine + try: + from slycot import sb02md + except ImportError: + raise ControlSlycot("can't find slycot module 'sb02md'") + + try: + from slycot import sb02mt + except ImportError: + raise ControlSlycot("can't find slycot module 'sb02mt'") + + # Make sure we can find the required slycot routine + try: + from slycot import sg02ad + except ImportError: + raise ControlSlycot("can't find slycot module 'sg02ad'") + + # Reshape 1-d arrays + if len(shape(A)) == 1: + A = A.reshape(1,A.size) + + if len(shape(B)) == 1: + B = B.reshape(1,B.size) + + if len(shape(Q)) == 1: + Q = Q.reshape(1,Q.size) + + if R != None and len(shape(R)) == 1: + R = R.reshape(1,R.size) + + if S != None and len(shape(S)) == 1: + S = S.reshape(1,S.size) + + if E != None and len(shape(E)) == 1: + E = E.reshape(1,E.size) + + # Determine main dimensions + if size(A) == 1: + n = 1 + else: + n = size(A,0) + + if size(B) == 1: + m = 1 + else: + m = size(B,1) + + # Solve the standard algebraic Riccati equation + if S==None and E==None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + size(Q) == 1 and n > 1: + raise ControlArgument("Q must be a quadratic matrix of the same \ + dimension as A.") + + if (size(B) > 1 and shape(B)[0] != n) or \ + size(B) == 1 and n > 1: + raise ControlArgument("Incompatible dimensions of B matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + if not (asarray(R) == asarray(R).T).all(): + raise ControlArgument("R must be a symmetric matrix.") + + # Create back-up of arrays needed for later computations + A_ba = copy(A) + R_ba = copy(R) + B_ba = copy(B) + + # Solve the standard algebraic Riccati equation by calling Slycot + # functions sb02mt and sb02md + try: + A_b,B_b,Q_b,R_b,L_b,ipiv,oufact,G = sb02mt(n,m,B,R) + except ValueError, ve: + if ve.info < 0: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == m+1: + e = ValueError("The matrix R is numerically singular.") + e.info = ve.info + else: + e = ValueError("The %i-th element of d in the UdU (LdL) \ + factorization is zero." % ve.info) + e.info = ve.info + raise e + + try: + X,rcond,w,S,U,A_inv = sb02md(n,A,G,Q,'D') + except ValueError, ve: + if ve.info < 0 or ve.info > 5: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The matrix A is (numerically) singular in \ + discrete-time case.") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The Hamiltonian or symplectic matrix H cannot \ + be reduced to real Schur form.") + e.info = ve.info + elif ve.info == 3: + e = ValueError("The real Schur form of the Hamiltonian or \ + symplectic matrix H cannot be appropriately ordered.") + e.info = ve.info + elif ve.info == 4: + e = ValueError("The Hamiltonian or symplectic matrix H has \ + less than n stable eigenvalues.") + e.info = ve.info + elif ve.info == 5: + e = ValueError("The N-th order system of linear algebraic \ + equations is singular to working precision.") + e.info = ve.info + raise e + + # Calculate the gain matrix G + if size(R_b) == 1: + G = dot( 1/(dot(asarray(B_ba).T,dot(X,B_ba))+R_ba) , \ + dot(asarray(B_ba).T,dot(X,A_ba)) ) + else: + G = dot( inv(dot(asarray(B_ba).T,dot(X,B_ba))+R_ba) , \ + dot(asarray(B_ba).T,dot(X,A_ba)) ) + + # Return the solution X, the closed-loop eigenvalues L and + # the gain matrix G + return (X , w[:n] , G) + + # Solve the generalized algebraic Riccati equation + elif S != None and E != None: + # Check input data for consistency + if size(A) > 1 and shape(A)[0] != shape(A)[1]: + raise ControlArgument("A must be a quadratic matrix.") + + if (size(Q) > 1 and shape(Q)[0] != shape(Q)[1]) or \ + (size(Q) > 1 and shape(Q)[0] != n) or \ + size(Q) == 1 and n > 1: + raise ControlArgument("Q must be a quadratic matrix of the same \ + dimension as A.") + + if (size(B) > 1 and shape(B)[0] != n) or \ + size(B) == 1 and n > 1: + raise ControlArgument("Incompatible dimensions of B matrix.") + + if (size(E) > 1 and shape(E)[0] != shape(E)[1]) or \ + (size(E) > 1 and shape(E)[0] != n) or \ + size(E) == 1 and n > 1: + raise ControlArgument("E must be a quadratic matrix of the same \ + dimension as A.") + + if (size(R) > 1 and shape(R)[0] != shape(R)[1]) or \ + (size(R) > 1 and shape(R)[0] != m) or \ + size(R) == 1 and m > 1: + raise ControlArgument("R must be a quadratic matrix of the same \ + dimension as the number of columns in the B matrix.") + + if (size(S) > 1 and shape(S)[0] != n) or \ + (size(S) > 1 and shape(S)[1] != m) or \ + size(S) == 1 and n > 1 or \ + size(S) == 1 and m > 1: + raise ControlArgument("Incompatible dimensions of S matrix.") + + if not (asarray(Q) == asarray(Q).T).all(): + raise ControlArgument("Q must be a symmetric matrix.") + + if not (asarray(R) == asarray(R).T).all(): + raise ControlArgument("R must be a symmetric matrix.") + + # Create back-up of arrays needed for later computations + A_b = copy(A) + R_b = copy(R) + B_b = copy(B) + E_b = copy(E) + S_b = copy(S) + + # Solve the generalized algebraic Riccati equation by calling the + # Slycot function sg02ad + try: + rcondu,X,alfar,alfai,beta,S_o,T,U,iwarn = \ + sg02ad('D','B','N','U','N','N','S','R',n,m,0,A,E,B,Q,R,S) + except ValueError, ve: + if ve.info < 0 or ve.info > 7: + e = ValueError(ve.message) + e.info = ve.info + elif ve.info == 1: + e = ValueError("The computed extended matrix pencil is \ + singular, possibly due to rounding errors.") + e.info = ve.info + elif ve.info == 2: + e = ValueError("The QZ algorithm failed.") + e.info = ve.info + elif ve.info == 3: + e = ValueError("Reordering of the generalized eigenvalues \ + failed.") + e.info = ve.info + elif ve.info == 4: + e = ValueError("After reordering, roundoff changed values of \ + some complex eigenvalues so that leading \ + eigenvalues in the generalized Schur form no \ + longer satisfy the stability condition; this \ + could also be caused due to scaling.") + e.info = ve.info + elif ve.info == 5: + e = ValueError("The computed dimension of the solution does \ + not equal N.") + e.info = ve.info + elif ve.info == 6: + e = ValueError("The spectrum is too close to the boundary of \ + the stability domain.") + e.info = ve.info + elif ve.info == 7: + e = ValueError("A singular matrix was encountered during the \ + computation of the solution matrix X.") + e.info = ve.info + raise e + + L = zeros((n,1)) + L.dtype = 'complex64' + for i in range(n): + L[i] = (alfar[i] + alfai[i]*1j)/beta[i] + + # Calculate the gain matrix G + if size(R_b) == 1: + G = dot( 1/(dot(asarray(B_b).T,dot(X,B_b))+R_b) , \ + dot(asarray(B_b).T,dot(X,A_b)) + asarray(S_b).T) + else: + G = dot( inv(dot(asarray(B_b).T,dot(X,B_b))+R_b) , \ + dot(asarray(B_b).T,dot(X,A_b)) + asarray(S_b).T) + + # Return the solution X, the closed-loop eigenvalues L and + # the gain matrix G + return (X , L , G) + + # Invalid set of input parameters + else: + raise ControlArgument("Invalid set of input parameters.") Modified: trunk/src/matlab.py =================================================================== --- trunk/src/matlab.py 2011-04-17 18:45:29 UTC (rev 156) +++ trunk/src/matlab.py 2011-06-17 23:51:46 UTC (rev 157) @@ -81,6 +81,7 @@ from statefbk import ctrb, obsv, gram, place, lqr from delay import pade from modelsimp import hsvd, balred, modred +from mateqn import lyap, dlyap, dare, care __doc__ += """ The control.matlab module defines functions that are roughly the @@ -255,9 +256,9 @@ lti/conj - complex conjugation of model coefficients Matrix equation solvers and linear algebra - lyap, dlyap - solve Lyapunov equations +\* lyap, dlyap - solve Lyapunov equations lyapchol, dlyapchol - square-root Lyapunov solvers - care, dare - solve algebraic Riccati equations +\* care, dare - solve algebraic Riccati equations gcare, gdare - generalized Riccati solvers bdschur - block diagonalization of a square matrix Added: trunk/tests/mateqn_test.py =================================================================== --- trunk/tests/mateqn_test.py (rev 0) +++ trunk/tests/mateqn_test.py 2011-06-17 23:51:46 UTC (rev 157) @@ -0,0 +1,236 @@ +#!/usr/bin/env python +# +# mateqn_test.py - test wuit for matrix equation solvers +# +#! Currently uses numpy.testing framework; will dump you out of unittest +#! if an error occurs. Should figure out the right way to fix this. + +""" Test cases for lyap, dlyap, care and dare functions in the file +pyctrl_lin_alg.py. """ + +"""Copyright (c) 2011, 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 project author 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. + +Author: Bjorn Olofsson +""" + +import unittest +from numpy import array +from numpy.testing import assert_array_almost_equal +from numpy.linalg import inv +from scipy import zeros,dot +from control.mateqn import lyap,dlyap,care,dare + +# Test cases (lyap and dlyap) + +class TestMatrixEquations(unittest.TestCase): + """These are tests for the matrix equation solvers in mateqn.py""" + + def setUp(self): + # Make sure that the slycot functions that we require exist + from slycot import sb02md, sb02mt, sb03md, sb04md, sg02ad, \ + sg03ad, sb04qd + + def test_lyap(self): + A = array([[-1, 1],[-1, 0]]) + Q = array([[1,0],[0,1]]) + X = lyap(A,Q) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,X)+dot(X,A.T)+Q,zeros((2,2))) + + A = array([[1, 2],[-3, -4]]) + Q = array([[3, 1],[1, 1]]) + X = lyap(A,Q) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,X)+dot(X,A.T)+Q,zeros((2,2))) + + def test_lyap_sylvester(self): + A = 5 + B = array([[4, 3], [4, 3]]) + C = array([2, 1]) + X = lyap(A,B,C) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,X)+dot(X,B)+C,zeros((1,2))) + + A = array([[2,1],[1,2]]) + B = array([[1,2],[0.5,0.1]]) + C = array([[1,0],[0,1]]) + X = lyap(A,B,C) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,X)+dot(X,B)+C,zeros((2,2))) + + def test_lyap_g(self): + A = array([[-1, 2],[-3, -4]]) + Q = array([[3, 1],[1, 1]]) + E = array([[1,2],[2,1]]) + X = lyap(A,Q,None,E) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,E.T)) + dot(E,dot(X,A.T)) + Q, \ + zeros((2,2))) + + def test_dlyap(self): + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[1,0],[0,1]]) + X = dlyap(A,Q) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,A.T))-X+Q,zeros((2,2))) + + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[3, 1],[1, 1]]) + X = dlyap(A,Q) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,A.T))-X+Q,zeros((2,2))) + + def test_dlyap_g(self): + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[3, 1],[1, 1]]) + E = array([[1, 1],[2, 1]]) + X = dlyap(A,Q,None,E) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,A.T))-dot(E,dot(X,E.T))+Q, \ + zeros((2,2))) + + def test_dlyap_sylvester(self): + A = 5 + B = array([[4, 3], [4, 3]]) + C = array([2, 1]) + X = dlyap(A,B,C) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,B.T))-X+C,zeros((1,2))) + + A = array([[2,1],[1,2]]) + B = array([[1,2],[0.5,0.1]]) + C = array([[1,0],[0,1]]) + X = dlyap(A,B,C) + # print "The solution obtained is ", X + assert_array_almost_equal(dot(A,dot(X,B.T))-X+C,zeros((2,2))) + + def test_care(self): + A = array([[-2, -1],[-1, -1]]) + Q = array([[0, 0],[0, 1]]) + B = array([[1, 0],[0, 4]]) + + X,L,G = care(A,B,Q) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,X) + dot(X,A) - \ + dot(X,dot(B,dot(B.T,X))) + Q , zeros((2,2))) + assert_array_almost_equal(dot(B.T,X) , G) + + def test_care_g(self): + A = array([[-2, -1],[-1, -1]]) + Q = array([[0, 0],[0, 1]]) + B = array([[1, 0],[0, 4]]) + R = array([[2, 0],[0, 1]]) + S = array([[0, 0],[0, 0]]) + E = array([[2, 1],[1, 2]]) + + X,L,G = care(A,B,Q,R,S,E) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,E)) + dot(E.T,dot(X,A)) - \ + dot(dot(dot(E.T,dot(X,B))+S,inv(R) ) , + dot(B.T,dot(X,E))+S.T ) + Q , \ + zeros((2,2))) + assert_array_almost_equal(dot( inv(R) , dot(B.T,dot(X,E)) + S.T) , G) + + A = array([[-2, -1],[-1, -1]]) + Q = array([[0, 0],[0, 1]]) + B = array([[1],[0]]) + R = 1 + S = array([[1],[0]]) + E = array([[2, 1],[1, 2]]) + + X,L,G = care(A,B,Q,R,S,E) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,E)) + dot(E.T,dot(X,A)) - \ + dot( dot( dot(E.T,dot(X,B))+S,1/R ) , dot(B.T,dot(X,E))+S.T ) \ + + Q , zeros((2,2))) + assert_array_almost_equal(dot( 1/R , dot(B.T,dot(X,E)) + S.T) , G) + + def test_dare(self): + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[2, 1],[1, 0]]) + B = array([[2, 1],[0, 1]]) + R = array([[1, 0],[0, 1]]) + + X,L,G = dare(A,B,Q,R) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,A))-X-dot(dot(dot(A.T,dot(X,B)) , \ + inv(dot(B.T,dot(X,B))+R)) , dot(B.T,dot(X,A))) + Q , zeros((2,2)) ) + assert_array_almost_equal( dot( inv( dot(B.T,dot(X,B)) + R) , \ + dot(B.T,dot(X,A)) ) , G) + + A = array([[1, 0],[-1, 1]]) + Q = array([[0, 1],[1, 1]]) + B = array([[1],[0]]) + R = 2 + + X,L,G = dare(A,B,Q,R) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,A))-X-dot(dot(dot(A.T,dot(X,B)) , \ + inv(dot(B.T,dot(X,B))+R)) , dot(B.T,dot(X,A))) + Q , zeros((2,2)) ) + assert_array_almost_equal( dot( 1 / ( dot(B.T,dot(X,B)) + R) , \ + dot(B.T,dot(X,A)) ) , G) + + def test_dare_g(self): + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[2, 1],[1, 3]]) + B = array([[1, 5],[2, 4]]) + R = array([[1, 0],[0, 1]]) + S = array([[1, 0],[2, 0]]) + E = array([[2, 1],[1, 2]]) + + X,L,G = dare(A,B,Q,R,S,E) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,A))-dot(E.T,dot(X,E)) - \ + dot( dot(A.T,dot(X,B))+S , dot( inv(dot(B.T,dot(X,B)) + R) , + dot(B.T,dot(X,A))+S.T)) + Q , zeros((2,2)) ) + assert_array_almost_equal( dot( inv( dot(B.T,dot(X,B)) + R) , \ + dot(B.T,dot(X,A)) + S.T ) , G) + + A = array([[-0.6, 0],[-0.1, -0.4]]) + Q = array([[2, 1],[1, 3]]) + B = array([[1],[2]]) + R = 1 + S = array([[1],[2]]) + E = array([[2, 1],[1, 2]]) + + X,L,G = dare(A,B,Q,R,S,E) + # print "The solution obtained is", X + assert_array_almost_equal(dot(A.T,dot(X,A))-dot(E.T,dot(X,E)) - \ + dot( dot(A.T,dot(X,B))+S , dot( inv(dot(B.T,dot(X,B)) + R) , + dot(B.T,dot(X,A))+S.T)) + Q , zeros((2,2)) ) + assert_array_almost_equal( dot( 1 / ( dot(B.T,dot(X,B)) + R) , \ + dot(B.T,dot(X,A)) + S.T ) , G) + +def suite(): + return unittest.TestLoader().loadTestsFromTestCase(TestMatrixEquations) + +if __name__ == "__main__": + unittest.main() This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: Richard M. <mu...@cd...> - 2011-06-13 22:51:42
|
Thanks Jerker, Björn, Ola and Vanessa! Cc'ing the discussion list so they know about these changes. I'll work to integrate as soon as possible (hopefully the next few weeks). -richard On 13 Jun 2011, at 6:59 , Jerker Nordh wrote: > Hi > > Attached in this email you will find the code Björn wrote to add lyap, dlyap, care and dare. Probably you want to merge this into one of the other files, but we leave the file/directory structure up to you. > > Also there are some test cases (using nosetests, http://somethingaboutorange.com/mrl/projects/nose/1.0.0/) for this code. > > For using the new functions you will need my modifications to slycot, they haven't yet been merged into the official slycot code, so until Avventi does that you can use my version of the code which you can find at: > https://github.com/jerkern/Slycot > > Also attached is "tfvis.py", which is a small application with takes the coefficients of the denominator/numerator of a SISO transfer function and plots pzmap,bode,nyquist and step response. You can drag-n-drop the poles/zeros in the pzmap, and when you release them the other figures will be updated accordingly. > > I was thinking this might be nice to distribute in an example/ subdirectory or such, and perhaps someone will want to extend it in the future. It is a quite nice visualization tool for eg. a basic course in control. > > It uses the Pmw library for the GUI elements, which I think is fairly standard but perhaps not present on all computers. You can find it at: > http://pmw.sourceforge.net/ > > BR > Jerker, Björn, Ola, Vanessa > > > > On 2011-06-05 16:26, Richard Murray wrote: >> Hi Jerker. Sorry for the delay in replying. It would be great to get the functions below into python-control and also a simple GUI, if you are willing to contribute it. Let me know when one are both are ready and I can have a look. >> >> -richard >> >> On 1 Jun 2011, at 5:00 , Jerker Nordh wrote: >> >>> Hi >>> >>> We didn't get started on this as soon as we had expected, but now we've had some progress. >>> >>> I've uploaded some code to github which I hoped will be merged to the official Slycot release shortly. >>> >>> Using these additional wrappers in slycot we intend (mostly done) to implement: >>> - lyap, dlyap >>> - care, dare >>> >>> If it's interesting we will perhaps also be able to contribute a simple gui application that helps visualize the effect of poles/zeros on a systems step respone/nyquist plot. This could perhaps be nice to distribute as an example along side python control? >>> >>> //Jerker >>> >>> On 2011-04-13 17:55, Richard Murray wrote: >>>> That's great that you will be able to participate in this. We are building on SLICOT (and the python version slycot) for most of the numerical functionality, so implementing the following functions would be useful and not too much work: >>>> >>>> -- >>>> Matrix equation solvers and linear algebra >>>> lyap, dlyap - solve Lyapunov equations >>>> lyapchol, dlyapchol - square-root Lyapunov solvers >>>> care, dare - solve algebraic Riccati equations >>>> gcare, gdare - generalized Riccati solvers >>>> bdschur - block diagonalization of a square matrix >>>> -- >>>> >>>> -richard >>>> >>>> On 13 Apr 2011, at 5:18 , Jerker Nordh wrote: >>>> >>>>> Hi again >>>>> >>>>> We've cleared the idea with course instructor, so it won't be any problem for us to do some work on python-control. >>>>> >>>>> Atleast Björn and me will be working on this, perhaps someone else as well. I talked to Per Hagander here at the department, he suggested implementing something around Luaponov/Riccati equations. >>>>> >>>>> After doing some googling I found the pyDARE package (http://code.google.com/p/pydare/), so perhaps it would be redundant to implement something similar in python-control when it already exists elsewhere? >>>>> >>>>> So I guess we will get back to you when we have settled more exactly what we'll be doing. >>>>> >>>>> BR >>>>> Jerker >>>>> >>>>> On 2011-04-02 21:33, Richard Murray wrote: >>>>>> I've update the list of functions that are implemented on the python-control wiki pages: >>>>>> >>>>>> https://sourceforge.net/apps/mediawiki/python-control/index.php?title=Developer_assignments >>>>>> >>>>>> -richard >>>>>> >>>>>> On 30 Mar 2011, at 7:46 , Richard Murray wrote: >>>>>> >>>>>>> It would be great to get your help. There *lots* of work to be done. I'll try to spend some time this week updating the wiki pages to reflect what is done and what needs to be done. What would probably make sense is for you to pick some collection of unimplemented functions that go together and then start working on them. Being novices with python definitely won't be a problem. >>>>>>> >>>>>>> Let me know if something like that makes sense and if you can get permission from your instructor. >>>>>>> >>>>>>> -richard >>>>>>> >>>>>>> On 30 Mar 2011, at 1:44 , Jerker Nordh wrote: >>>>>>> >>>>>>>> Hi >>>>>>>> >>>>>>>> We are a small group of graduate students within automatic control in Lund who are currently following a basic course in Python which contains a small project part. We are thinking that instead of doing the standard project within the course we could probably convince the course lectutrer to allow us to do something more "productive". >>>>>>>> >>>>>>>> Our idea is that we could help with some of the implementation work in control-python. Is the project in a state were you could accept some outside help, and are there any parts suitable for "novice" python programmers corresponding roughly to one week full time work for 3-4 people? >>>>>>>> >>>>>>>> Best regards, >>>>>>>> Jerker Nordh >>>>>>> >>>>>> >>>> >> > > <pyctrl_lin_alg.py><test_pyctrl_lin_alg.py><tfvis.py> |
From: Richard M. <mu...@cd...> - 2011-06-12 17:28:38
|
Thanks, Eike! I am just finishing up a busy term and hope to put some time into python-control over the next several weeks. Getting MIMO functionality in is a great boost. -richard On 12 Jun 2011, at 10:05 , Eike Welk wrote: > I've created a new patch, that adds MIMO capabilities to the ``matlab`` > module. > > https://sourceforge.net/tracker/?func=detail&aid=3315485&group_id=282523&atid=1198311 > > I'm doing the development in a separate Mercurial repository: > https://bitbucket.org/eike_welk/python-control/ > > ------------------------------------------------------------------------------ > EditLive Enterprise is the world's most technically advanced content > authoring tool. Experience the power of Track Changes, Inline Image > Editing and ensure content is compliant with Accessibility Checking. > http://p.sf.net/sfu/ephox-dev2dev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss |
From: Eike W. <eik...@gm...> - 2011-06-12 17:05:21
|
I've created a new patch, that adds MIMO capabilities to the ``matlab`` module. https://sourceforge.net/tracker/?func=detail&aid=3315485&group_id=282523&atid=1198311 I'm doing the development in a separate Mercurial repository: https://bitbucket.org/eike_welk/python-control/ |
From: Richard M. <mu...@cd...> - 2011-05-12 23:23:15
|
Hi Eike. Thanks for your interest in python-control! I'll take a look at your patches as soon as possible (developers: if anyone else wants to volunteer, just let me know!). We have had some discussion about the output formats and have a plan for how to implement that, so might have to sort through some of the changes below if they are not consistent with the current plan (see the discussion list archives for more info). Will respond to the parameter convention suggestion a bit later (busy few weeks ahead). I've added you to the discuss list so that we can have a conversation about it. -richard On 12 May 2011, at 16:11 , Eike Welk wrote: > Hello! > > I have written a patch for the Python Control Systems Library with the > following contents: > > * An implementation of the four simulation functions ``lsim``, ``step``, > ``initial``, and ``impulse`` of the module ``matlab``. > > * It also adds a function ``dcgain`` to the ``matlab`` module, which computes > the gain of a linear system for steady state and constant input. > > * The patch contains a bug fix for class ``StateSpace``, which enables it to > work properly together with Scipy's ``signal`` module. > > * The simulation functions' return values are changed (back?) to arrays, > because matrices confuse Matplotlib. > > http://sourceforge.net/tracker/?func=detail&aid=3301246&group_id=282523&atid=1198311 > > > Would you include my patch into the library? > > What do you think about the parameter convention below? IMHO a detailed > section that explains the used convention should be included in the module's > documentation. The documentation of the individual functions should link to > it. > > What is the proper communication channel for the library's developers? > > If you include my patch, my next step would be to extend ``lsim`` to MIMO > systems (by copying the code from ``scipy.signal.lsim2``); and to convert the > module's documentation to proper reStructuredText. > > > Implementation Notes > ------------------- > > The implementation is centered around ``lsim``, which checks the parameters > thoroughly, and generates useful error messages. It then calls > ``scipy.signal.lsim2`` to solve the differential equations. The other > simulation functions (``step``, ``initial``, ``impulse``) are small and call > ``lsim``. > > > Parameter Convention > -------------------- > > The new convention for parameters and return values harmonizes with the way > how the system equations are written. It can be generalized to MIMO systems, > and it also works well with Matplotlib: > > All parameters can be arrays, matrices, or nested lists. > > The time vector is either 1D, or 2D with shape (1, n):: > > T = [[t1, t2, t3, ..., tn ]] > > Input, state, and output all follow the same convention. Columns are different > points in time, rows are different components. When there is only one row, a > 1D object is accepted or returned, which adds convenience for SISO systems:: > > U = [[u1(t1), u1(t2), u1(t3), ..., u1(tn)] > [u2(t1), u2(t2), u2(t3), ..., u2(tn)] > ... > ... > [ui(t1), ui(t2), ui(t3), ..., ui(tn)]] > > Same for X, Y > > The initial conditions are either 1D, or 2D with shape (j, 1):: > > X0 = [[u1] > [u2] > ... > ... > [uj]] > > So, U[:,2] is the system's input at the third point in time; and U[1] or > U[1,:] is the sequence of values for the system's second input. > > As all simulation functions return array plotting is convenient:: > > t, y = step(sys) > plot(t, y) > > The output of a MIMO system would be plotted like this:: > > t, y, x = lsim(sys, u, t) > plot(t, y[0], label='y_0') > plot(t, y[1], label='y_1') > > > Yours, > Eike. > <make-matlab-work.patch> |
From: Eike W. <eik...@gm...> - 2011-05-12 23:11:48
|
Hello! I have written a patch for the Python Control Systems Library with the following contents: * An implementation of the four simulation functions ``lsim``, ``step``, ``initial``, and ``impulse`` of the module ``matlab``. * It also adds a function ``dcgain`` to the ``matlab`` module, which computes the gain of a linear system for steady state and constant input. * The patch contains a bug fix for class ``StateSpace``, which enables it to work properly together with Scipy's ``signal`` module. * The simulation functions' return values are changed (back?) to arrays, because matrices confuse Matplotlib. http://sourceforge.net/tracker/?func=detail&aid=3301246&group_id=282523&atid=1198311 Would you include my patch into the library? What do you think about the parameter convention below? IMHO a detailed section that explains the used convention should be included in the module's documentation. The documentation of the individual functions should link to it. What is the proper communication channel for the library's developers? If you include my patch, my next step would be to extend ``lsim`` to MIMO systems (by copying the code from ``scipy.signal.lsim2``); and to convert the module's documentation to proper reStructuredText. Implementation Notes ------------------- The implementation is centered around ``lsim``, which checks the parameters thoroughly, and generates useful error messages. It then calls ``scipy.signal.lsim2`` to solve the differential equations. The other simulation functions (``step``, ``initial``, ``impulse``) are small and call ``lsim``. Parameter Convention -------------------- The new convention for parameters and return values harmonizes with the way how the system equations are written. It can be generalized to MIMO systems, and it also works well with Matplotlib: All parameters can be arrays, matrices, or nested lists. The time vector is either 1D, or 2D with shape (1, n):: T = [[t1, t2, t3, ..., tn ]] Input, state, and output all follow the same convention. Columns are different points in time, rows are different components. When there is only one row, a 1D object is accepted or returned, which adds convenience for SISO systems:: U = [[u1(t1), u1(t2), u1(t3), ..., u1(tn)] [u2(t1), u2(t2), u2(t3), ..., u2(tn)] ... ... [ui(t1), ui(t2), ui(t3), ..., ui(tn)]] Same for X, Y The initial conditions are either 1D, or 2D with shape (j, 1):: X0 = [[u1] [u2] ... ... [uj]] So, U[:,2] is the system's input at the third point in time; and U[1] or U[1,:] is the sequence of values for the system's second input. As all simulation functions return array plotting is convenient:: t, y = step(sys) plot(t, y) The output of a MIMO system would be plotted like this:: t, y, x = lsim(sys, u, t) plot(t, y[0], label='y_0') plot(t, y[1], label='y_1') Yours, Eike. |
From: Richard M. <mu...@cd...> - 2011-04-17 19:43:05
|
Had the settings on the list wrong, so this got accidentally discarded (fixed now). -richard Begin forwarded message: > From: pyt...@li... > Date: 17 April 2011 11:45:36 PDT > To: pyt...@li... > Subject: Auto-discard notification > > The attached message has been automatically discarded. > From: gor...@us... > Date: 17 April 2011 11:45:29 PDT > To: pyt...@li... > Subject: SF.net SVN: python-control:[156] trunk/src/xferfcn.py > > > Revision: 156 > http://python-control.svn.sourceforge.net/python-control/?rev=156&view=rev > Author: goretkin > Date: 2011-04-17 18:45:29 +0000 (Sun, 17 Apr 2011) > > Log Message: > ----------- > The following no longer causes a Numpy ValueError: > (cases where the order of the numerator is higher than the order of the denominator) > > s = control.tf.TransferFunction([1, 0], [1]) > control.bode(s) > > Modified Paths: > -------------- > trunk/src/xferfcn.py > > Modified: trunk/src/xferfcn.py > =================================================================== > --- trunk/src/xferfcn.py 2011-04-16 23:45:46 UTC (rev 155) > +++ trunk/src/xferfcn.py 2011-04-17 18:45:29 UTC (rev 156) > @@ -643,8 +643,10 @@ > # are the same size as the denominator. > for i in range(self.outputs): > for j in range(self.inputs): > - num[i][j] = insert(num[i][j], zeros(len(den) - len(num[i][j])), > - zeros(len(den) - len(num[i][j]))) > + pad = len(den) - len(num[i][j]) > + if(pad>0): > + num[i][j] = insert(num[i][j], zeros(pad), > + zeros(pad)) > # Finally, convert the numerator to a 3-D array. > num = array(num) > # Remove trivial imaginary parts. Check for nontrivial imaginary parts. > > > This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. > > > |
From: Richard M. <mu...@cd...> - 2011-04-17 18:10:33
|
I've been using symlinks at that works pretty well (and is easy). I'll play with the setup changes and undo if there are problems. Experience from others (distutils vs setuptools) are welcome. -richard On 17 Apr 2011, at 11:07 , Gustavo Goretkin wrote: > Hey All, > > I didn't intent to commit the change to setup.py. Sorry about that. > > I was trying to install "control" like so: > $ python setup.py develop > > The "develop" option makes apparently makes an egg link from the python dist-packages to src folder. This way changes to the src folder take effect in my python environment. You can accomplish the same thing manually with symlinks, I think. > > Anyway I haven't been able to get this to work. I haven't developed a python module before so I thought I'd ask your methods. > > Thanks, > Gustavo > > On Sat, Apr 16, 2011 at 7:45 PM, <gor...@us...> wrote: > Revision: 155 > http://python-control.svn.sourceforge.net/python-control/?rev=155&view=rev > Author: goretkin > Date: 2011-04-16 23:45:46 +0000 (Sat, 16 Apr 2011) > > Log Message: > ----------- > Support for the **,/ operator. > >> s = control.tf.TransferFunction([1, 0],[1]) > sys = s/(s**2+s+1) #works as expected > > Modified Paths: > -------------- > trunk/setup.py > trunk/src/xferfcn.py > > Modified: trunk/setup.py > =================================================================== > --- trunk/setup.py 2011-04-07 20:12:28 UTC (rev 154) > +++ trunk/setup.py 2011-04-16 23:45:46 UTC (rev 155) > @@ -1,6 +1,7 @@ > #!/usr/bin/env python > > -from distutils.core import setup > +#from distutils.core import setup > +from setuptools import setup > > setup(name = 'control', > version = '0.4c', > > Modified: trunk/src/xferfcn.py > =================================================================== > --- trunk/src/xferfcn.py 2011-04-07 20:12:28 UTC (rev 154) > +++ trunk/src/xferfcn.py 2011-04-16 23:45:46 UTC (rev 155) > @@ -372,9 +372,13 @@ > def __div__(self, other): > """Divide two LTI objects.""" > > - # Convert the second argument to a transfer function. > - other = _convertToTransferFunction(other) > + if isinstance(other, (int, float, long, complex)): > + other = _convertToTransferFunction(other, inputs=self.inputs, > + outputs=self.inputs) > + else: > + other = _convertToTransferFunction(other) > > + > if (self.inputs > 1 or self.outputs > 1 or > other.inputs > 1 or other.outputs > 1): > raise NotImplementedError("TransferFunction.__div__ is currently \ > @@ -388,6 +392,11 @@ > # TODO: Division of MIMO transfer function objects is not written yet. > def __rdiv__(self, other): > """Right divide two LTI objects.""" > + if isinstance(other, (int, float, long, complex)): > + other = _convertToTransferFunction(other, inputs=self.inputs, > + outputs=self.inputs) > + else: > + other = _convertToTransferFunction(other) > > if (self.inputs > 1 or self.outputs > 1 or > other.inputs > 1 or other.outputs > 1): > @@ -395,6 +404,16 @@ > implemented only for SISO systems.") > > return other / self > + def __pow__(self,other): > + if not type(other) == int: > + raise ValueError("Exponent must be an integer") > + if other == 0: > + return TransferFunction([1],[1]) #unity > + if other > 0: > + return self * (self**(other-1)) > + if other < 0: > + return (TransferFunction([1],[1]) / self) * (self**(other+1)) > + > > def evalfr(self, omega): > """Evaluate a transfer function at a single angular frequency. > > > This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. > > ------------------------------------------------------------------------------ > Benefiting from Server Virtualization: Beyond Initial Workload > Consolidation -- Increasing the use of server virtualization is a top > priority.Virtualization can reduce costs, simplify management, and improve > application availability and disaster protection. Learn more about boosting > the value of server virtualization. http://p.sf.net/sfu/vmware-sfdev2dev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > ------------------------------------------------------------------------------ > Benefiting from Server Virtualization: Beyond Initial Workload > Consolidation -- Increasing the use of server virtualization is a top > priority.Virtualization can reduce costs, simplify management, and improve > application availability and disaster protection. Learn more about boosting > the value of server virtualization. http://p.sf.net/sfu/vmware-sfdev2dev_______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss |
From: Gustavo G. <gor...@mi...> - 2011-04-17 18:07:48
|
Hey All, I didn't intent to commit the change to setup.py. Sorry about that. I was trying to install "control" like so: $ python setup.py develop The "develop" option makes apparently makes an egg link from the python dist-packages to src folder. This way changes to the src folder take effect in my python environment. You can accomplish the same thing manually with symlinks, I think. Anyway I haven't been able to get this to work. I haven't developed a python module before so I thought I'd ask your methods. Thanks, Gustavo On Sat, Apr 16, 2011 at 7:45 PM, <gor...@us...> wrote: > Revision: 155 > > http://python-control.svn.sourceforge.net/python-control/?rev=155&view=rev > Author: goretkin > Date: 2011-04-16 23:45:46 +0000 (Sat, 16 Apr 2011) > > Log Message: > ----------- > Support for the **,/ operator. > >> s = control.tf.TransferFunction([1, 0],[1]) > sys = s/(s**2+s+1) #works as expected > > Modified Paths: > -------------- > trunk/setup.py > trunk/src/xferfcn.py > > Modified: trunk/setup.py > =================================================================== > --- trunk/setup.py 2011-04-07 20:12:28 UTC (rev 154) > +++ trunk/setup.py 2011-04-16 23:45:46 UTC (rev 155) > @@ -1,6 +1,7 @@ > #!/usr/bin/env python > > -from distutils.core import setup > +#from distutils.core import setup > +from setuptools import setup > > setup(name = 'control', > version = '0.4c', > > Modified: trunk/src/xferfcn.py > =================================================================== > --- trunk/src/xferfcn.py 2011-04-07 20:12:28 UTC (rev 154) > +++ trunk/src/xferfcn.py 2011-04-16 23:45:46 UTC (rev 155) > @@ -372,9 +372,13 @@ > def __div__(self, other): > """Divide two LTI objects.""" > > - # Convert the second argument to a transfer function. > - other = _convertToTransferFunction(other) > + if isinstance(other, (int, float, long, complex)): > + other = _convertToTransferFunction(other, inputs=self.inputs, > + outputs=self.inputs) > + else: > + other = _convertToTransferFunction(other) > > + > if (self.inputs > 1 or self.outputs > 1 or > other.inputs > 1 or other.outputs > 1): > raise NotImplementedError("TransferFunction.__div__ is > currently \ > @@ -388,6 +392,11 @@ > # TODO: Division of MIMO transfer function objects is not written yet. > def __rdiv__(self, other): > """Right divide two LTI objects.""" > + if isinstance(other, (int, float, long, complex)): > + other = _convertToTransferFunction(other, inputs=self.inputs, > + outputs=self.inputs) > + else: > + other = _convertToTransferFunction(other) > > if (self.inputs > 1 or self.outputs > 1 or > other.inputs > 1 or other.outputs > 1): > @@ -395,6 +404,16 @@ > implemented only for SISO systems.") > > return other / self > + def __pow__(self,other): > + if not type(other) == int: > + raise ValueError("Exponent must be an integer") > + if other == 0: > + return TransferFunction([1],[1]) #unity > + if other > 0: > + return self * (self**(other-1)) > + if other < 0: > + return (TransferFunction([1],[1]) / self) * (self**(other+1)) > + > > def evalfr(self, omega): > """Evaluate a transfer function at a single angular frequency. > > > This was sent by the SourceForge.net collaborative development platform, > the world's largest Open Source development site. > > > ------------------------------------------------------------------------------ > Benefiting from Server Virtualization: Beyond Initial Workload > Consolidation -- Increasing the use of server virtualization is a top > priority.Virtualization can reduce costs, simplify management, and improve > application availability and disaster protection. Learn more about boosting > the value of server virtualization. http://p.sf.net/sfu/vmware-sfdev2dev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > |
From: <gor...@us...> - 2011-04-16 23:45:52
|
Revision: 155 http://python-control.svn.sourceforge.net/python-control/?rev=155&view=rev Author: goretkin Date: 2011-04-16 23:45:46 +0000 (Sat, 16 Apr 2011) Log Message: ----------- Support for the **,/ operator. >> s = control.tf.TransferFunction([1, 0],[1]) sys = s/(s**2+s+1) #works as expected Modified Paths: -------------- trunk/setup.py trunk/src/xferfcn.py Modified: trunk/setup.py =================================================================== --- trunk/setup.py 2011-04-07 20:12:28 UTC (rev 154) +++ trunk/setup.py 2011-04-16 23:45:46 UTC (rev 155) @@ -1,6 +1,7 @@ #!/usr/bin/env python -from distutils.core import setup +#from distutils.core import setup +from setuptools import setup setup(name = 'control', version = '0.4c', Modified: trunk/src/xferfcn.py =================================================================== --- trunk/src/xferfcn.py 2011-04-07 20:12:28 UTC (rev 154) +++ trunk/src/xferfcn.py 2011-04-16 23:45:46 UTC (rev 155) @@ -372,9 +372,13 @@ def __div__(self, other): """Divide two LTI objects.""" - # Convert the second argument to a transfer function. - other = _convertToTransferFunction(other) + if isinstance(other, (int, float, long, complex)): + other = _convertToTransferFunction(other, inputs=self.inputs, + outputs=self.inputs) + else: + other = _convertToTransferFunction(other) + if (self.inputs > 1 or self.outputs > 1 or other.inputs > 1 or other.outputs > 1): raise NotImplementedError("TransferFunction.__div__ is currently \ @@ -388,6 +392,11 @@ # TODO: Division of MIMO transfer function objects is not written yet. def __rdiv__(self, other): """Right divide two LTI objects.""" + if isinstance(other, (int, float, long, complex)): + other = _convertToTransferFunction(other, inputs=self.inputs, + outputs=self.inputs) + else: + other = _convertToTransferFunction(other) if (self.inputs > 1 or self.outputs > 1 or other.inputs > 1 or other.outputs > 1): @@ -395,6 +404,16 @@ implemented only for SISO systems.") return other / self + def __pow__(self,other): + if not type(other) == int: + raise ValueError("Exponent must be an integer") + if other == 0: + return TransferFunction([1],[1]) #unity + if other > 0: + return self * (self**(other-1)) + if other < 0: + return (TransferFunction([1],[1]) / self) * (self**(other+1)) + def evalfr(self, omega): """Evaluate a transfer function at a single angular frequency. This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: Richard M. <mu...@cd...> - 2011-04-16 22:32:48
|
Thanks, Roberto. I'll try to create some equivalent object-oriented implementations, create some test functions, and then post to the repository so that you can see if they work (they should be compatible). -richard On 15 Apr 2011, at 12:16 , Roberto Bucher wrote: > I've atteched the file obtained with diff -u > > I've only inserted a new field in the 2 classes for the sampling time (0- >> continous, != 0 -> discrete) > > Best regards > > Roberto > > -- > ----------------------------------------------------------------------------- > Great spirits have always encountered violent opposition > from mediocre minds (A. Einstein) > ---------------------------------------------------------------------------- > University of Applied Sciences of Southern Switzerland > Dept. Innovative Technologies > CH-6928 Lugano-Manno > http://web.dti.supsi.ch/~bucher > <statesp.patch><matlab.patch><xferfcn.patch> |
From: Richard M. <mu...@cd...> - 2011-04-15 14:33:52
|
Roberto, The problem may be that control.Lti objects are no longer compatible with scipy.signal.lti objects, which the scipy.signal.step() function expects. A couple of fixes: * Instead of using scipy.signal.step(), use the control.matlab.step() function. You can do this by just getting rid of the scipy.signal import statement. Note that we don't have a step2() to function yet, so you may get warnings if you pass a system with a pole at the origin and you don't give a time interval (because it can't figure out the default time scale to use). * You can get the signal.lti object from a control.Lti object using the returnScipySignalLti() method. Note that this returns a 2-dimensional set of scipy.signal.lti objects, even for SISO systems (this will eventually be under the control of the toSISO and toMIMO keywords, which I hope to make part of the v0.4c release). Also, it would be nice to hear how you are implementing the discrete time modifications. I think the cleanest way to do this may be to create a separate class, derived from Lti, for discrete-time systems (transfer functions and state space). -richard On 15 Apr 2011, at 5:04 , Roberto Bucher wrote: > Hi Richard > > I've finally found some time to look the new modifications for your control > toolbox. With few modifications I've reached to put the sampling time in the > new matlab.py, statesp.py and xferfcn.py files. > > My examples run correctly again, but I have some problems with the step and > step2 functions. Here is the code: > > #------------------------------------------------------- > from matplotlib.pylab import * > from control.matlab import * > from scipy.signal import step, step2 > > # Motor parameters > Kt = 126e-6 > Jm = 1.3024e-3 > Dm = 857.4e-6 > > # Transfer function > g=tf([Kt/Jm],[1,Dm/Jm,0]) > > # Continous state space form > a=[[0,1],[0,-Dm/Jm]] > b=[[0],[1]] > c=[[Kt/Jm,0]]; > d=[0]; > sysc=ss(a,b,c,d) > > t1,y1 = step(g) > t2,y2 = step(sysc) > t1,y1 = step2(g) > t2,y2 = step2(sysc) > #--------------------------------------------------------- > I have some problems with the step and step2 functions (linalg problems or > > 695 sys = system > 696 else: > --> 697 sys = lti(*system) > 698 if N is None: > 699 N = 100 > > TypeError: type object argument after * must be a sequence, not instance > > Any Idea? > > Thanks in advance > > Roberto > > -- > ----------------------------------------------------------------------------- > Great spirits have always encountered violent opposition > from mediocre minds (A. Einstein) > ---------------------------------------------------------------------------- > University of Applied Sciences of Southern Switzerland > Dept. Innovative Technologies > CH-6928 Lugano-Manno > http://web.dti.supsi.ch/~bucher |
From: Roberto B. <rob...@su...> - 2011-04-15 12:04:33
|
Hi Richard I've finally found some time to look the new modifications for your control toolbox. With few modifications I've reached to put the sampling time in the new matlab.py, statesp.py and xferfcn.py files. My examples run correctly again, but I have some problems with the step and step2 functions. Here is the code: #------------------------------------------------------- from matplotlib.pylab import * from control.matlab import * from scipy.signal import step, step2 # Motor parameters Kt = 126e-6 Jm = 1.3024e-3 Dm = 857.4e-6 # Transfer function g=tf([Kt/Jm],[1,Dm/Jm,0]) # Continous state space form a=[[0,1],[0,-Dm/Jm]] b=[[0],[1]] c=[[Kt/Jm,0]]; d=[0]; sysc=ss(a,b,c,d) t1,y1 = step(g) t2,y2 = step(sysc) t1,y1 = step2(g) t2,y2 = step2(sysc) #--------------------------------------------------------- I have some problems with the step and step2 functions (linalg problems or 695 sys = system 696 else: --> 697 sys = lti(*system) 698 if N is None: 699 N = 100 TypeError: type object argument after * must be a sequence, not instance Any Idea? Thanks in advance Roberto -- ----------------------------------------------------------------------------- Great spirits have always encountered violent opposition from mediocre minds (A. Einstein) ---------------------------------------------------------------------------- University of Applied Sciences of Southern Switzerland Dept. Innovative Technologies CH-6928 Lugano-Manno http://web.dti.supsi.ch/~bucher |
From: <bli...@us...> - 2011-04-07 20:12:34
|
Revision: 154 http://python-control.svn.sourceforge.net/python-control/?rev=154&view=rev Author: blinkminster Date: 2011-04-07 20:12:28 +0000 (Thu, 07 Apr 2011) Log Message: ----------- added special case to pade to not crash when given zero time delay Modified Paths: -------------- trunk/src/delay.py Modified: trunk/src/delay.py =================================================================== --- trunk/src/delay.py 2011-04-07 20:09:44 UTC (rev 153) +++ trunk/src/delay.py 2011-04-07 20:12:28 UTC (rev 154) @@ -54,15 +54,19 @@ 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] + if T == 0: + num = [1,] + den = [1,] + else: + 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 This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <bli...@us...> - 2011-04-07 20:09:50
|
Revision: 153 http://python-control.svn.sourceforge.net/python-control/?rev=153&view=rev Author: blinkminster Date: 2011-04-07 20:09:44 +0000 (Thu, 07 Apr 2011) Log Message: ----------- added margin command and associated matlab-like wrapper (does not plot yet). bugfixes to bode and default_frequency_range. Modified Paths: -------------- trunk/src/freqplot.py trunk/src/matlab.py Modified: trunk/src/freqplot.py =================================================================== --- trunk/src/freqplot.py 2011-04-03 04:55:51 UTC (rev 152) +++ trunk/src/freqplot.py 2011-04-07 20:09:44 UTC (rev 153) @@ -55,12 +55,13 @@ # # Bode plot -def bode(syslist, omega=None, dB=False, Hz=False, color=None, Plot=True): +def bode(syslist, omega=None, dB=False, Hz=False, deg=True, + color=None, Plot=True): """Bode plot for a system Usage ===== - (mag, phase, 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, deg=True, Plot=True) Plots a Bode plot for the system over a (optional) frequency range. @@ -74,23 +75,30 @@ If True, plot result in dB Hz : boolean If True, plot frequency in Hz (omega must be provided in rad/sec) + color : matplotlib color + Color of line in bode plot + deg : boolean + If True, return phase in degrees (else radians) Plot : boolean If True, plot magnitude and phase Return values ------------- - mag : magnitude array - phase : phase array - omega : frequency array + mag : magnitude array (list if len(syslist) > 1) + phase : phase array (list if len(syslist) > 1) + omega : frequency array (list if len(syslist) > 1) Notes ----- - 1. Alternatively, may use (mag, phase, freq) = sys.freqresp(freq) to generate the frequency response for a system. + 1. Alternatively, you may use the lower-level method + (mag, phase, freq) = sys.freqresp(freq) to generate the frequency + response for a system, but it returns a MIMO response. """ # If argument was a singleton, turn it into a list if (not getattr(syslist, '__iter__', False)): syslist = (syslist,) + mags, phases, omegas = [], [], [] for sys in syslist: if (sys.inputs > 1 or sys.outputs > 1): #TODO: Add MIMO bode plots. @@ -104,10 +112,14 @@ mag_tmp, phase_tmp, omega = sys.freqresp(omega) mag = np.squeeze(mag_tmp) phase = np.squeeze(phase_tmp) + phase = unwrap(phase) if Hz: omega = omega/(2*sp.pi) if dB: mag = 20*sp.log10(mag) - phase = unwrap(phase*180/sp.pi, 360) - + if deg: phase = phase * 180 / sp.pi + + mags.append(mag) + phases.append(phase) + omegas.append(omega) # Get the dimensions of the current axis, which we will divide up #! TODO: Not current implemented; just use subplot for now @@ -134,10 +146,14 @@ # Phase plot plt.subplot(212); + if deg: + phase_deg = phase + else: + phase_deg = phase * 180 / sp.pi if color==None: - plt.semilogx(omega, phase) + plt.semilogx(omega, phase_deg) else: - plt.semilogx(omega, phase, color=color) + plt.semilogx(omega, phase_deg, color=color) plt.hold(True) # Add a grid to the plot @@ -151,7 +167,10 @@ else: plt.xlabel("Frequency (rad/sec)") - return mag, phase, omega + if len(syslist) == 1: + return mags[0], phases[0], omegas[0] + else: + return mags, phases, omegas # Nyquist plot def nyquist(syslist, omega=None, Plot=True): @@ -274,6 +293,101 @@ phase = np.squeeze(phase_tmp) plt.subplot(224); plt.loglog(omega, mag); + +# gain and phase margins +# contributed by Sawyer B. Fuller <mi...@ca...> +def margin(sysdata, deg=True): + """Calculate gain and phase margins and associated crossover frequencies + + Usage: + + gm, pm, sm, wg, wp, ws = margin(sysdata, deg=True) + + Parameters + ---------- + sysdata: linsys or (mag, phase, omega) sequence + sys : linsys + Linear SISO system + mag, phase, omega : sequence of array_like + Input magnitude, phase, and frequencies (rad/sec) sequence from + bode frequency response data + deg=True: boolean + If true, all input and output phases in degrees, else in radians + + Returns + ------- + gm, pm, sm, wg, wp, ws: float + Gain margin gm, phase margin pm, stability margin sm, and + associated crossover + frequencies wg, wp, and ws of SISO open-loop. If more than + one crossover frequency is detected, returns the lowest corresponding + margin. + """ + #TODO do this precisely without the effects of discretization of frequencies? + #TODO assumes SISO + #TODO unit tests, margin plot + + if (not getattr(sysdata, '__iter__', False)): + sys = sysdata + mag, phase, omega = bode(sys, deg=deg, Plot=False) + elif len(sysdata) == 3: + mag, phase, omega = sysdata + else: + raise ValueError("Margin sysdata must be either a linear system or a 3-sequence of mag, phase, omega.") + + if deg: + cycle = 360. + crossover = 180. + else: + cycle = 2 * np.pi + crossover = np.pi + + wrapped_phase = -np.mod(phase, cycle) + + # phase margin from minimum phase among all gain crossovers + neg_mag_crossings_i = np.nonzero(np.diff(mag < 1) > 0)[0] + mag_crossings_p = wrapped_phase[neg_mag_crossings_i] + if len(neg_mag_crossings_i) == 0: + if mag[0] < 1: # gain always less than one + wp = np.nan + pm = np.inf + else: # gain always greater than one + print "margin: no magnitude crossings found" + wp = np.nan + pm = np.nan + else: + min_mag_crossing_i = neg_mag_crossings_i[np.argmin(mag_crossings_p)] + wp = omega[min_mag_crossing_i] + pm = crossover + phase[min_mag_crossing_i] + if pm < 0: + print "warning: system unstable: negative phase margin" + + # gain margin from minimum gain margin among all phase crossovers + neg_phase_crossings_i = np.nonzero(np.diff(wrapped_phase < -crossover) > 0)[0] + neg_phase_crossings_g = mag[neg_phase_crossings_i] + if len(neg_phase_crossings_i) == 0: + wg = np.nan + gm = np.inf + else: + min_phase_crossing_i = neg_phase_crossings_i[ + np.argmax(neg_phase_crossings_g)] + wg = omega[min_phase_crossing_i] + gm = abs(1/mag[min_phase_crossing_i]) + if gm < 1: + print "warning: system unstable: gain margin < 1" + + # stability margin from minimum abs distance from -1 point + if deg: + phase_rad = phase * np.pi / 180. + else: + phase_rad = phase + L = mag * np.exp(1j * phase_rad) # complex loop response to -1 pt + min_Lplus1_i = np.argmin(np.abs(L + 1)) + sm = np.abs(L[min_Lplus1_i] + 1) + ws = phase[min_Lplus1_i] + + return gm, pm, sm, wg, wp, ws + # # Utility functions # @@ -311,6 +425,10 @@ # Find the list of all poles and zeros in the systems features = np.array(()) + + # detect if single sys passed by checking if it is sequence-like + if (not getattr(syslist, '__iter__', False)): + syslist = (syslist,) for sys in syslist: # Add new features to the list features = np.concatenate((features, np.abs(sys.pole()))) Modified: trunk/src/matlab.py =================================================================== --- trunk/src/matlab.py 2011-04-03 04:55:51 UTC (rev 152) +++ trunk/src/matlab.py 2011-04-07 20:09:44 UTC (rev 153) @@ -781,6 +781,39 @@ return rlist, klist +def margin(*args): + """Calculate gain and phase margins and associated crossover frequencies + + Usage: + gm, pm, wg, wp = margin(sys) + gm, pm, wg, wp = margin(mag,phase,w) + + Parameters + ---------- + sys : linsys + Linear SISO system + mag, phase, w : array_like + Input magnitude, phase (in deg.), and frequencies (rad/sec) from bode + frequency response data + + Returns + ------- + gm, pm, wg, wp : float + Gain margin gm, phase margin pm (in deg), and associated crossover + frequencies wg and wp (in rad/sec) of SISO open-loop. If more than + one crossover frequency is detected, returns the lowest corresponding + margin. + """ + if len(args) == 1: + sys = args[0] + margins = freqplot.margin(sys) + elif len(args) == 3: + margins = freqplot.margin(args) + else: + raise ValueError("Margin needs 1 or 3 arguments; received %i." + % len(args)) + + return margins[0], margins[1], margins[3], margins[4] # # Modifications to scipy.signal functions # This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: Sawyer F. <mi...@ca...> - 2011-04-07 18:11:19
|
What Ryan and Richard have suggested seem like pretty good solutions to me: maybe a property of the system that defaults to being SISO if the system has only input and one output (but can be set to MIMO if desired), and a way to override that setting in the calling function? Sawyer ------------------------ Sawyer B. Fuller Ph.D. Candidate, Bioengineering California Institute of Technology http://www.cds.caltech.edu/~minster/ <http://alumni.media.mit.edu/~minster/> On Thu, Apr 7, 2011 at 10:18 AM, Ryan Krauss <rk...@si...> wrote: > I think the idea of having toSISO be a property of the system makes a > lot of sense. At worst, I would have to override it once for each > system that I analyze. We could allow it to be overwritten in the > function calls if we wanted to, but default to the instance property > if it is not passed in: > > def bode(self, ...., toSISO=None): > if toSISO is None: > toSISO = self.toSISO > > Just my thoughts. > > Ryan > > > > On Thu, Apr 7, 2011 at 11:47 AM, Steve Brunton <sbr...@pr...> > wrote: > > Hi All, > > > > This idea of having keywords to change the output format is what we had > in mind when extending to MIMO (as well as whether to plot or just return > output for a command like 'bode'). A a nice interface might have a SISO > system default toSISO=True, a MIMO system would default toMIMO=True, and > there would be the option to have a SISO system output as a MIMO system (for > example if you have scripts that work on both SISO and MIMO outputs). > > > > Even Matlab doesn't have this completely sorted out. When I do > [m,p,w]=bode(sys,w), I still have to squeeze the output for a SISO system. > > > > -S,L,K,B > > > > > > On Apr 7, 2011, at 11:15 AM, Ryan Krauss wrote: > > > >> I think this essentially makes sense, but I use the toolbox with my > >> undergrads who are new to python. They might find it annoying to have > >> to pass in the extra keyword argument toSISO=True every time they > >> generate a Bode plot or something. Can we try to intelligently guess > >> what toSISO should be in the code? i.e. if the system has only one > >> input and one output, assume toSISO=True. We may be able to make this > >> work by using numpy.squeeze on all array outputs. > >> > >> Ryan > >> > >> -- > >> Ryan Krauss, Ph.D. > >> Assistant Professor > >> Mechanical Engineering > >> Southern Illinois University Edwardsville > >> > >> > >> > >> On Thu, Apr 7, 2011 at 9:56 AM, Richard Murray <mu...@cd...> > wrote: > >>> I noticed this change as well. If you are just using the various > functions in python-control, everything works fine (eg, none of the examples > had to change). But if you are extracting frequency responses or otherwise > playing with data generated from your system, this is a bit of a hassle. > >>> > >>> Here is a proposal: > >>> > >>> * For all functions in python-control that accept MIMO systems (all of > them eventually), we add two keywords: > >>> > >>> - toSISO=True will force output to be SISO-like (v0.3) if inputs==1, > outputs==1 > >>> - toSISO=(n, m) will give you SISO-like output for the nth input to > mth output > >>> - toMIMO=True will force the output to be MIMO-like even if inputs==1, > outputs==1 > >>> > >>> * For the Python interface, the default will be toMIMO=True, so that > you get the current behavior. If you want the scalar version of the > outputs, you just add toSISO=True as a keyword. > >>> > >>> * For the MATLAB interface, the default will toSISO=True, so that you > get MATLAB-like behavior if you extract data from bode(), freqresp(), etc. > >>> > >>> One problem with this is that you can have conflicts if you give *both* > sets of keywords. Sometimes this makes sense ("toSISO=(2,3) toMIMO=True"), > but sometimes it doesn't ("toSISO=True, toMIMO=True"). So probably needs a > bit more thought. But the idea is that the following code: > >>> > >>> (mag, phase, omega) = bode(sys) > >>> plot(omega[0][0]), mag[0][0]) > >>> > >>> becomes > >>> > >>> (mag, phase, omega) = bode(sys, toSISO=True) > >>> plot(omega, mag) > >>> > >>> which I think is a bit cleaner. > >>> > >>> Comments, suggestions? > >>> > >>> -richard > >>> > >>> > >>> > >>> On 6 Apr 2011, at 14:19 , Sawyer Fuller wrote: > >>> > >>>> Hey i just downloaded the latest version of python-control and it > looks like everything has gone MIMO. Pretty cool, but is there any way to > way to stick to SISO, eg a subclass or flag? A little bit of a drag to > constantly be appending [0][0] to every frequency response for the most > common use case. I think matlab does a special-case for SISO. Anything like > that in the works or somewhere i'm not finding it? > >>>> > >>>> S > >>>> > >>>> > >>>> ------------------------ > >>>> Sawyer B. Fuller > >>>> Ph.D. Candidate, Bioengineering > >>>> California Institute of Technology > >>>> http://www.cds.caltech.edu/~minster/ > >>>> > >>>> > >>>> > ------------------------------------------------------------------------------ > >>>> Xperia(TM) PLAY > >>>> It's a major breakthrough. An authentic gaming > >>>> smartphone on the nation's most reliable network. > >>>> And it wants your games. > >>>> > http://p.sf.net/sfu/verizon-sfdev_______________________________________________ > >>>> python-control-discuss mailing list > >>>> pyt...@li... > >>>> https://lists.sourceforge.net/lists/listinfo/python-control-discuss > >>> > >>> > >>> > ------------------------------------------------------------------------------ > >>> Xperia(TM) PLAY > >>> It's a major breakthrough. An authentic gaming > >>> smartphone on the nation's most reliable network. > >>> And it wants your games. > >>> http://p.sf.net/sfu/verizon-sfdev > >>> _______________________________________________ > >>> python-control-discuss mailing list > >>> pyt...@li... > >>> https://lists.sourceforge.net/lists/listinfo/python-control-discuss > >>> > >> > >> > ------------------------------------------------------------------------------ > >> Xperia(TM) PLAY > >> It's a major breakthrough. An authentic gaming > >> smartphone on the nation's most reliable network. > >> And it wants your games. > >> http://p.sf.net/sfu/verizon-sfdev > >> _______________________________________________ > >> python-control-discuss mailing list > >> pyt...@li... > >> https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > > > > > > ------------------------------------------------------------------------------ > > Xperia(TM) PLAY > > It's a major breakthrough. An authentic gaming > > smartphone on the nation's most reliable network. > > And it wants your games. > > http://p.sf.net/sfu/verizon-sfdev > > _______________________________________________ > > python-control-discuss mailing list > > pyt...@li... > > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > > > > ------------------------------------------------------------------------------ > Xperia(TM) PLAY > It's a major breakthrough. An authentic gaming > smartphone on the nation's most reliable network. > And it wants your games. > http://p.sf.net/sfu/verizon-sfdev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > |
From: Ryan K. <rk...@si...> - 2011-04-07 17:18:40
|
I think the idea of having toSISO be a property of the system makes a lot of sense. At worst, I would have to override it once for each system that I analyze. We could allow it to be overwritten in the function calls if we wanted to, but default to the instance property if it is not passed in: def bode(self, ...., toSISO=None): if toSISO is None: toSISO = self.toSISO Just my thoughts. Ryan On Thu, Apr 7, 2011 at 11:47 AM, Steve Brunton <sbr...@pr...> wrote: > Hi All, > > This idea of having keywords to change the output format is what we had in mind when extending to MIMO (as well as whether to plot or just return output for a command like 'bode'). A a nice interface might have a SISO system default toSISO=True, a MIMO system would default toMIMO=True, and there would be the option to have a SISO system output as a MIMO system (for example if you have scripts that work on both SISO and MIMO outputs). > > Even Matlab doesn't have this completely sorted out. When I do [m,p,w]=bode(sys,w), I still have to squeeze the output for a SISO system. > > -S,L,K,B > > > On Apr 7, 2011, at 11:15 AM, Ryan Krauss wrote: > >> I think this essentially makes sense, but I use the toolbox with my >> undergrads who are new to python. They might find it annoying to have >> to pass in the extra keyword argument toSISO=True every time they >> generate a Bode plot or something. Can we try to intelligently guess >> what toSISO should be in the code? i.e. if the system has only one >> input and one output, assume toSISO=True. We may be able to make this >> work by using numpy.squeeze on all array outputs. >> >> Ryan >> >> -- >> Ryan Krauss, Ph.D. >> Assistant Professor >> Mechanical Engineering >> Southern Illinois University Edwardsville >> >> >> >> On Thu, Apr 7, 2011 at 9:56 AM, Richard Murray <mu...@cd...> wrote: >>> I noticed this change as well. If you are just using the various functions in python-control, everything works fine (eg, none of the examples had to change). But if you are extracting frequency responses or otherwise playing with data generated from your system, this is a bit of a hassle. >>> >>> Here is a proposal: >>> >>> * For all functions in python-control that accept MIMO systems (all of them eventually), we add two keywords: >>> >>> - toSISO=True will force output to be SISO-like (v0.3) if inputs==1, outputs==1 >>> - toSISO=(n, m) will give you SISO-like output for the nth input to mth output >>> - toMIMO=True will force the output to be MIMO-like even if inputs==1, outputs==1 >>> >>> * For the Python interface, the default will be toMIMO=True, so that you get the current behavior. If you want the scalar version of the outputs, you just add toSISO=True as a keyword. >>> >>> * For the MATLAB interface, the default will toSISO=True, so that you get MATLAB-like behavior if you extract data from bode(), freqresp(), etc. >>> >>> One problem with this is that you can have conflicts if you give *both* sets of keywords. Sometimes this makes sense ("toSISO=(2,3) toMIMO=True"), but sometimes it doesn't ("toSISO=True, toMIMO=True"). So probably needs a bit more thought. But the idea is that the following code: >>> >>> (mag, phase, omega) = bode(sys) >>> plot(omega[0][0]), mag[0][0]) >>> >>> becomes >>> >>> (mag, phase, omega) = bode(sys, toSISO=True) >>> plot(omega, mag) >>> >>> which I think is a bit cleaner. >>> >>> Comments, suggestions? >>> >>> -richard >>> >>> >>> >>> On 6 Apr 2011, at 14:19 , Sawyer Fuller wrote: >>> >>>> Hey i just downloaded the latest version of python-control and it looks like everything has gone MIMO. Pretty cool, but is there any way to way to stick to SISO, eg a subclass or flag? A little bit of a drag to constantly be appending [0][0] to every frequency response for the most common use case. I think matlab does a special-case for SISO. Anything like that in the works or somewhere i'm not finding it? >>>> >>>> S >>>> >>>> >>>> ------------------------ >>>> Sawyer B. Fuller >>>> Ph.D. Candidate, Bioengineering >>>> California Institute of Technology >>>> http://www.cds.caltech.edu/~minster/ >>>> >>>> >>>> ------------------------------------------------------------------------------ >>>> Xperia(TM) PLAY >>>> It's a major breakthrough. An authentic gaming >>>> smartphone on the nation's most reliable network. >>>> And it wants your games. >>>> http://p.sf.net/sfu/verizon-sfdev_______________________________________________ >>>> python-control-discuss mailing list >>>> pyt...@li... >>>> https://lists.sourceforge.net/lists/listinfo/python-control-discuss >>> >>> >>> ------------------------------------------------------------------------------ >>> Xperia(TM) PLAY >>> It's a major breakthrough. An authentic gaming >>> smartphone on the nation's most reliable network. >>> And it wants your games. >>> http://p.sf.net/sfu/verizon-sfdev >>> _______________________________________________ >>> python-control-discuss mailing list >>> pyt...@li... >>> https://lists.sourceforge.net/lists/listinfo/python-control-discuss >>> >> >> ------------------------------------------------------------------------------ >> Xperia(TM) PLAY >> It's a major breakthrough. An authentic gaming >> smartphone on the nation's most reliable network. >> And it wants your games. >> http://p.sf.net/sfu/verizon-sfdev >> _______________________________________________ >> python-control-discuss mailing list >> pyt...@li... >> https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > > ------------------------------------------------------------------------------ > Xperia(TM) PLAY > It's a major breakthrough. An authentic gaming > smartphone on the nation's most reliable network. > And it wants your games. > http://p.sf.net/sfu/verizon-sfdev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > |
From: Steve B. <sbr...@pr...> - 2011-04-07 16:47:31
|
Hi All, This idea of having keywords to change the output format is what we had in mind when extending to MIMO (as well as whether to plot or just return output for a command like 'bode'). A a nice interface might have a SISO system default toSISO=True, a MIMO system would default toMIMO=True, and there would be the option to have a SISO system output as a MIMO system (for example if you have scripts that work on both SISO and MIMO outputs). Even Matlab doesn't have this completely sorted out. When I do [m,p,w]=bode(sys,w), I still have to squeeze the output for a SISO system. -S,L,K,B On Apr 7, 2011, at 11:15 AM, Ryan Krauss wrote: > I think this essentially makes sense, but I use the toolbox with my > undergrads who are new to python. They might find it annoying to have > to pass in the extra keyword argument toSISO=True every time they > generate a Bode plot or something. Can we try to intelligently guess > what toSISO should be in the code? i.e. if the system has only one > input and one output, assume toSISO=True. We may be able to make this > work by using numpy.squeeze on all array outputs. > > Ryan > > -- > Ryan Krauss, Ph.D. > Assistant Professor > Mechanical Engineering > Southern Illinois University Edwardsville > > > > On Thu, Apr 7, 2011 at 9:56 AM, Richard Murray <mu...@cd...> wrote: >> I noticed this change as well. If you are just using the various functions in python-control, everything works fine (eg, none of the examples had to change). But if you are extracting frequency responses or otherwise playing with data generated from your system, this is a bit of a hassle. >> >> Here is a proposal: >> >> * For all functions in python-control that accept MIMO systems (all of them eventually), we add two keywords: >> >> - toSISO=True will force output to be SISO-like (v0.3) if inputs==1, outputs==1 >> - toSISO=(n, m) will give you SISO-like output for the nth input to mth output >> - toMIMO=True will force the output to be MIMO-like even if inputs==1, outputs==1 >> >> * For the Python interface, the default will be toMIMO=True, so that you get the current behavior. If you want the scalar version of the outputs, you just add toSISO=True as a keyword. >> >> * For the MATLAB interface, the default will toSISO=True, so that you get MATLAB-like behavior if you extract data from bode(), freqresp(), etc. >> >> One problem with this is that you can have conflicts if you give *both* sets of keywords. Sometimes this makes sense ("toSISO=(2,3) toMIMO=True"), but sometimes it doesn't ("toSISO=True, toMIMO=True"). So probably needs a bit more thought. But the idea is that the following code: >> >> (mag, phase, omega) = bode(sys) >> plot(omega[0][0]), mag[0][0]) >> >> becomes >> >> (mag, phase, omega) = bode(sys, toSISO=True) >> plot(omega, mag) >> >> which I think is a bit cleaner. >> >> Comments, suggestions? >> >> -richard >> >> >> >> On 6 Apr 2011, at 14:19 , Sawyer Fuller wrote: >> >>> Hey i just downloaded the latest version of python-control and it looks like everything has gone MIMO. Pretty cool, but is there any way to way to stick to SISO, eg a subclass or flag? A little bit of a drag to constantly be appending [0][0] to every frequency response for the most common use case. I think matlab does a special-case for SISO. Anything like that in the works or somewhere i'm not finding it? >>> >>> S >>> >>> >>> ------------------------ >>> Sawyer B. Fuller >>> Ph.D. Candidate, Bioengineering >>> California Institute of Technology >>> http://www.cds.caltech.edu/~minster/ >>> >>> >>> ------------------------------------------------------------------------------ >>> Xperia(TM) PLAY >>> It's a major breakthrough. An authentic gaming >>> smartphone on the nation's most reliable network. >>> And it wants your games. >>> http://p.sf.net/sfu/verizon-sfdev_______________________________________________ >>> python-control-discuss mailing list >>> pyt...@li... >>> https://lists.sourceforge.net/lists/listinfo/python-control-discuss >> >> >> ------------------------------------------------------------------------------ >> Xperia(TM) PLAY >> It's a major breakthrough. An authentic gaming >> smartphone on the nation's most reliable network. >> And it wants your games. >> http://p.sf.net/sfu/verizon-sfdev >> _______________________________________________ >> python-control-discuss mailing list >> pyt...@li... >> https://lists.sourceforge.net/lists/listinfo/python-control-discuss >> > > ------------------------------------------------------------------------------ > Xperia(TM) PLAY > It's a major breakthrough. An authentic gaming > smartphone on the nation's most reliable network. > And it wants your games. > http://p.sf.net/sfu/verizon-sfdev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss |
From: Ryan K. <rk...@si...> - 2011-04-07 15:16:02
|
I think this essentially makes sense, but I use the toolbox with my undergrads who are new to python. They might find it annoying to have to pass in the extra keyword argument toSISO=True every time they generate a Bode plot or something. Can we try to intelligently guess what toSISO should be in the code? i.e. if the system has only one input and one output, assume toSISO=True. We may be able to make this work by using numpy.squeeze on all array outputs. Ryan -- Ryan Krauss, Ph.D. Assistant Professor Mechanical Engineering Southern Illinois University Edwardsville On Thu, Apr 7, 2011 at 9:56 AM, Richard Murray <mu...@cd...> wrote: > I noticed this change as well. If you are just using the various functions in python-control, everything works fine (eg, none of the examples had to change). But if you are extracting frequency responses or otherwise playing with data generated from your system, this is a bit of a hassle. > > Here is a proposal: > > * For all functions in python-control that accept MIMO systems (all of them eventually), we add two keywords: > > - toSISO=True will force output to be SISO-like (v0.3) if inputs==1, outputs==1 > - toSISO=(n, m) will give you SISO-like output for the nth input to mth output > - toMIMO=True will force the output to be MIMO-like even if inputs==1, outputs==1 > > * For the Python interface, the default will be toMIMO=True, so that you get the current behavior. If you want the scalar version of the outputs, you just add toSISO=True as a keyword. > > * For the MATLAB interface, the default will toSISO=True, so that you get MATLAB-like behavior if you extract data from bode(), freqresp(), etc. > > One problem with this is that you can have conflicts if you give *both* sets of keywords. Sometimes this makes sense ("toSISO=(2,3) toMIMO=True"), but sometimes it doesn't ("toSISO=True, toMIMO=True"). So probably needs a bit more thought. But the idea is that the following code: > > (mag, phase, omega) = bode(sys) > plot(omega[0][0]), mag[0][0]) > > becomes > > (mag, phase, omega) = bode(sys, toSISO=True) > plot(omega, mag) > > which I think is a bit cleaner. > > Comments, suggestions? > > -richard > > > > On 6 Apr 2011, at 14:19 , Sawyer Fuller wrote: > >> Hey i just downloaded the latest version of python-control and it looks like everything has gone MIMO. Pretty cool, but is there any way to way to stick to SISO, eg a subclass or flag? A little bit of a drag to constantly be appending [0][0] to every frequency response for the most common use case. I think matlab does a special-case for SISO. Anything like that in the works or somewhere i'm not finding it? >> >> S >> >> >> ------------------------ >> Sawyer B. Fuller >> Ph.D. Candidate, Bioengineering >> California Institute of Technology >> http://www.cds.caltech.edu/~minster/ >> >> >> ------------------------------------------------------------------------------ >> Xperia(TM) PLAY >> It's a major breakthrough. An authentic gaming >> smartphone on the nation's most reliable network. >> And it wants your games. >> http://p.sf.net/sfu/verizon-sfdev_______________________________________________ >> python-control-discuss mailing list >> pyt...@li... >> https://lists.sourceforge.net/lists/listinfo/python-control-discuss > > > ------------------------------------------------------------------------------ > Xperia(TM) PLAY > It's a major breakthrough. An authentic gaming > smartphone on the nation's most reliable network. > And it wants your games. > http://p.sf.net/sfu/verizon-sfdev > _______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss > |
From: Richard M. <mu...@cd...> - 2011-04-07 14:56:31
|
I noticed this change as well. If you are just using the various functions in python-control, everything works fine (eg, none of the examples had to change). But if you are extracting frequency responses or otherwise playing with data generated from your system, this is a bit of a hassle. Here is a proposal: * For all functions in python-control that accept MIMO systems (all of them eventually), we add two keywords: - toSISO=True will force output to be SISO-like (v0.3) if inputs==1, outputs==1 - toSISO=(n, m) will give you SISO-like output for the nth input to mth output - toMIMO=True will force the output to be MIMO-like even if inputs==1, outputs==1 * For the Python interface, the default will be toMIMO=True, so that you get the current behavior. If you want the scalar version of the outputs, you just add toSISO=True as a keyword. * For the MATLAB interface, the default will toSISO=True, so that you get MATLAB-like behavior if you extract data from bode(), freqresp(), etc. One problem with this is that you can have conflicts if you give *both* sets of keywords. Sometimes this makes sense ("toSISO=(2,3) toMIMO=True"), but sometimes it doesn't ("toSISO=True, toMIMO=True"). So probably needs a bit more thought. But the idea is that the following code: (mag, phase, omega) = bode(sys) plot(omega[0][0]), mag[0][0]) becomes (mag, phase, omega) = bode(sys, toSISO=True) plot(omega, mag) which I think is a bit cleaner. Comments, suggestions? -richard On 6 Apr 2011, at 14:19 , Sawyer Fuller wrote: > Hey i just downloaded the latest version of python-control and it looks like everything has gone MIMO. Pretty cool, but is there any way to way to stick to SISO, eg a subclass or flag? A little bit of a drag to constantly be appending [0][0] to every frequency response for the most common use case. I think matlab does a special-case for SISO. Anything like that in the works or somewhere i'm not finding it? > > S > > > ------------------------ > Sawyer B. Fuller > Ph.D. Candidate, Bioengineering > California Institute of Technology > http://www.cds.caltech.edu/~minster/ > > > ------------------------------------------------------------------------------ > Xperia(TM) PLAY > It's a major breakthrough. An authentic gaming > smartphone on the nation's most reliable network. > And it wants your games. > http://p.sf.net/sfu/verizon-sfdev_______________________________________________ > python-control-discuss mailing list > pyt...@li... > https://lists.sourceforge.net/lists/listinfo/python-control-discuss |