From: <par...@us...> - 2010-09-16 22:40:53
|
Revision: 7740 http://octave.svn.sourceforge.net/octave/?rev=7740&view=rev Author: paramaniac Date: 2010-09-16 22:40:46 +0000 (Thu, 16 Sep 2010) Log Message: ----------- control: improve argument checks Modified Paths: -------------- trunk/octave-forge/main/control/inst/@lti/connect.m trunk/octave-forge/main/control/inst/@lti/freqresp.m trunk/octave-forge/main/control/inst/@lti/lft.m trunk/octave-forge/main/control/inst/@lti/mconnect.m trunk/octave-forge/main/control/inst/@lti/minreal.m trunk/octave-forge/main/control/inst/@lti/mpower.m trunk/octave-forge/main/control/inst/@lti/norm.m trunk/octave-forge/main/control/inst/@lti/series.m trunk/octave-forge/main/control/inst/@lti/sminreal.m trunk/octave-forge/main/control/inst/@lti/xperm.m trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m trunk/octave-forge/main/control/inst/__frequency_response__.m trunk/octave-forge/main/control/inst/__ss_dim__.m trunk/octave-forge/main/control/inst/__tf2ss__.m trunk/octave-forge/main/control/inst/__time_response__.m trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/ctrb.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/dlyap.m trunk/octave-forge/main/control/inst/dlyapchol.m trunk/octave-forge/main/control/inst/h2syn.m trunk/octave-forge/main/control/inst/hinfsyn.m trunk/octave-forge/main/control/inst/isctrb.m trunk/octave-forge/main/control/inst/issample.m trunk/octave-forge/main/control/inst/isstabilizable.m trunk/octave-forge/main/control/inst/lyap.m trunk/octave-forge/main/control/inst/lyapchol.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/is_real_scalar.cc trunk/octave-forge/main/control/src/makefile_all.m trunk/octave-forge/main/control/src/makefile_helpers.m Added Paths: ----------- trunk/octave-forge/main/control/src/is_real_matrix.cc trunk/octave-forge/main/control/src/is_real_square_matrix.cc trunk/octave-forge/main/control/src/is_real_vector.cc Modified: trunk/octave-forge/main/control/inst/@lti/connect.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/connect.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/connect.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -36,7 +36,7 @@ ## TODO: proper argument checking ## TODO: name-based interconnections - if (! isreal (cm)) + if (! is_real_matrix (cm)) error ("connect: second argument must be a matrix with real coefficients"); endif Modified: trunk/octave-forge/main/control/inst/@lti/freqresp.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -48,7 +48,7 @@ print_usage (); endif - if (! isreal (w) || ! isvector (w)) # catches freqresp (sys, sys) and freqresp (w, sys) as well + if (! is_real_vector (w)) # catches freqresp (sys, sys) and freqresp (w, sys) as well error ("freqresp: second argument must be a real vector"); endif Modified: trunk/octave-forge/main/control/inst/@lti/lft.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lft.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/lft.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -107,11 +107,11 @@ nu = nu_max; ny = ny_max; else # sys = lft (sys1, sys2, nu, ny) - if (! isnumeric (nu) || ! isscalar (nu) || ! isreal (nu) || nu < 0) + if (! is_real_scalar (nu) || nu < 0) error ("lft: argument nu must be a positive integer"); endif - if (! isnumeric (ny) || ! isscalar (ny) || ! isreal (ny) || ny < 0) + if (! is_real_scalar (ny) || ny < 0) error ("lft: argument ny must be a positive integer"); endif Modified: trunk/octave-forge/main/control/inst/@lti/mconnect.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -75,7 +75,7 @@ error ("mconnect: second argument must be a (%dx&d) matrix", m, p); endif - if (! isreal (M)) + if (! is_real_matrix (M)) error ("mconnect: second argument must be a matrix with real coefficients"); endif Modified: trunk/octave-forge/main/control/inst/@lti/minreal.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/minreal.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/minreal.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -31,7 +31,7 @@ print_usage (); endif - if (isa (tol, "lti") || (tol != "def" && ! isreal (tol) && ! isscalar (tol))) + if (! is_real_scalar (tol) && tol != "def") error ("minreal: second argument must be a real scalar"); endif Modified: trunk/octave-forge/main/control/inst/@lti/mpower.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -25,7 +25,7 @@ function retsys = mpower (sys, e) - if (! isnumeric (e) || ! isscalar (e) || ! isreal (e) || e != round (e)) + if (! is_real_scalar (e) || e != round (e)) error ("lti: mpower: exponent must be an integer"); endif Modified: trunk/octave-forge/main/control/inst/@lti/norm.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/norm.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/norm.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -34,7 +34,7 @@ print_usage (); endif - if (isnumeric (ntype) && isscalar (ntype)) + if (is_real_scalar (ntype)) if (ntype == 2) ntype = "2"; elseif (isinf (ntype)) Modified: trunk/octave-forge/main/control/inst/@lti/series.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/series.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/series.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -59,11 +59,11 @@ [p1, m1] = size (sys1); [p2, m2] = size (sys2); - if (! isvector (out1)) + if (! is_real_vector (out1)) error ("series: argument 3 (outputs1) invalid"); endif - if (! isvector (in2)) + if (! is_real_vector (in2)) error ("series: argument 4 (inputs2) invalid"); endif Modified: trunk/octave-forge/main/control/inst/@lti/sminreal.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/sminreal.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/sminreal.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -56,7 +56,7 @@ sys = ss (sys); endif - if (! (isreal (tol) && isscalar (tol) && (tol >= 0))) + if (! (is_real_scalar (tol) && (tol >= 0))) error ("sminreal: second argument is not a valid tolerance"); endif Modified: trunk/octave-forge/main/control/inst/@lti/xperm.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/xperm.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@lti/xperm.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -30,7 +30,7 @@ print_usage (); endif - if (! isreal (st_idx) || ! isvector (st_idx)) + if (! is_real_vector (st_idx)) error ("xperm: second argument invalid"); endif Modified: trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -35,7 +35,7 @@ if (isa (a, "tfpoly")) p = a; return; - elseif (isreal (a) && isvector (a)) + elseif (is_real_vector (a)) p.poly = reshape (a, 1, []); p = class (p, "tfpoly"); p = __remove_leading_zeros__ (p); Modified: trunk/octave-forge/main/control/inst/__frequency_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -30,7 +30,7 @@ error ("frequency_response: first argument sys must be an LTI system"); endif - if (! isempty (w) && ! (isreal (w) && isvector (w))) + if (! is_real_vector (w)) error ("frequency_response: second argument w must be a vector of frequencies"); endif Modified: trunk/octave-forge/main/control/inst/__ss_dim__.m =================================================================== --- trunk/octave-forge/main/control/inst/__ss_dim__.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/__ss_dim__.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -25,14 +25,12 @@ function [m, n, p] = __ss_dim__ (a, b, c, d, e = []) - if (! all ([isreal(a), isreal(b), isreal(c), isreal(d), isreal(e)])) + ## TODO: create oct-file? + + if (! is_real_matrix (a, b, c, d, e)) error ("ss: system matrices must be real"); endif - if (! all ([ndims(a), ndims(b), ndims(c), ndims(d), ndims(e)] == 2)) - error ("ss: system matrices must be two-dimensional arrays"); - endif - [arows, acols] = size (a); [brows, bcols] = size (b); [crows, ccols] = size (c); Modified: trunk/octave-forge/main/control/inst/__tf2ss__.m =================================================================== --- trunk/octave-forge/main/control/inst/__tf2ss__.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/__tf2ss__.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -66,9 +66,9 @@ error ("tf2ss: empty numerator"); elseif (isempty (den)) error ("tf2ss: empy denominator"); - elseif (! isvector (num)) + elseif (! is_real_vector (num)) error ("num(%dx%d) must be a vector", rows (num), columns (num)); - elseif (! isvector (den)) + elseif (! is_real_vector (den)) error ("den(%dx%d) must be a vector", rows (den), columns (den)); endif Modified: trunk/octave-forge/main/control/inst/__time_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__time_response__.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/__time_response__.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -28,7 +28,7 @@ sys = ss (sys); # sys must be proper endif - if (! isempty (tfinal) && ! isscalar (tfinal)) # time vector t passed + if (! isempty (tfinal) && ! is_real_scalar (tfinal)) # time vector t passed dt = tfinal(2) - tfinal(1); # assume that t is regularly spaced tfinal = tfinal(end); endif Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/care.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -81,27 +81,19 @@ print_usage (); endif - if (! isreal (a) || ! issquare (a)) - error ("care: a must be real and square"); + if (! is_real_square_matrix (a, q, r)) + error ("care: a, q, r must be real and square"); endif - if (! isreal (b) || rows (a) != rows (b)) + if (! is_real_matrix (b) || rows (a) != rows (b)) error ("care: b must be real and conformal to a"); endif - - if (! isreal (q) || ! issquare (q)) - error ("care: q must be real and square"); - endif - - if (! isreal (r) || ! issquare (r)) - error ("care: r must be real and square"); - endif if (columns (r) != columns (b)) error ("care: (b, r) not conformable"); endif - if (! isempty (s) && (! isreal (s) || any (size (s) != size (b)))) + if (! isempty (s) && (! is_real_matrix (s) || ! size_equal (s, b))) error ("care: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", rows (s), columns (s), rows (b), columns (b)); endif Modified: trunk/octave-forge/main/control/inst/ctrb.m =================================================================== --- trunk/octave-forge/main/control/inst/ctrb.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/ctrb.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -34,8 +34,7 @@ endif [a, b] = ssdata (a); elseif (nargin == 2) # ctrb (a, b) - if (! isreal (a) || ! isreal (b) - || rows (a) != rows (b) || ! issquare (a)) + if (! is_real_square_matrix (a) || ! is_real_matrix (b) || rows (a) != rows (b)) error ("ctrb: invalid arguments (a, b)"); endif else Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/dare.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -81,27 +81,19 @@ print_usage (); endif - if (! isreal (a) || ! issquare (a)) - error ("dare: a must be real and square"); + if (! is_real_square_matrix (a, q, r)) + error ("dare: a, q, r must be real and square"); endif - if (! isreal (b) || rows (a) != rows (b)) - error ("dare: b must be real and conformal to a"); + if (! is_real_matrix (b) || rows (a) != rows (b)) + error ("dare: a and b must have the same number of rows"); endif - - if (! isreal (q) || ! issquare (q)) - error ("dare: q must be real and square"); - endif - - if (! isreal (r) || ! issquare (r)) - error ("dare: r must be real and square"); - endif if (columns (r) != columns (b)) - error ("dare: (b, r) not conformable"); + error ("dare: b and r must have the same number of columns"); endif - if (! isempty (s) && (! isreal (s) || any (size (s) != size (b)))) + if (! isempty (s) && (! is_real_matrix (s) || ! size_equal (s, b))) error ("dare: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", rows (s), columns (s), rows (b), columns (b)); endif Modified: trunk/octave-forge/main/control/inst/dlyap.m =================================================================== --- trunk/octave-forge/main/control/inst/dlyap.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/dlyap.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -47,16 +47,12 @@ switch (nargin) case 2 # Lyapunov equation - if (! isreal (a) || ! issquare (a) || isempty (a)) - error ("dlyap: a must be real and square"); + if (! is_real_square_matrix (a, b)) + error ("dlyap: a, b must be real and square"); endif - - if (! isreal (b) || ! issquare (b) || isempty (b)) - error ("dlyap: b must be real and square") - endif if (rows (a) != rows (b)) - error ("dlyap: a and b must have the same number of rows"); + error ("dlyap: a, b must have the same number of rows"); endif [x, scale] = slsb03md (a, -b, true); # AXA' - X = -B @@ -65,15 +61,11 @@ case 3 # Sylvester equation - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("dlyap: a must be real and square"); + if (! is_real_square_matrix (a, b)) + error ("dlyap: a, b must be real and square"); endif - if (! isreal (b) || isempty (b) || ! issquare (b)) - error ("dlyap: b must be real and square"); - endif - - if (! isreal (c) || isempty (c) || rows (c) != rows (a) || columns (c) != columns (b)) + if (! is_real_matrix (c) || rows (c) != rows (a) || columns (c) != columns (b)) error ("dlyap: c must be a real (%dx%d) matrix", rows (a), columns (b)); endif @@ -85,20 +77,12 @@ print_usage (); endif - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("dlyap: a must be real and square"); + if (! is_real_square_matrix (a, b, e)) + error ("dlyap: a, b, e must be real and square"); endif - if (! isreal (b) || isempty (b) || ! issquare (b)) - error ("dlyap: b must be real and square"); - endif - - if (! isreal (e) || isempty (e) || ! issquare (e)) - error ("dlyap: e must be real and square"); - endif - if (rows (b) != rows (a) || rows (e) != rows (a)) - error ("dlyap: a, b, e not conformal"); + error ("dlyap: a, b, e must have the same number of rows"); endif if (! issymmetric (b)) Modified: trunk/octave-forge/main/control/inst/dlyapchol.m =================================================================== --- trunk/octave-forge/main/control/inst/dlyapchol.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/dlyapchol.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -42,12 +42,12 @@ switch (nargin) case 2 - if (! isreal (a) || isempty (a) || ! issquare (a)) + if (! is_real_square_matrix (a)) error ("dlyapchol: a must be real and square"); endif - if (! isreal (b) || isempty (b)) - error ("dlyapchol: b must be real and square") + if (! is_real_matrix (b)) + error ("dlyapchol: b must be real") endif if (rows (a) != rows (b)) @@ -60,20 +60,16 @@ case 3 - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("dlyapchol: a must be real and square"); + if (! is_real_square_matrix (a, e)) + error ("dlyapchol: a, e must be real and square"); endif - - if (! isreal (e) || isempty (e) || ! issquare (e)) - error ("dlyapchol: e must be real and square"); - endif - if (! isreal (b) || isempty (b)) + if (! is_real_matrix (b)) error ("dlyapchol: b must be real"); endif if (rows (b) != rows (a) || rows (e) != rows (a)) - error ("dlyapchol: a, b, e not conformal"); + error ("dlyapchol: a, b, e must have the same number of rows"); endif [u, scale] = slsg03bd (a.', e.', b.', true); Modified: trunk/octave-forge/main/control/inst/h2syn.m =================================================================== --- trunk/octave-forge/main/control/inst/h2syn.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/h2syn.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -84,11 +84,11 @@ error ("h2syn: first argument must be an LTI system"); endif - if (! isscalar (nmeas) || ! isnumeric (nmeas) || isempty (nmeas)) + if (! is_real_scalar (nmeas) || isempty (nmeas)) error ("h2syn: second argument invalid"); endif - if (! isscalar (ncon) || ! isnumeric (ncon) || isempty (ncon)) + if (! is_real_scalar (ncon) || isempty (ncon)) error ("h2syn: third argument invalid"); endif Modified: trunk/octave-forge/main/control/inst/hinfsyn.m =================================================================== --- trunk/octave-forge/main/control/inst/hinfsyn.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/hinfsyn.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -90,15 +90,15 @@ error ("hinfsyn: first argument must be an LTI system"); endif - if (! isscalar (nmeas) || ! isnumeric (nmeas) || isempty (nmeas)) + if (! is_real_scalar (nmeas) || isempty (nmeas)) error ("hinfsyn: second argument invalid"); endif - if (! isscalar (ncon) || ! isnumeric (ncon) || isempty (ncon)) + if (! is_real_scalar (ncon) || isempty (ncon)) error ("hinfsyn: third argument invalid"); endif - if (! isscalar (gmax) || ! isnumeric (gmax) || isempty (gmax) || gmax < 0) + if (! is_real_scalar (gmax) || isempty (gmax) || gmax < 0) error ("hinfsyn: fourth argument invalid"); endif Modified: trunk/octave-forge/main/control/inst/isctrb.m =================================================================== --- trunk/octave-forge/main/control/inst/isctrb.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/isctrb.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -65,15 +65,15 @@ [a, b] = ssdata (a); elseif (nargin < 2) # isctrb (a, b), isctrb (a, b, tol) print_usage (); - elseif (isempty (a) || isempty (b) || rows (a) != rows (b) || ! issquare (a)) + elseif (! is_real_square_matrix (a) || ! is_real_matrix (b) || rows (a) != rows (b)) error ("isctrb: a(%dx%d), b(%dx%d) not conformal", rows (a), columns (a), rows (b), columns (b)); endif - if (! isreal (tol) && ! isscalar (tol)) + if (isempty (tol)) + tol = 0; # default tolerance + elseif (! is_real_scalar (tol)) error ("isctrb: tol must be a real scalar"); - elseif (isempty (tol)) - tol = 0; # default tolerance endif [ac, bc, u, ncont] = slab01od (a, b, tol); Modified: trunk/octave-forge/main/control/inst/issample.m =================================================================== --- trunk/octave-forge/main/control/inst/issample.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/issample.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -36,9 +36,9 @@ endif if (flg == 0) # refuse -1 and 0 - bool = (isreal (tsam) && isscalar (tsam) && (tsam > 0)); + bool = is_real_scalar (tsam) && (tsam > 0); else # allow -1 and 0 - bool = (isreal (tsam) && isscalar (tsam) && (tsam >= 0 || tsam == -1)); + bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1); endif endfunction Modified: trunk/octave-forge/main/control/inst/isstabilizable.m =================================================================== --- trunk/octave-forge/main/control/inst/isstabilizable.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/isstabilizable.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -85,10 +85,10 @@ error ("isstabilizable: a must be square and conformal to b") endif - if (! isreal (tol) && ! isscalar (tol)) + if (isempty (tol)) + tol = 0; # default tolerance + elseif (! is_real_scalar (tol)) error ("isstabilizable: tol must be a real scalar"); - elseif (isempty (tol)) - tol = 0; # default tolerance endif ## controllability staircase form Modified: trunk/octave-forge/main/control/inst/lyap.m =================================================================== --- trunk/octave-forge/main/control/inst/lyap.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/lyap.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -47,16 +47,12 @@ switch (nargin) case 2 # Lyapunov equation - if (! isreal (a) || ! issquare (a) || isempty (a)) - error ("lyap: a must be real and square"); + if (! is_real_square_matrix (a, b)) + error ("lyap: a, b must be real and square"); endif - - if (! isreal (b) || ! issquare (b) || isempty (b)) - error ("lyap: b must be real and square") - endif if (rows (a) != rows (b)) - error ("lyap: a and b must have the same number of rows"); + error ("lyap: a, b must have the same number of rows"); endif [x, scale] = slsb03md (a, -b, false); # AX + XA' = -B @@ -65,15 +61,11 @@ case 3 # Sylvester equation - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("lyap: a must be real and square"); + if (! is_real_square_matrix (a, b)) + error ("lyap: a, b must be real and square"); endif - if (! isreal (b) || isempty (b) || ! issquare (b)) - error ("lyap: b must be real and square"); - endif - - if (! isreal (c) || isempty (c) || rows (c) != rows (a) || columns (c) != columns (b)) + if (! is_real_matrix (c) || rows (c) != rows (a) || columns (c) != columns (b)) error ("lyap: c must be a real (%dx%d) matrix", rows (a), columns (b)); endif @@ -85,20 +77,12 @@ print_usage (); endif - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("lyap: a must be real and square"); + if (! is_real_square_matrix (a, b, e)) + error ("lyap: a, b, e must be real and square"); endif - if (! isreal (b) || isempty (b) || ! issquare (b)) - error ("lyap: b must be real and square"); - endif - - if (! isreal (e) || isempty (e) || ! issquare (e)) - error ("lyap: e must be real and square"); - endif - if (rows (b) != rows (a) || rows (e) != rows (a)) - error ("lyap: a, b, e not conformal"); + error ("lyap: a, b, e must have the same number of rows"); endif if (! issymmetric (b)) Modified: trunk/octave-forge/main/control/inst/lyapchol.m =================================================================== --- trunk/octave-forge/main/control/inst/lyapchol.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/inst/lyapchol.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -42,12 +42,12 @@ switch (nargin) case 2 - if (! isreal (a) || isempty (a) || ! issquare (a)) + if (! is_real_square_matrix (a)) error ("lyapchol: a must be real and square"); endif - if (! isreal (b) || isempty (b)) - error ("lyapchol: b must be real and square") + if (! is_real_matrix (b)) + error ("lyapchol: b must be real") endif if (rows (a) != rows (b)) @@ -60,20 +60,16 @@ case 3 - if (! isreal (a) || isempty (a) || ! issquare (a)) - error ("lyapchol: a must be real and square"); + if (! is_real_square_matrix (a, e)) + error ("lyapchol: a, e must be real and square"); endif - - if (! isreal (e) || isempty (e) || ! issquare (e)) - error ("lyapchol: e must be real and square"); - endif - if (! isreal (b) || isempty (b)) + if (! is_real_matrix (b)) error ("lyapchol: b must be real"); endif if (rows (b) != rows (a) || rows (e) != rows (a)) - error ("lyapchol: a, b, e not conformal"); + error ("lyapchol: a, b, e must have the same number of rows"); endif [u, scale] = slsg03bd (a.', e.', b.', false); Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/src/Makefile 2010-09-16 22:40:46 UTC (rev 7740) @@ -2,7 +2,8 @@ slsb01bd.oct slsb10fd.oct slsb10dd.oct slsb03md.oct slsb04md.oct \ slsb04qd.oct slsg03ad.oct slsb02od.oct slab13ad.oct slab01od.oct \ sltb01pd.oct slsb03od.oct slsg03bd.oct \ - is_ss_mat.oct is_real_scalar.oct + is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ + is_real_square_matrix.oct # transmission zeros of state-space models slab08nd.oct: slab08nd.cc @@ -133,11 +134,17 @@ SG03BY.f MB02UU.f MB02UV.f # helpers -is_ss_mat.oct: is_ss_mat.cc - mkoctfile is_ss_mat.cc - is_real_scalar.oct: is_real_scalar.cc mkoctfile is_real_scalar.cc +is_real_vector.oct: is_real_vector.cc + mkoctfile is_real_vector.cc + +is_real_matrix.oct: is_real_matrix.cc + mkoctfile is_real_matrix.cc + +is_real_square_matrix.oct: is_real_square_matrix.cc + mkoctfile is_real_square_matrix.cc + clean: rm *.o core octave-core *.oct *~ Added: trunk/octave-forge/main/control/src/is_real_matrix.cc =================================================================== --- trunk/octave-forge/main/control/src/is_real_matrix.cc (rev 0) +++ trunk/octave-forge/main/control/src/is_real_matrix.cc 2010-09-16 22:40:46 UTC (rev 7740) @@ -0,0 +1,32 @@ +#include <octave/oct.h> + +DEFUN_DLD (is_real_matrix, args, nargout, + "-*- texinfo -*-\n\ +@deftypefn {Loadable Function} {} is_real_matrix (@var{a}, @dots{})\n\ +Return true if arguments look like a state-space matrix.\n\ +Avoid nasty stuff like @code{true = isreal (""a"")}\n\ +@seealso{is_real_square_matrix, is_real_vector, is_real_scalar}\n\ +@end deftypefn") +{ + octave_value retval = true; + int nargin = args.length (); + + if (nargin == 0) + { + print_usage (); + } + else + { + for (int i = 0; i < nargin; i++) + { + if (args(i).ndims () != 2 || ! args(i).is_numeric_type () + || ! args(i).is_real_type ()) + { + retval = false; + break; + } + } + } + + return retval; +} Modified: trunk/octave-forge/main/control/src/is_real_scalar.cc =================================================================== --- trunk/octave-forge/main/control/src/is_real_scalar.cc 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/src/is_real_scalar.cc 2010-09-16 22:40:46 UTC (rev 7740) @@ -3,8 +3,9 @@ DEFUN_DLD (is_real_scalar, args, nargout, "-*- texinfo -*-\n\ @deftypefn {Loadable Function} {} is_real_scalar (@var{a}, @dots{})\n\ -Return true if arguent is a real scalar.\n\ -@seealso{isreal, ndims}\n\ +Return true if argument is a real scalar.\n\ +Avoid nasty stuff like @code{true = isreal (""a"")}\n\ +@seealso{is_real_matrix, is_real_vector}\n\ @end deftypefn") { octave_value retval = true; Added: trunk/octave-forge/main/control/src/is_real_square_matrix.cc =================================================================== --- trunk/octave-forge/main/control/src/is_real_square_matrix.cc (rev 0) +++ trunk/octave-forge/main/control/src/is_real_square_matrix.cc 2010-09-16 22:40:46 UTC (rev 7740) @@ -0,0 +1,32 @@ +#include <octave/oct.h> + +DEFUN_DLD (is_real_square_matrix, args, nargout, + "-*- texinfo -*-\n\ +@deftypefn {Loadable Function} {} is_real_square_matrix (@var{a}, @dots{})\n\ +Return true if arguments look like a square state-space matrix.\n\ +Avoid nasty stuff like @code{true = isreal (""a"")}\n\ +@seealso{is_real_matrix, is_real_vector, is_real_scalar}\n\ +@end deftypefn") +{ + octave_value retval = true; + int nargin = args.length (); + + if (nargin == 0) + { + print_usage (); + } + else + { + for (int i = 0; i < nargin; i++) + { + if (args(i).ndims () != 2 || args(i).rows () != args(i).columns () + || ! args(i).is_numeric_type () || ! args(i).is_real_type ()) + { + retval = false; + break; + } + } + } + + return retval; +} Added: trunk/octave-forge/main/control/src/is_real_vector.cc =================================================================== --- trunk/octave-forge/main/control/src/is_real_vector.cc (rev 0) +++ trunk/octave-forge/main/control/src/is_real_vector.cc 2010-09-16 22:40:46 UTC (rev 7740) @@ -0,0 +1,32 @@ +#include <octave/oct.h> + +DEFUN_DLD (is_real_vector, args, nargout, + "-*- texinfo -*-\n\ +@deftypefn {Loadable Function} {} is_real_vwctor (@var{a}, @dots{})\n\ +Return true if argument is a real vector.\n\ +Avoid nasty stuff like @code{true = isreal (""a"")}\n\ +@seealso{is_real_square_matrix, is_real_matrix, is_real_scalar}\n\ +@end deftypefn") +{ + octave_value retval = true; + int nargin = args.length (); + + if (nargin == 0) + { + print_usage (); + } + else + { + for (int i = 0; i < nargin; i++) + { + if (args(i).ndims () != 2 || ! (args(i).rows () == 1 || args(i).columns () == 1) + || ! args(i).is_numeric_type () || ! args(i).is_real_type ()) + { + retval = false; + break; + } + } + } + + return retval; +} Modified: trunk/octave-forge/main/control/src/makefile_all.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_all.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/src/makefile_all.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -13,6 +13,7 @@ makefile_chol makefile_h2syn makefile_hankel +makefile_helpers makefile_hinfsyn makefile_lqr makefile_lyap Modified: trunk/octave-forge/main/control/src/makefile_helpers.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_helpers.m 2010-09-16 19:27:34 UTC (rev 7739) +++ trunk/octave-forge/main/control/src/makefile_helpers.m 2010-09-16 22:40:46 UTC (rev 7740) @@ -10,8 +10,12 @@ srcdir = fileparts (which ("makefile_helpers")); cd (srcdir); -mkoctfile is_ss_mat.cc - mkoctfile is_real_scalar.cc +mkoctfile is_real_vector.cc + +mkoctfile is_real_matrix.cc + +mkoctfile is_real_square_matrix.cc + cd (homedir); \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-09-17 17:45:32
|
Revision: 7748 http://octave.svn.sourceforge.net/octave/?rev=7748&view=rev Author: paramaniac Date: 2010-09-17 17:45:25 +0000 (Fri, 17 Sep 2010) Log Message: ----------- control: extend texinfo Modified Paths: -------------- trunk/octave-forge/main/control/inst/@ss/__minreal__.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/slab01od.cc trunk/octave-forge/main/control/src/slab08nd.cc trunk/octave-forge/main/control/src/slab13ad.cc trunk/octave-forge/main/control/src/slab13bd.cc trunk/octave-forge/main/control/src/slab13dd.cc trunk/octave-forge/main/control/src/slsb01bd.cc trunk/octave-forge/main/control/src/slsb02od.cc trunk/octave-forge/main/control/src/slsb03md.cc trunk/octave-forge/main/control/src/slsb03od.cc trunk/octave-forge/main/control/src/slsb04md.cc trunk/octave-forge/main/control/src/slsb04qd.cc trunk/octave-forge/main/control/src/slsb10dd.cc trunk/octave-forge/main/control/src/slsb10ed.cc trunk/octave-forge/main/control/src/slsb10fd.cc trunk/octave-forge/main/control/src/slsb10hd.cc trunk/octave-forge/main/control/src/slsg03ad.cc trunk/octave-forge/main/control/src/slsg03bd.cc trunk/octave-forge/main/control/src/sltb01pd.cc Modified: trunk/octave-forge/main/control/inst/@ss/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-09-17 17:45:25 UTC (rev 7748) @@ -26,7 +26,7 @@ function retsys = __minreal__ (sys, tol) if (! isempty (sys.e)) - error ("ss: zero: dss models not supported yet"); + error ("ss: minreal: dss models not supported yet"); endif if (tol == "def") Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/Makefile 2010-09-17 17:45:25 UTC (rev 7748) @@ -5,6 +5,11 @@ is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ is_real_square_matrix.oct +# TODO: automatically run "rm makefile_*.m" for installation +# TODO: leading and trailing underscores for sl* functions +# (__sl*__.oct) would be nice, but this can be an issue +# for fortran compilers. + # transmission zeros of state-space models slab08nd.oct: slab08nd.cc mkoctfile slab08nd.cc \ Modified: trunk/octave-forge/main/control/src/slab01od.cc =================================================================== --- trunk/octave-forge/main/control/src/slab01od.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slab01od.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -49,7 +49,11 @@ int& INFO); } -DEFUN_DLD (slab01od, args, nargout, "Slicot AB01OD Release 5.0") +DEFUN_DLD (slab01od, args, nargout, + "-*- texinfo -*-\n\ +Slicot AB01OD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slab08nd.cc =================================================================== --- trunk/octave-forge/main/control/src/slab08nd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slab08nd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -64,7 +64,11 @@ int& INFO); } -DEFUN_DLD (slab08nd, args, nargout, "Slicot AB08ND Release 5.0") +DEFUN_DLD (slab08nd, args, nargout, + "-*- texinfo -*-\n\ +Slicot AB08ND Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slab13ad.cc =================================================================== --- trunk/octave-forge/main/control/src/slab13ad.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slab13ad.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -46,7 +46,11 @@ int& INFO); } -DEFUN_DLD (slab13ad, args, nargout, "Slicot AB13AD Release 5.0") +DEFUN_DLD (slab13ad, args, nargout, + "-*- texinfo -*-\n\ +Slicot AB13AD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slab13bd.cc =================================================================== --- trunk/octave-forge/main/control/src/slab13bd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slab13bd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -47,7 +47,11 @@ int& INFO); } -DEFUN_DLD (slab13bd, args, nargout, "Slicot AB13BD Release 5.0") +DEFUN_DLD (slab13bd, args, nargout, + "-*- texinfo -*-\n\ +Slicot AB13BD Release 5.\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slab13dd.cc =================================================================== --- trunk/octave-forge/main/control/src/slab13dd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slab13dd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -51,7 +51,11 @@ int& INFO); } -DEFUN_DLD (slab13dd, args, nargout, "Slicot AB13DD Release 5.0") +DEFUN_DLD (slab13dd, args, nargout, + "-*- texinfo -*-\n\ +Slicot AB13DD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb01bd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb01bd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb01bd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -48,7 +48,11 @@ int& IWARN, int& INFO); } -DEFUN_DLD (slsb01bd, args, nargout, "Slicot SB01BD Release 5.0") +DEFUN_DLD (slsb01bd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB01BD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb02od.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb02od.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb02od.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -58,7 +58,11 @@ int& INFO); } -DEFUN_DLD (slsb02od, args, nargout, "Slicot SB02OD Release 5.0") +DEFUN_DLD (slsb02od, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB02OD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb03md.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb03md.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb03md.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -48,7 +48,11 @@ int& INFO); } -DEFUN_DLD (slsb03md, args, nargout, "Slicot SB03MD Release 5.0") +DEFUN_DLD (slsb03md, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB03MD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb03od.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb03od.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb03od.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -45,7 +45,11 @@ int& INFO); } -DEFUN_DLD (slsb03od, args, nargout, "Slicot SB03OD Release 5.0") +DEFUN_DLD (slsb03od, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB03OD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb04md.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb04md.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb04md.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -44,7 +44,11 @@ int& INFO); } -DEFUN_DLD (slsb04md, args, nargout, "Slicot SB04MD Release 5.0") +DEFUN_DLD (slsb04md, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB04MD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb04qd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb04qd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb04qd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -44,7 +44,11 @@ int& INFO); } -DEFUN_DLD (slsb04qd, args, nargout, "Slicot SB04QD Release 5.0") +DEFUN_DLD (slsb04qd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB04QD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb10dd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb10dd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb10dd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -55,7 +55,11 @@ int& INFO); } -DEFUN_DLD (slsb10dd, args, nargout, "Slicot SB10DD Release 5.0") +DEFUN_DLD (slsb10dd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB10DD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb10ed.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb10ed.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb10ed.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -52,7 +52,11 @@ int& INFO); } -DEFUN_DLD (slsb10ed, args, nargout, "Slicot SB10ED Release 5.0") +DEFUN_DLD (slsb10ed, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB10ED Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb10fd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb10fd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb10fd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -53,7 +53,11 @@ int& INFO); } -DEFUN_DLD (slsb10fd, args, nargout, "Slicot SB10FD Release 5.0") +DEFUN_DLD (slsb10fd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB10FD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsb10hd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsb10hd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsb10hd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -52,7 +52,11 @@ int& INFO); } -DEFUN_DLD (slsb10hd, args, nargout, "Slicot SB10HD Release 5.0") +DEFUN_DLD (slsb10hd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SB10HD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsg03ad.cc =================================================================== --- trunk/octave-forge/main/control/src/slsg03ad.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsg03ad.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -52,7 +52,11 @@ int& INFO); } -DEFUN_DLD (slsg03ad, args, nargout, "Slicot SG03AD Release 5.0") +DEFUN_DLD (slsg03ad, args, nargout, + "-*- texinfo -*-\n\ +Slicot SG03AD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/slsg03bd.cc =================================================================== --- trunk/octave-forge/main/control/src/slsg03bd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/slsg03bd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -48,7 +48,11 @@ int& INFO); } -DEFUN_DLD (slsg03bd, args, nargout, "Slicot SG03BD Release 5.0") +DEFUN_DLD (slsg03bd, args, nargout, + "-*- texinfo -*-\n\ +Slicot SG03BD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; Modified: trunk/octave-forge/main/control/src/sltb01pd.cc =================================================================== --- trunk/octave-forge/main/control/src/sltb01pd.cc 2010-09-17 15:28:07 UTC (rev 7747) +++ trunk/octave-forge/main/control/src/sltb01pd.cc 2010-09-17 17:45:25 UTC (rev 7748) @@ -46,7 +46,11 @@ int& INFO); } -DEFUN_DLD (sltb01pd, args, nargout, "Slicot TB01PD Release 5.0") +DEFUN_DLD (sltb01pd, args, nargout, + "-*- texinfo -*-\n\ +Slicot TB01PD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") { int nargin = args.length (); octave_value_list retval; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2012-08-27 13:22:49
|
Revision: 10923 http://octave.svn.sourceforge.net/octave/?rev=10923&view=rev Author: paramaniac Date: 2012-08-27 13:22:35 +0000 (Mon, 27 Aug 2012) Log Message: ----------- control: prepare release of control-2.3.53 Modified Paths: -------------- trunk/octave-forge/main/control/DESCRIPTION trunk/octave-forge/main/control/NEWS trunk/octave-forge/main/control/devel/RELEASE_PACKAGE trunk/octave-forge/main/control/doc/control.pdf trunk/octave-forge/main/control/doc/control.tex trunk/octave-forge/main/control/doc/functions.texi Modified: trunk/octave-forge/main/control/DESCRIPTION =================================================================== --- trunk/octave-forge/main/control/DESCRIPTION 2012-08-27 01:58:14 UTC (rev 10922) +++ trunk/octave-forge/main/control/DESCRIPTION 2012-08-27 13:22:35 UTC (rev 10923) @@ -1,6 +1,6 @@ Name: Control Version: 2.3.53 -Date: 2012-08-14 +Date: 2012-08-27 Author: Lukas Reichlin <luk...@gm...> Maintainer: Lukas Reichlin <luk...@gm...> Title: Control Systems Modified: trunk/octave-forge/main/control/NEWS =================================================================== --- trunk/octave-forge/main/control/NEWS 2012-08-27 01:58:14 UTC (rev 10922) +++ trunk/octave-forge/main/control/NEWS 2012-08-27 13:22:35 UTC (rev 10923) @@ -1,7 +1,7 @@ Summary of important user-visible changes for releases of the control package =============================================================================== -control-2.3.53 Release Date: 2012-xx-yy Release Manager: Lukas Reichlin +control-2.3.53 Release Date: 2012-08-27 Release Manager: Lukas Reichlin =============================================================================== ** Added new functions for system identification, including: Modified: trunk/octave-forge/main/control/devel/RELEASE_PACKAGE =================================================================== --- trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2012-08-27 01:58:14 UTC (rev 10922) +++ trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2012-08-27 13:22:35 UTC (rev 10923) @@ -21,12 +21,12 @@ rm -R ~/octave/__TEMP__/control/devel cd ~/octave/__TEMP__ grep -i version control/DESCRIPTION -tar czf control-2.3.52.tar.gz control/ -md5 control-2.3.52.tar.gz -md5 control-2.3.52.tar.gz > md5_control_pkg.txt -uuencode control-2.3.52.tar.gz < control-2.3.52.tar.gz > control-2.3.52.tar.gz.uue +tar czf control-2.3.53.tar.gz control/ +md5 control-2.3.53.tar.gz +md5 control-2.3.53.tar.gz > md5_control_pkg.txt +uuencode control-2.3.53.tar.gz < control-2.3.53.tar.gz > control-2.3.53.tar.gz.uue octave -q --eval \ -"pkg install control-2.3.52.tar.gz" +"pkg install control-2.3.53.tar.gz" octave -q --eval \ "pkg load generate_html; generate_package_html ('control', 'control-html', 'octave-forge')" tar czf control-html.tar.gz control-html @@ -41,7 +41,7 @@ ===================================================================================== rm -R ~/octave/__TEMP__ -rm -R ~/octave/control-2.3.52 +rm -R ~/octave/control-2.3.53 ===================================================================================== Modified: trunk/octave-forge/main/control/doc/control.pdf =================================================================== --- trunk/octave-forge/main/control/doc/control.pdf 2012-08-27 01:58:14 UTC (rev 10922) +++ trunk/octave-forge/main/control/doc/control.pdf 2012-08-27 13:22:35 UTC (rev 10923) @@ -42,7 +42,7 @@ >> stream xڅ\x90MK1\x86\xEF\xFB+rL3\x99\xCC&\xB9*\xB6 \xE2Gݞ\xC4ònk\xE9n\xAB\xE0\xBF7i\/\x8A\xC3̛y\x9F\xBC(L:(\xBC>\xF2\xA2\xDBV\xE6\xD4\x96\xA2\xB3i\x85_:\xC7\xEC(\xD5\xCA\xF4\xA8\xD3H\xDD?Kur\x8Eb\x9E7\xD5\xD9ij\xB0j,\x9AEƫ -\x817A4\xCF\xE2Qv\xFB\x9D"\x94\xC7a\xBFQ\x9A<K\xC9Ϫ\xA7檺l\xAA\xD7\xEF\xD5\xE9!GOaD\xC9W\xDA=\xF4bQ\xDDKf\x81\xA2\x89\x98-\xC9\xD4\xE8}\xF1\xBDH\xBE6\x8C\xBED\xF2\xE1\xE3p\xEC\xB7J\xA3<\x94\xC6]\x9E\xB7]\xBEY\xB6˾\xFB\xA1ӛy.\x9C\xBC\xED\x8Emֽ\xE7\xAB\xCF\xEC\xA7o\xA3r\xB5\xCD\xDA2\x9E \xB4\x8B\xA2-\xD7okU[\xD9fG\xEF\xE4J\xB3>c\xAC:EV\xBElV\xBB_\xC3\xF0\xEC\x8F(b\xA41\x8AO\x97Ps\x8E +\x817A4\xCF\xE2Qv\xFB\x9D"\x94\xC7a\xBFQ\x9A<Kɏ\xD4SsU]6\xD5\xEB\xF7\xEA\xF4\x90#\x83\xA70"\x8Cd\x89+\xEDz\xB1\xA8\xEE\x8B%\xB3@\xD1D̖d j\x8C\x82\x83\xF4\xBE\xF8^$_F_"\xF9\xF0q8\xF6[\xA5QJ\xE3.\xCF\xDB.\xDFk\xC5,\xDBe_\x8B\xFDP\x8A\xE9\xCD<N\xDEv\xC76\xEB\xDE\xF3\xD5g\xF6ӷ\xD1\xB9\xDAfmO\xDA\xC5 |
From: <par...@us...> - 2010-09-17 21:19:45
|
Revision: 7749 http://octave.svn.sourceforge.net/octave/?rev=7749&view=rev Author: paramaniac Date: 2010-09-17 21:19:37 +0000 (Fri, 17 Sep 2010) Log Message: ----------- control: transmission zeros of descriptor state-space models Modified Paths: -------------- trunk/octave-forge/main/control/inst/@ss/__zero__.m trunk/octave-forge/main/control/inst/ltimodels.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/makefile_zero.m trunk/octave-forge/main/control/src/slab08nd.cc Added Paths: ----------- trunk/octave-forge/main/control/src/AG08BD.f trunk/octave-forge/main/control/src/AG08BY.f trunk/octave-forge/main/control/src/MA02BD.f trunk/octave-forge/main/control/src/MA02CD.f trunk/octave-forge/main/control/src/TG01FD.f trunk/octave-forge/main/control/src/slag08bd.cc Modified: trunk/octave-forge/main/control/inst/@ss/__zero__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__zero__.m 2010-09-17 17:45:25 UTC (rev 7748) +++ trunk/octave-forge/main/control/inst/@ss/__zero__.m 2010-09-17 21:19:37 UTC (rev 7749) @@ -26,10 +26,11 @@ function [zer, gain] = __zero__ (sys) - if (! isempty (sys.e)) - error ("ss: zero: dss models not supported yet"); + if (isempty (sys.e)) + [zer, gain] = slab08nd (sys.a, sys.b, sys.c, sys.d); + else + zer = slag08bd (sys.a, sys.e, sys.b, sys.c, sys.d); + gain = []; endif - [zer, gain] = slab08nd (sys.a, sys.b, sys.c, sys.d); - endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/ltimodels.m =================================================================== --- trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-17 17:45:25 UTC (rev 7748) +++ trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-17 21:19:37 UTC (rev 7749) @@ -197,6 +197,54 @@ %!assert (z, z_exp, 1e-4); +transmission zeros of descriptor state-space models +%!shared z, z_exp +%! A = [ 1 0 0 0 0 0 0 0 0 +%! 0 1 0 0 0 0 0 0 0 +%! 0 0 1 0 0 0 0 0 0 +%! 0 0 0 1 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 1 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 +%! 0 0 0 0 0 0 0 0 1 ]; +%! +%! E = [ 0 0 0 0 0 0 0 0 0 +%! 1 0 0 0 0 0 0 0 0 +%! 0 1 0 0 0 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 1 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 ]; +%! +%! B = [ -1 0 0 +%! 0 0 0 +%! 0 0 0 +%! 0 -1 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 -1 +%! 0 0 0 +%! 0 0 0 ]; +%! +%! C = [ 0 1 1 0 3 4 0 0 2 +%! 0 1 0 0 4 0 0 2 0 +%! 0 0 1 0 -1 4 0 -2 2 ]; +%! +%! D = [ 1 2 -2 +%! 0 -1 -2 +%! 0 0 0 ]; +%! +%! sys = dss (A, B, C, D, E); +%! z = zero (sys); +%! +%! z_exp = 1; +%! +%!assert (z, z_exp, 1e-4); + + ## ss: minreal (SLICOT TB01PD) %!shared C, D %! Added: trunk/octave-forge/main/control/src/AG08BD.f =================================================================== --- trunk/octave-forge/main/control/src/AG08BD.f (rev 0) +++ trunk/octave-forge/main/control/src/AG08BD.f 2010-09-17 21:19:37 UTC (rev 7749) @@ -0,0 +1,628 @@ + SUBROUTINE AG08BD( EQUIL, L, N, M, P, A, LDA, E, LDE, B, LDB, + $ C, LDC, D, LDD, NFZ, NRANK, NIZ, DINFZ, NKROR, + $ NINFE, NKROL, INFZ, KRONR, INFE, KRONL, + $ TOL, IWORK, DWORK, LDWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To extract from the system pencil +C +C ( A-lambda*E B ) +C S(lambda) = ( ) +C ( C D ) +C +C a regular pencil Af-lambda*Ef which has the finite Smith zeros of +C S(lambda) as generalized eigenvalues. The routine also computes +C the orders of the infinite Smith zeros and determines the singular +C and infinite Kronecker structure of system pencil, i.e., the right +C and left Kronecker indices, and the multiplicities of infinite +C eigenvalues. +C +C ARGUMENTS +C +C Mode Parameters +C +C EQUIL CHARACTER*1 +C Specifies whether the user wishes to balance the system +C matrix as follows: +C = 'S': Perform balancing (scaling); +C = 'N': Do not perform balancing. +C +C Input/Output Parameters +C +C L (input) INTEGER +C The number of rows of matrices A, B, and E. L >= 0. +C +C N (input) INTEGER +C The number of columns of matrices A, E, and C. N >= 0. +C +C M (input) INTEGER +C The number of columns of matrix B. M >= 0. +C +C P (input) INTEGER +C The number of rows of matrix C. P >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading L-by-N part of this array must +C contain the state dynamics matrix A of the system. +C On exit, the leading NFZ-by-NFZ part of this array +C contains the matrix Af of the reduced pencil. +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,L). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading L-by-N part of this array must +C contain the descriptor matrix E of the system. +C On exit, the leading NFZ-by-NFZ part of this array +C contains the matrix Ef of the reduced pencil. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,L). +C +C B (input/output) DOUBLE PRECISION array, dimension (LDB,M) +C On entry, the leading L-by-M part of this array must +C contain the input/state matrix B of the system. +C On exit, this matrix does not contain useful information. +C +C LDB INTEGER +C The leading dimension of array B. +C LDB >= MAX(1,L) if M > 0; +C LDB >= 1 if M = 0. +C +C C (input/output) DOUBLE PRECISION array, dimension (LDC,N) +C On entry, the leading P-by-N part of this array must +C contain the state/output matrix C of the system. +C On exit, this matrix does not contain useful information. +C +C LDC INTEGER +C The leading dimension of array C. LDC >= MAX(1,P). +C +C D (input) DOUBLE PRECISION array, dimension (LDD,M) +C The leading P-by-M part of this array must contain the +C direct transmission matrix D of the system. +C +C LDD INTEGER +C The leading dimension of array D. LDD >= MAX(1,P). +C +C NFZ (output) INTEGER +C The number of finite zeros. +C +C NRANK (output) INTEGER +C The normal rank of the system pencil. +C +C NIZ (output) INTEGER +C The number of infinite zeros. +C +C DINFZ (output) INTEGER +C The maximal multiplicity of infinite Smith zeros. +C +C NKROR (output) INTEGER +C The number of right Kronecker indices. +C +C NINFE (output) INTEGER +C The number of elementary infinite blocks. +C +C NKROL (output) INTEGER +C The number of left Kronecker indices. +C +C INFZ (output) INTEGER array, dimension (N+1) +C The leading DINFZ elements of INFZ contain information +C on the infinite elementary divisors as follows: +C the system has INFZ(i) infinite elementary divisors of +C degree i in the Smith form, where i = 1,2,...,DINFZ. +C +C KRONR (output) INTEGER array, dimension (N+M+1) +C The leading NKROR elements of this array contain the +C right Kronecker (column) indices. +C +C INFE (output) INTEGER array, dimension (1+MIN(L+P,N+M)) +C The leading NINFE elements of INFE contain the +C multiplicities of infinite eigenvalues. +C +C KRONL (output) INTEGER array, dimension (L+P+1) +C The leading NKROL elements of this array contain the +C left Kronecker (row) indices. +C +C Tolerances +C +C TOL DOUBLE PRECISION +C A tolerance used in rank decisions to determine the +C effective rank, which is defined as the order of the +C largest leading (or trailing) triangular submatrix in the +C QR (or RQ) factorization with column (or row) pivoting +C whose estimated condition number is less than 1/TOL. +C If the user sets TOL <= 0, then default tolerances are +C used instead, as follows: TOLDEF = L*N*EPS in TG01FD +C (to determine the rank of E) and TOLDEF = (L+P)*(N+M)*EPS +C in the rest, where EPS is the machine precision +C (see LAPACK Library routine DLAMCH). TOL < 1. +C +C Workspace +C +C IWORK INTEGER array, dimension N+max(1,M) +C On output, IWORK(1) contains the normal rank of the +C transfer function matrix. +C +C DWORK DOUBLE PRECISION array, dimension (LDWORK) +C On exit, if INFO = 0, DWORK(1) returns the optimal value +C of LDWORK. +C +C LDWORK INTEGER +C The length of the array DWORK. +C LDWORK >= max( 4*(L+N), LDW ), if EQUIL = 'S', +C LDWORK >= LDW, if EQUIL = 'N', where +C LDW = max(L+P,M+N)*(M+N) + max(1,5*max(L+P,M+N)). +C For optimum performance LDWORK should be larger. +C +C If LDWORK = -1, then a workspace query is assumed; +C the routine only calculates the optimal size of the +C DWORK array, returns this value as the first entry of +C the DWORK array, and no error message related to LDWORK +C is issued by XERBLA. +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The routine extracts from the system matrix of a descriptor +C system (A-lambda*E,B,C,D) a regular pencil Af-lambda*Ef which +C has the finite zeros of the system as generalized eigenvalues. +C The procedure has the following main computational steps: +C +C (a) construct the (L+P)-by-(N+M) system pencil +C +C S(lambda) = ( B A )-lambda*( 0 E ); +C ( D C ) ( 0 0 ) +C +C (b) reduce S(lambda) to S1(lambda) with the same finite +C zeros and right Kronecker structure but with E +C upper triangular and nonsingular; +C +C (c) reduce S1(lambda) to S2(lambda) with the same finite +C zeros and right Kronecker structure but with D of +C full row rank; +C +C (d) reduce S2(lambda) to S3(lambda) with the same finite zeros +C and with D square invertible; +C +C (e) perform a unitary transformation on the columns of +C +C S3(lambda) = (A-lambda*E B) in order to reduce it to +C ( C D) +C +C (Af-lambda*Ef X), with Y and Ef square invertible; +C ( 0 Y) +C +C (f) compute the right and left Kronecker indices of the system +C matrix, which together with the multiplicities of the +C finite and infinite eigenvalues constitute the +C complete set of structural invariants under strict +C equivalence transformations of a linear system. +C +C REFERENCES +C +C [1] P. Misra, P. Van Dooren and A. Varga. +C Computation of structural invariants of generalized +C state-space systems. +C Automatica, 30, pp. 1921-1936, 1994. +C +C NUMERICAL ASPECTS +C +C The algorithm is backward stable (see [1]). +C +C FURTHER COMMENTS +C +C In order to compute the finite Smith zeros of the system +C explicitly, a call to this routine may be followed by a +C call to the LAPACK Library routines DGEGV or DGGEV. +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen, +C May 1999. +C +C REVISIONS +C +C V. Sima, Research Institute for Informatics, Bucharest, Sep. 1999, +C Jan. 2009, Mar. 2009, Apr. 2009. +C A. Varga, DLR Oberpfaffenhofen, Nov. 1999, Feb. 2002, Mar. 2002. +C +C KEYWORDS +C +C Generalized eigenvalue problem, Kronecker indices, multivariable +C system, orthogonal transformation, structural invariant. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ONE, ZERO + PARAMETER ( ONE = 1.0D0, ZERO = 0.0D0 ) +C .. Scalar Arguments .. + CHARACTER EQUIL + INTEGER DINFZ, INFO, L, LDA, LDB, LDC, LDD, LDE, LDWORK, + $ M, N, NFZ, NINFE, NIZ, NKROL, NKROR, NRANK, P + DOUBLE PRECISION TOL +C .. Array Arguments .. + INTEGER INFE(*), INFZ(*), IWORK(*), KRONL(*), KRONR(*) + DOUBLE PRECISION A(LDA,*), B(LDB,*), C(LDC,*), D(LDD,*), + $ DWORK(*), E(LDE,*) +C .. Local Scalars .. + LOGICAL LEQUIL, LQUERY + INTEGER I, I0, I1, II, IPD, ITAU, J, JWORK, KABCD, + $ LABCD2, LDABCD, LDW, MM, MU, N2, NB, NN, NSINFE, + $ NU, NUMU, PP, WRKOPT + DOUBLE PRECISION SVLMAX, TOLER +C .. Local Arrays .. + DOUBLE PRECISION DUM(1) +C .. External Functions .. + LOGICAL LSAME + INTEGER ILAENV + DOUBLE PRECISION DLAMCH, DLANGE + EXTERNAL DLAMCH, DLANGE, ILAENV, LSAME +C .. External Subroutines .. + EXTERNAL AG08BY, DLACPY, DLASET, DORMRZ, DTZRZF, MA02BD, + $ MA02CD, TB01XD, TG01AD, TG01FD, XERBLA +C .. Intrinsic Functions .. + INTRINSIC DBLE, INT, MAX, MIN +C .. Executable Statements .. +C + INFO = 0 + LDABCD = MAX( L+P, N+M ) + LABCD2 = LDABCD*( N+M ) + LEQUIL = LSAME( EQUIL, 'S' ) + LQUERY = ( LDWORK.EQ.-1 ) +C +C Test the input scalar arguments. +C + IF( .NOT.LEQUIL .AND. .NOT.LSAME( EQUIL, 'N' ) ) THEN + INFO = -1 + ELSE IF( L.LT.0 ) THEN + INFO = -2 + ELSE IF( N.LT.0 ) THEN + INFO = -3 + ELSE IF( M.LT.0 ) THEN + INFO = -4 + ELSE IF( P.LT.0 ) THEN + INFO = -5 + ELSE IF( LDA.LT.MAX( 1, L ) ) THEN + INFO = -7 + ELSE IF( LDE.LT.MAX( 1, L ) ) THEN + INFO = -9 + ELSE IF( LDB.LT.1 .OR. ( M.GT.0 .AND. LDB.LT.L ) ) THEN + INFO = -11 + ELSE IF( LDC.LT.MAX( 1, P ) ) THEN + INFO = -13 + ELSE IF( LDD.LT.MAX( 1, P ) ) THEN + INFO = -15 + ELSE IF( TOL.GE.ONE ) THEN + INFO = -27 + ELSE + I0 = MIN( L+P, M+N ) + I1 = MIN( L, N ) + II = MIN( M, P ) + LDW = LABCD2 + MAX( 1, 5*LDABCD ) + IF( LEQUIL ) + $ LDW = MAX( 4*( L + N ), LDW ) + IF( LQUERY ) THEN + CALL TG01FD( 'N', 'N', 'N', L, N, M, P, A, LDA, E, LDE, B, + $ LDB, C, LDC, DUM, 1, DUM, 1, NN, N2, TOL, + $ IWORK, DWORK, -1, INFO ) + WRKOPT = MAX( LDW, INT( DWORK(1) ) ) + SVLMAX = ZERO + CALL AG08BY( .TRUE., I1, M+N, P+L, SVLMAX, DWORK, LDABCD+I1, + $ E, LDE, NU, MU, NIZ, DINFZ, NKROL, INFZ, KRONL, + $ TOL, IWORK, DWORK, -1, INFO ) + WRKOPT = MAX( WRKOPT, LABCD2 + INT( DWORK(1) ) ) + CALL AG08BY( .FALSE., I1, II, M+N, SVLMAX, DWORK, LDABCD+I1, + $ E, LDE, NU, MU, NIZ, DINFZ, NKROL, INFZ, KRONL, + $ TOL, IWORK, DWORK, -1, INFO ) + WRKOPT = MAX( WRKOPT, LABCD2 + INT( DWORK(1) ) ) + NB = ILAENV( 1, 'ZGERQF', ' ', II, I1+II, -1, -1 ) + WRKOPT = MAX( WRKOPT, LABCD2 + II + II*NB ) + NB = MIN( 64, ILAENV( 1, 'DORMRQ', 'RT', I1, I1+II, II, + $ -1 ) ) + WRKOPT = MAX( WRKOPT, LABCD2 + II + I1*NB ) + ELSE IF( LDWORK.LT.LDW ) THEN + INFO = -30 + END IF + END IF +C + IF( INFO.NE.0 ) THEN +C +C Error return. +C + CALL XERBLA( 'AG08BD', -INFO ) + RETURN + ELSE IF( LQUERY ) THEN + DWORK(1) = WRKOPT + RETURN + END IF +C + NIZ = 0 + NKROL = 0 + NKROR = 0 +C +C Quick return if possible. +C + IF( MAX( L, N, M, P ).EQ.0 ) THEN + NFZ = 0 + DINFZ = 0 + NINFE = 0 + NRANK = 0 + IWORK(1) = 0 + DWORK(1) = ONE + RETURN + END IF +C +C (Note: Comments in the code beginning "Workspace:" describe the +C minimal amount of real workspace needed at that point in the +C code, as well as the preferred amount for good performance.) +C + WRKOPT = 1 + KABCD = 1 + JWORK = KABCD + LABCD2 +C +C If required, balance the system pencil. +C Workspace: need 4*(L+N). +C + IF( LEQUIL ) THEN + CALL TG01AD( 'A', L, N, M, P, ZERO, A, LDA, E, LDE, B, LDB, + $ C, LDC, DWORK, DWORK(L+1), DWORK(L+N+1), INFO ) + WRKOPT = 4*(L+N) + END IF + SVLMAX = DLANGE( 'Frobenius', L, N, E, LDE, DWORK ) +C +C Reduce the system matrix to QR form, +C +C ( A11-lambda*E11 A12 B1 ) +C ( A21 A22 B2 ) , +C ( C1 C2 D ) +C +C with E11 invertible and upper triangular. +C Real workspace: need max( 1, N+P, min(L,N)+max(3*N-1,M,L) ); +C prefer larger. +C Integer workspace: N. +C + CALL TG01FD( 'N', 'N', 'N', L, N, M, P, A, LDA, E, LDE, B, LDB, + $ C, LDC, DUM, 1, DUM, 1, NN, N2, TOL, IWORK, DWORK, + $ LDWORK, INFO ) + WRKOPT = MAX( WRKOPT, INT( DWORK(1) ) ) +C +C Construct the system pencil +C +C MM NN +C ( B1 A12 A11-lambda*E11 ) NN +C S1(lambda) = ( B2 A22 A21 ) L-NN +C ( D C2 C1 ) P +C +C of dimension (L+P)-by-(M+N). +C Workspace: need LABCD2 = max( L+P, N+M )*( N+M ). +C + N2 = N - NN + MM = M + N2 + PP = P + ( L - NN ) + CALL DLACPY( 'Full', L, M, B, LDB, DWORK(KABCD), LDABCD ) + CALL DLACPY( 'Full', P, M, D, LDD, DWORK(KABCD+L), LDABCD ) + CALL DLACPY( 'Full', L, N2, A(1,NN+1), LDA, + $ DWORK(KABCD+LDABCD*M), LDABCD ) + CALL DLACPY( 'Full', P, N2, C(1,NN+1), LDC, + $ DWORK(KABCD+LDABCD*M+L), LDABCD ) + CALL DLACPY( 'Full', L, NN, A, LDA, + $ DWORK(KABCD+LDABCD*MM), LDABCD ) + CALL DLACPY( 'Full', P, NN, C, LDC, + $ DWORK(KABCD+LDABCD*MM+L), LDABCD ) +C +C If required, set tolerance. +C + TOLER = TOL + IF( TOLER.LE.ZERO ) THEN + TOLER = DBLE( ( L + P )*( M + N ) ) * DLAMCH( 'Precision' ) + END IF + SVLMAX = MAX( SVLMAX, + $ DLANGE( 'Frobenius', NN+PP, NN+MM, DWORK(KABCD), + $ LDABCD, DWORK(JWORK) ) ) +C +C Extract the reduced pencil S2(lambda) +C +C ( Bc Ac-lambda*Ec ) +C ( Dc Cc ) +C +C having the same finite Smith zeros as the system pencil +C S(lambda) but with Dc, a MU-by-MM full row rank +C left upper trapezoidal matrix, and Ec, an NU-by-NU +C upper triangular nonsingular matrix. +C +C Real workspace: need max( min(P+L,M+N)+max(min(L,N),3*(M+N)-1), +C 5*(P+L), 1 ) + LABCD2; +C prefer larger. +C Integer workspace: MM, MM <= M+N; PP <= P+L. +C + CALL AG08BY( .TRUE., NN, MM, PP, SVLMAX, DWORK(KABCD), LDABCD, + $ E, LDE, NU, MU, NIZ, DINFZ, NKROL, INFZ, KRONL, + $ TOLER, IWORK, DWORK(JWORK), LDWORK-JWORK+1, INFO ) +C + WRKOPT = MAX( WRKOPT, INT( DWORK(JWORK) ) + JWORK - 1 ) +C +C Set the number of simple (nondynamic) infinite eigenvalues +C and the normal rank of the system pencil. +C + NSINFE = MU + NRANK = NN + MU +C +C Pertranspose the system. +C + CALL TB01XD( 'D', NU, MM, MM, MAX( 0, NU-1 ), MAX( 0, NU-1 ), + $ DWORK(KABCD+LDABCD*MM), LDABCD, + $ DWORK(KABCD), LDABCD, + $ DWORK(KABCD+LDABCD*MM+NU), LDABCD, + $ DWORK(KABCD+NU), LDABCD, INFO ) + CALL MA02BD( 'Right', NU+MM, MM, DWORK(KABCD), LDABCD ) + CALL MA02BD( 'Left', MM, NU+MM, DWORK(KABCD+NU), LDABCD ) + CALL MA02CD( NU, 0, MAX( 0, NU-1 ), E, LDE ) +C + IF( MU.NE.MM ) THEN + NN = NU + PP = MM + MM = MU + KABCD = KABCD + ( PP - MM )*LDABCD +C +C Extract the reduced pencil S3(lambda), +C +C ( Br Ar-lambda*Er ) , +C ( Dr Cr ) +C +C having the same finite Smith zeros as the pencil S(lambda), +C but with Dr, an MU-by-MU invertible upper triangular matrix, +C and Er, an NU-by-NU upper triangular nonsingular matrix. +C +C Workspace: need max( 1, 5*(M+N) ) + LABCD2. +C prefer larger. +C No integer workspace necessary. +C + CALL AG08BY( .FALSE., NN, MM, PP, SVLMAX, DWORK(KABCD), LDABCD, + $ E, LDE, NU, MU, I0, I1, NKROR, IWORK, KRONR, + $ TOLER, IWORK, DWORK(JWORK), LDWORK-JWORK+1, INFO ) +C + WRKOPT = MAX( WRKOPT, INT( DWORK(JWORK) ) + JWORK - 1 ) + END IF +C + IF( NU.NE.0 ) THEN +C +C Perform a unitary transformation on the columns of +C ( Br Ar-lambda*Er ) +C ( Dr Cr ) +C in order to reduce it to +C ( * Af-lambda*Ef ) +C ( Y 0 ) +C with Y and Ef square invertible. +C +C Compute Af by reducing ( Br Ar ) to ( * Af ) . +C ( Dr Cr ) ( Y 0 ) +C + NUMU = NU + MU + IPD = KABCD + NU + ITAU = JWORK + JWORK = ITAU + MU +C +C Workspace: need LABCD2 + 2*min(M,P); +C prefer LABCD2 + min(M,P) + min(M,P)*NB. +C + CALL DTZRZF( MU, NUMU, DWORK(IPD), LDABCD, DWORK(ITAU), + $ DWORK(JWORK), LDWORK-JWORK+1, INFO ) + WRKOPT = MAX( WRKOPT, INT( DWORK(JWORK) ) + JWORK - 1 ) +C +C Workspace: need LABCD2 + min(M,P) + min(L,N); +C prefer LABCD2 + min(M,P) + min(L,N)*NB. +C + CALL DORMRZ( 'Right', 'Transpose', NU, NUMU, MU, NU, + $ DWORK(IPD), LDABCD, DWORK(ITAU), DWORK(KABCD), + $ LDABCD, DWORK(JWORK), LDWORK-JWORK+1, INFO ) + WRKOPT = MAX( WRKOPT, INT( DWORK(JWORK) ) + JWORK - 1 ) +C +C Save Af. +C + CALL DLACPY( 'Full', NU, NU, DWORK(KABCD+LDABCD*MU), LDABCD, A, + $ LDA ) +C +C Compute Ef by applying the saved transformations from previous +C reduction to ( 0 Er ) . +C + CALL DLASET( 'Full', NU, MU, ZERO, ZERO, DWORK(KABCD), LDABCD ) + CALL DLACPY( 'Full', NU, NU, E, LDE, DWORK(KABCD+LDABCD*MU), + $ LDABCD ) +C + CALL DORMRZ( 'Right', 'Transpose', NU, NUMU, MU, NU, + $ DWORK(IPD), LDABCD, DWORK(ITAU), DWORK(KABCD), + $ LDABCD, DWORK(JWORK), LDWORK-JWORK+1, INFO ) +C +C Save Ef. +C + CALL DLACPY( 'Full', NU, NU, DWORK(KABCD+LDABCD*MU), LDABCD, E, + $ LDE ) + END IF +C + NFZ = NU +C +C Set right Kronecker indices (column indices). +C + DO 10 I = 1, NKROR + IWORK(I) = KRONR(I) + 10 CONTINUE +C + J = 0 + DO 30 I = 1, NKROR + DO 20 II = J + 1, J + IWORK(I) + KRONR(II) = I - 1 + 20 CONTINUE + J = J + IWORK(I) + 30 CONTINUE +C + NKROR = J +C +C Set left Kronecker indices (row indices). +C + DO 40 I = 1, NKROL + IWORK(I) = KRONL(I) + 40 CONTINUE +C + J = 0 + DO 60 I = 1, NKROL + DO 50 II = J + 1, J + IWORK(I) + KRONL(II) = I - 1 + 50 CONTINUE + J = J + IWORK(I) + 60 CONTINUE +C + NKROL = J +C +C Determine the number of simple infinite blocks +C as the difference between the number of infinite blocks +C of order greater than one and the order of Dr. +C + NINFE = 0 + DO 70 I = 1, DINFZ + NINFE = NINFE + INFZ(I) + 70 CONTINUE + NINFE = NSINFE - NINFE + DO 80 I = 1, NINFE + INFE(I) = 1 + 80 CONTINUE +C +C Set the structure of infinite eigenvalues. +C + DO 100 I = 1, DINFZ + DO 90 II = NINFE + 1, NINFE + INFZ(I) + INFE(II) = I + 1 + 90 CONTINUE + NINFE = NINFE + INFZ(I) + 100 CONTINUE +C + IWORK(1) = NSINFE + DWORK(1) = WRKOPT + RETURN +C *** Last line of AG08BD *** + END Added: trunk/octave-forge/main/control/src/AG08BY.f =================================================================== --- trunk/octave-forge/main/control/src/AG08BY.f (rev 0) +++ trunk/octave-forge/main/control/src/AG08BY.f 2010-09-17 21:19:37 UTC (rev 7749) @@ -0,0 +1,680 @@ + SUBROUTINE AG08BY( FIRST, N, M, P, SVLMAX, ABCD, LDABCD, E, LDE, + $ NR, PR, NINFZ, DINFZ, NKRONL, INFZ, KRONL, + $ TOL, IWORK, DWORK, LDWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To extract from the (N+P)-by-(M+N) descriptor system pencil +C +C S(lambda) = ( B A - lambda*E ) +C ( D C ) +C +C with E nonsingular and upper triangular a +C (NR+PR)-by-(M+NR) "reduced" descriptor system pencil +C +C ( Br Ar-lambda*Er ) +C Sr(lambda) = ( ) +C ( Dr Cr ) +C +C having the same finite Smith zeros as the pencil +C S(lambda) but with Dr, a PR-by-M full row rank +C left upper trapezoidal matrix, and Er, an NR-by-NR +C upper triangular nonsingular matrix. +C +C ARGUMENTS +C +C Mode Parameters +C +C FIRST LOGICAL +C Specifies if AG08BY is called first time or it is called +C for an already reduced system, with D full column rank +C with the last M rows in upper triangular form: +C FIRST = .TRUE., first time called; +C FIRST = .FALSE., not first time called. +C +C Input/Output Parameters +C +C N (input) INTEGER +C The number of rows of matrix B, the number of columns of +C matrix C and the order of square matrices A and E. +C N >= 0. +C +C M (input) INTEGER +C The number of columns of matrices B and D. M >= 0. +C M <= P if FIRST = .FALSE. . +C +C P (input) INTEGER +C The number of rows of matrices C and D. P >= 0. +C +C SVLMAX (input) DOUBLE PRECISION +C During each reduction step, the rank-revealing QR +C factorization of a matrix stops when the estimated minimum +C singular value is smaller than TOL * MAX(SVLMAX,EMSV), +C where EMSV is the estimated maximum singular value. +C SVLMAX >= 0. +C +C ABCD (input/output) DOUBLE PRECISION array, dimension +C (LDABCD,M+N) +C On entry, the leading (N+P)-by-(M+N) part of this array +C must contain the compound matrix +C ( B A ) , +C ( D C ) +C where A is an N-by-N matrix, B is an N-by-M matrix, +C C is a P-by-N matrix and D is a P-by-M matrix. +C If FIRST = .FALSE., then D must be a full column +C rank matrix with the last M rows in upper triangular form. +C On exit, the leading (NR+PR)-by-(M+NR) part of ABCD +C contains the reduced compound matrix +C ( Br Ar ) , +C ( Dr Cr ) +C where Ar is an NR-by-NR matrix, Br is an NR-by-M matrix, +C Cr is a PR-by-NR matrix, Dr is a PR-by-M full row rank +C left upper trapezoidal matrix with the first PR columns +C in upper triangular form. +C +C LDABCD INTEGER +C The leading dimension of array ABCD. +C LDABCD >= MAX(1,N+P). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading N-by-N part of this array must +C contain the upper triangular nonsingular matrix E. +C On exit, the leading NR-by-NR part contains the reduced +C upper triangular nonsingular matrix Er. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,N). +C +C NR (output) INTEGER +C The order of the reduced matrices Ar and Er; also the +C number of rows of the reduced matrix Br and the number +C of columns of the reduced matrix Cr. +C If Dr is invertible, NR is also the number of finite +C Smith zeros. +C +C PR (output) INTEGER +C The rank of the resulting matrix Dr; also the number of +C rows of reduced matrices Cr and Dr. +C +C NINFZ (output) INTEGER +C Number of infinite zeros. NINFZ = 0 if FIRST = .FALSE. . +C +C DINFZ (output) INTEGER +C The maximal multiplicity of infinite zeros. +C DINFZ = 0 if FIRST = .FALSE. . +C +C NKRONL (output) INTEGER +C The maximal dimension of left elementary Kronecker blocks. +C +C INFZ (output) INTEGER array, dimension (N) +C INFZ(i) contains the number of infinite zeros of +C degree i, where i = 1,2,...,DINFZ. +C INFZ is not referenced if FIRST = .FALSE. . +C +C KRONL (output) INTEGER array, dimension (N+1) +C KRONL(i) contains the number of left elementary Kronecker +C blocks of dimension i-by-(i-1), where i = 1,2,...,NKRONL. +C +C Tolerances +C +C TOL DOUBLE PRECISION +C A tolerance used in rank decisions to determine the +C effective rank, which is defined as the order of the +C largest leading (or trailing) triangular submatrix in the +C QR (or RQ) factorization with column (or row) pivoting +C whose estimated condition number is less than 1/TOL. +C If the user sets TOL <= 0, then an implicitly computed, +C default tolerance TOLDEF = (N+P)*(N+M)*EPS, is used +C instead, where EPS is the machine precision +C (see LAPACK Library routine DLAMCH). +C NOTE that when SVLMAX > 0, the estimated ranks could be +C less than those defined above (see SVLMAX). TOL <= 1. +C +C Workspace +C +C IWORK INTEGER array, dimension (M) +C If FIRST = .FALSE., IWORK is not referenced. +C +C DWORK DOUBLE PRECISION array, dimension (LDWORK) +C On exit, if INFO = 0, DWORK(1) returns the optimal value +C of LDWORK. +C +C LDWORK INTEGER +C The length of the array DWORK. +C LDWORK >= 1, if P = 0; otherwise +C LDWORK >= MAX( 1, N+M-1, MIN(P,M) + MAX(3*M-1,N), 5*P ), +C if FIRST = .TRUE.; +C LDWORK >= MAX( 1, N+M-1, 5*P ), if FIRST = .FALSE. . +C The second term is not needed if M = 0. +C For optimum performance LDWORK should be larger. +C +C If LDWORK = -1, then a workspace query is assumed; +C the routine only calculates the optimal size of the +C DWORK array, returns this value as the first entry of +C the DWORK array, and no error message related to LDWORK +C is issued by XERBLA. +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The subroutine is based on the reduction algorithm of [1]. +C +C REFERENCES +C +C [1] P. Misra, P. Van Dooren and A. Varga. +C Computation of structural invariants of generalized +C state-space systems. +C Automatica, 30, pp. 1921-1936, 1994. +C +C NUMERICAL ASPECTS +C +C The algorithm is numerically backward stable and requires +C 0( (P+N)*(M+N)*N ) floating point operations. +C +C FURTHER COMMENTS +C +C The number of infinite zeros is computed as +C +C DINFZ +C NINFZ = Sum (INFZ(i)*i) . +C i=1 +C Note that each infinite zero of multiplicity k corresponds to +C an infinite eigenvalue of multiplicity k+1. +C The multiplicities of the infinite eigenvalues can be determined +C from PR, DINFZ and INFZ(i), i = 1, ..., DINFZ, as follows: +C +C DINFZ +C - there are PR - Sum (INFZ(i)) simple infinite eigenvalues; +C i=1 +C +C - there are INFZ(i) infinite eigenvalues with multiplicity i+1, +C for i = 1, ..., DINFZ. +C +C The left Kronecker indices are: +C +C [ 0 0 ... 0 | 1 1 ... 1 | .... | NKRONL ... NKRONL ] +C |<- KRONL(1) ->|<- KRONL(2) ->| |<- KRONL(NKRONL) ->| +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C May 1999. Based on the RASP routine SRISEP. +C +C REVISIONS +C +C V. Sima, Research Institute for Informatics, Bucharest, Sep. 1999, +C Jan. 2009, Apr. 2009. +C A. Varga, DLR Oberpfaffenhofen, March 2002. +C +C KEYWORDS +C +C Generalized eigenvalue problem, Kronecker indices, multivariable +C system, orthogonal transformation, structural invariant. +C +C ****************************************************************** +C +C .. Parameters .. + INTEGER IMAX, IMIN + PARAMETER ( IMAX = 1, IMIN = 2 ) + DOUBLE PRECISION ONE, P05, ZERO + PARAMETER ( ONE = 1.0D0, P05 = 0.05D0, ZERO = 0.0D0 ) +C .. Scalar Arguments .. + INTEGER DINFZ, INFO, LDABCD, LDE, LDWORK, M, N, NINFZ, + $ NKRONL, NR, P, PR + DOUBLE PRECISION SVLMAX, TOL + LOGICAL FIRST +C .. Array Arguments .. + INTEGER INFZ( * ), IWORK(*), KRONL( * ) + DOUBLE PRECISION ABCD( LDABCD, * ), DWORK( * ), E( LDE, * ) +C .. Local Scalars .. + LOGICAL LQUERY + INTEGER I, ICOL, ILAST, IRC, IROW, ISMAX, ISMIN, ITAU, + $ J, JLAST, JWORK1, JWORK2, K, MN, MN1, MNR, + $ MNTAU, MP1, MPM, MUI, MUIM1, N1, NB, NBLCKS, + $ PN, RANK, RO, RO1, SIGMA, TAUI, WRKOPT + DOUBLE PRECISION C, C1, C2, RCOND, S, S1, S2, SMAX, SMAXPR, + $ SMIN, SMINPR, T, TT +C .. Local Arrays .. + DOUBLE PRECISION DUM(1), SVAL(3) +C .. External Functions .. + INTEGER IDAMAX, ILAENV + DOUBLE PRECISION DLAMCH, DNRM2 + EXTERNAL DLAMCH, DNRM2, IDAMAX, ILAENV +C .. External Subroutines .. + EXTERNAL DCOPY, DLAIC1, DLAPMT, DLARFG, DLARTG, DLASET, + $ DLATZM, DORMQR, DROT, DSWAP, MB03OY, XERBLA +C .. Intrinsic Functions .. + INTRINSIC ABS, DBLE, INT, MAX, MIN, SQRT +C .. Executable Statements .. +C +C Test the input parameters. +C + LQUERY = ( LDWORK.EQ.-1 ) + INFO = 0 + PN = P + N + MN = M + N + MPM = MIN( P, M ) + IF( N.LT.0 ) THEN + INFO = -2 + ELSE IF( M.LT.0 .OR. ( .NOT.FIRST .AND. M.GT.P ) ) THEN + INFO = -3 + ELSE IF( P.LT.0 ) THEN + INFO = -4 + ELSE IF( SVLMAX.LT.ZERO ) THEN + INFO = -5 + ELSE IF( LDABCD.LT.MAX( 1, PN ) ) THEN + INFO = -7 + ELSE IF( LDE.LT.MAX( 1, N ) ) THEN + INFO = -9 + ELSE IF( TOL.GT.ONE ) THEN + INFO = -17 + ELSE + WRKOPT = MAX( 1, 5*P ) + IF( P.GT.0 ) THEN + IF( M.GT.0 ) THEN + WRKOPT = MAX( WRKOPT, MN-1 ) + IF( FIRST ) THEN + WRKOPT = MAX( WRKOPT, MPM + MAX( 3*M-1, N ) ) + IF( LQUERY ) THEN + NB = MIN( 64, ILAENV( 1, 'DORMQR', 'LT', P, N, + $ MPM, -1 ) ) + WRKOPT = MAX( WRKOPT, MPM + MAX( 1, N )*NB ) + END IF + END IF + END IF + END IF + IF( LDWORK.LT.WRKOPT .AND. .NOT.LQUERY ) THEN + INFO = -20 + END IF + END IF + IF( INFO.NE.0 ) THEN + CALL XERBLA( 'AG08BY', -INFO ) + RETURN + ELSE IF( LQUERY ) THEN + DWORK(1) = WRKOPT + RETURN + END IF +C +C Initialize output variables. +C + PR = P + NR = N + DINFZ = 0 + NINFZ = 0 + NKRONL = 0 +C +C Quick return if possible. +C + IF( P.EQ.0 ) THEN + DWORK(1) = ONE + RETURN + END IF + IF( N.EQ.0 .AND. M.EQ.0 ) THEN + PR = 0 + NKRONL = 1 + KRONL(1) = P + DWORK(1) = ONE + RETURN + END IF +C + RCOND = TOL + IF( RCOND.LE.ZERO ) THEN +C +C Use the default tolerance in rank determination. +C + RCOND = DBLE( PN*MN )*DLAMCH( 'EPSILON' ) + END IF +C +C The D matrix is (RO+SIGMA)-by-M, where RO = P - SIGMA and +C SIGMA = 0 for FIRST = .TRUE. and SIGMA = M for FIRST = .FALSE.. +C The leading (RO+SIGMA)-by-SIGMA submatrix of D has full column +C rank, with the trailing SIGMA-by-SIGMA submatrix upper triangular. +C + IF( FIRST ) THEN + SIGMA = 0 + ELSE + SIGMA = M + END IF + RO = P - SIGMA + MP1 = M + 1 + MUI = 0 + DUM(1) = ZERO +C + ITAU = 1 + JWORK1 = ITAU + MPM + ISMIN = 2*P + 1 + ISMAX = ISMIN + P + JWORK2 = ISMAX + P + NBLCKS = 0 + WRKOPT = 1 +C + 10 IF( PR.EQ.0 ) GO TO 90 +C +C (NR+1,ICOL+1) points to the current position of matrix D. +C + RO1 = RO + MNR = M + NR + IF( M.GT.0 ) THEN +C +C Compress rows of D; first exploit the trapezoidal shape of the +C (RO+SIGMA)-by-SIGMA matrix in the first SIGMA columns of D; +C compress the first SIGMA columns without column pivoting: +C +C ( x x x x x ) ( x x x x x ) +C ( x x x x x ) ( 0 x x x x ) +C ( x x x x x ) - > ( 0 0 x x x ) +C ( 0 x x x x ) ( 0 0 0 x x ) +C ( 0 0 x x x ) ( 0 0 0 x x ) +C +C where SIGMA = 3 and RO = 2. +C Workspace: need maximum M+N-1. +C + IROW = NR + DO 20 ICOL = 1, SIGMA + IROW = IROW + 1 + CALL DLARFG( RO+1, ABCD(IROW,ICOL), ABCD(IROW+1,ICOL), 1, + $ T ) + CALL DLATZM( 'L', RO+1, MNR-ICOL, ABCD(IROW+1,ICOL), 1, T, + $ ABCD(IROW,ICOL+1), ABCD(IROW+1,ICOL+1), + $ LDABCD, DWORK ) + CALL DCOPY( PR-ICOL, DUM, 0, ABCD(IROW+1,ICOL), 1 ) + 20 CONTINUE + WRKOPT = MAX( WRKOPT, MN - 1 ) +C + IF( FIRST ) THEN +C +C Continue with Householder with column pivoting. +C +C ( x x x x x ) ( x x x x x ) +C ( 0 x x x x ) ( 0 x x x x ) +C ( 0 0 x x x ) - > ( 0 0 x x x ) +C ( 0 0 0 x x ) ( 0 0 0 x x ) +C ( 0 0 0 x x ) ( 0 0 0 0 0 ) +C +C Real workspace: need maximum min(P,M)+3*M-1; +C Integer workspace: need maximum M. +C + IROW = MIN( NR+SIGMA+1, PN ) + ICOL = MIN( SIGMA+1, M ) + CALL MB03OY( RO1, M-SIGMA, ABCD(IROW,ICOL), LDABCD, + $ RCOND, SVLMAX, RANK, SVAL, IWORK, DWORK(ITAU), + $ DWORK(JWORK1), INFO ) + WRKOPT = MAX( WRKOPT, JWORK1 + 3*M - 2 ) +C +C Apply the column permutations to B and part of D. +C + CALL DLAPMT( .TRUE., NR+SIGMA, M-SIGMA, ABCD(1,ICOL), + $ LDABCD, IWORK ) +C + IF( RANK.GT.0 ) THEN +C +C Apply the Householder transformations to the submatrix C. +C Workspace: need maximum min(P,M) + N; +C prefer maximum min(P,M) + N*NB. +C + CALL DORMQR( 'Left', 'Transpose', RO1, NR, RANK, + $ ABCD(IROW,ICOL), LDABCD, DWORK(ITAU), + $ ABCD(IROW,MP1), LDABCD, DWORK(JWORK1), + $ LDWORK-JWORK1+1, INFO ) + WRKOPT = MAX( WRKOPT, JWORK1 + INT( DWORK(JWORK1) ) - 1 ) + CALL DLASET( 'Lower', RO1-1, MIN( RO1-1, RANK ), ZERO, + $ ZERO, ABCD(MIN( IROW+1, PN ),ICOL), LDABCD ) + RO1 = RO1 - RANK + END IF + END IF +C +C Terminate if Dr has maximal row rank. +C + IF( RO1.EQ.0 ) GO TO 90 +C + END IF +C +C Update SIGMA. +C + SIGMA = PR - RO1 +C + NBLCKS = NBLCKS + 1 + TAUI = RO1 +C +C Compress the columns of current C to separate a TAUI-by-MUI +C full column rank block. +C + IF( NR.EQ.0 ) THEN +C +C Finish for zero state dimension. +C + PR = SIGMA + RANK = 0 + ELSE +C +C Perform RQ-decomposition with row pivoting on the current C +C while keeping E upper triangular. +C The current C is the TAUI-by-NR matrix delimited by rows +C IRC+1 to IRC+TAUI and columns M+1 to M+NR of ABCD. +C The rank of current C is computed in MUI. +C Workspace: need maximum 5*P. +C + IRC = NR + SIGMA + N1 = NR + IF( TAUI.GT.1 ) THEN +C +C Compute norms. +C + DO 30 I = 1, TAUI + DWORK(I) = DNRM2( NR, ABCD(IRC+I,MP1), LDABCD ) + DWORK(P+I) = DWORK(I) + 30 CONTINUE + END IF +C + RANK = 0 + MNTAU = MIN( TAUI, NR ) +C +C ICOL and IROW will point to the current pivot position in C. +C + ILAST = NR + PR + JLAST = M + NR + IROW = ILAST + ICOL = JLAST + I = TAUI + 40 IF( RANK.LT.MNTAU ) THEN + MN1 = M + N1 +C +C Pivot if necessary. +C + IF( I.NE.1 ) THEN + J = IDAMAX( I, DWORK, 1 ) + IF( J.NE.I ) THEN + DWORK(J) = DWORK(I) + DWORK(P+J) = DWORK(P+I) + CALL DSWAP( N1, ABCD(IROW,MP1), LDABCD, + $ ABCD(IRC+J,MP1), LDABCD ) + END IF + END IF +C +C Zero elements left to ABCD(IROW,ICOL). +C + DO 50 K = 1, N1-1 + J = M + K +C +C Rotate columns J, J+1 to zero ABCD(IROW,J). +C + T = ABCD(IROW,J+1) + CALL DLARTG( T, ABCD(IROW,J), C, S, ABCD(IROW,J+1) ) + ABCD(IROW,J) = ZERO + CALL DROT( IROW-1, ABCD(1,J+1), 1, ABCD(1,J), 1, C, S ) + CALL DROT( K+1, E(1,K+1), 1, E(1,K), 1, C, S ) +C +C Rotate rows K, K+1 to zero E(K+1,K). +C + T = E(K,K) + CALL DLARTG( T, E(K+1,K), C, S, E(K,K) ) + E(K+1,K) = ZERO + CALL DROT( N1-K, E(K,K+1), LDE, E(K+1,K+1), LDE, C, S ) + CALL DROT( MN1, ABCD(K,1), LDABCD, ABCD(K+1,1), LDABCD, + $ C, S ) + 50 CONTINUE +C + IF( RANK.EQ.0 ) THEN +C +C Initialize; exit if matrix is zero (RANK = 0). +C + SMAX = ABS( ABCD(ILAST,JLAST) ) + IF ( SMAX.EQ.ZERO ) GO TO 80 + SMIN = SMAX + SMAXPR = SMAX + SMINPR = SMIN + C1 = ONE + C2 = ONE + ELSE +C +C One step of incremental condition estimation. +C + CALL DCOPY( RANK, ABCD(IROW,ICOL+1), LDABCD, + $ DWORK(JWORK2), 1 ) + CALL DLAIC1( IMIN, RANK, DWORK( ISMIN ), SMIN, + $ DWORK(JWORK2), ABCD(IROW,ICOL), SMINPR, S1, + $ C1 ) + CALL DLAIC1( IMAX, RANK, DWORK( ISMAX ), SMAX, + $ DWORK(JWORK2), ABCD(IROW,ICOL), SMAXPR, S2, + $ C2 ) + WRKOPT = MAX( WRKOPT, 5*P ) + END IF +C +C Check the rank; finish the loop if rank loss occurs. +C + IF( SVLMAX*RCOND.LE.SMAXPR ) THEN + IF( SVLMAX*RCOND.LE.SMINPR ) THEN + IF( SMAXPR*RCOND.LE.SMINPR ) THEN +C +C Finish the loop if last row. +C + IF( N1.EQ.0 ) THEN + RANK = RANK + 1 + GO TO 80 + END IF +C + IF( N1.GT.1 ) THEN +C +C Update norms. +C + IF( I-1.GT.1 ) THEN + DO 60 J = 1, I - 1 + IF( DWORK(J).NE.ZERO ) THEN + T = ONE - ( ABS( ABCD(IRC+J,ICOL) ) + $ /DWORK(J) )**2 + T = MAX( T, ZERO ) + TT = ONE + + $ P05*T*( DWORK(J)/DWORK(P+J) )**2 + IF( TT.NE.ONE ) THEN + DWORK(J) = DWORK(J)*SQRT( T ) + ELSE + DWORK(J) = DNRM2( N1-1, + $ ABCD(IRC+J,MP1), LDABCD ) + DWORK(P+J) = DWORK(J) + END IF + END IF + 60 CONTINUE + END IF + END IF +C + DO 70 J = 1, RANK + DWORK( ISMIN+J-1 ) = S1*DWORK( ISMIN+J-1 ) + DWORK( ISMAX+J-1 ) = S2*DWORK( ISMAX+J-1 ) + 70 CONTINUE +C + DWORK( ISMIN+RANK ) = C1 + DWORK( ISMAX+RANK ) = C2 + SMIN = SMINPR + SMAX = SMAXPR + RANK = RANK + 1 + ICOL = ICOL - 1 + IROW = IROW - 1 + N1 = N1 - 1 + I = I - 1 + GO TO 40 + END IF + END IF + END IF + END IF + END IF +C + 80 CONTINUE + MUI = RANK + NR = NR - MUI + PR = SIGMA + MUI +C +C Set number of left Kronecker blocks of order (i-1)-by-i. +C + KRONL(NBLCKS) = TAUI - MUI +C +C Set number of infinite divisors of order i-1. +C + IF( FIRST .AND. NBLCKS.GT.1 ) + $ INFZ(NBLCKS-1) = MUIM1 - TAUI + MUIM1 = MUI + RO = MUI +C +C Continue reduction if rank of current C is positive. +C + IF( MUI.GT.0 ) + $ GO TO 10 +C +C Determine the maximal degree of infinite zeros and +C the number of infinite zeros. +C + 90 CONTINUE + IF( FIRST ) THEN + IF( MUI.EQ.0 ) THEN + DINFZ = MAX( 0, NBLCKS - 1 ) + ELSE + DINFZ = NBLCKS + INFZ(NBLCKS) = MUI + END IF + K = DINFZ + DO 100 I = K, 1, -1 + IF( INFZ(I).NE.0 ) GO TO 110 + DINFZ = DINFZ - 1 + 100 CONTINUE + 110 CONTINUE + DO 120 I = 1, DINFZ + NINFZ = NINFZ + INFZ(I)*I + 120 CONTINUE + END IF +C +C Determine the maximal order of left elementary Kronecker blocks. +C + NKRONL = NBLCKS + DO 130 I = NBLCKS, 1, -1 + IF( KRONL(I).NE.0 ) GO TO 140 + NKRONL = NKRONL - 1 + 130 CONTINUE + 140 CONTINUE +C + DWORK(1) = WRKOPT + RETURN +C *** Last line of AG08BY *** + END Added: trunk/octave-forge/main/control/src/MA02BD.f =================================================================== --- trunk/octave-forge/main/control/src/MA02BD.f (rev 0) +++ trunk/octave-forge/main/control/src/MA02BD.f 2010-09-17 21:19:37 UTC (rev 7749) @@ -0,0 +1,113 @@ + SUBROUTINE MA02BD( SIDE, M, N, A, LDA ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To reverse the order of rows and/or columns of a given matrix A +C by pre-multiplying and/or post-multiplying it, respectively, with +C a permutation matrix P, where P is a square matrix of appropriate +C order, with ones down the secondary diagonal. +C +C ARGUMENTS +C +C Mode Parameters +C +C SIDE CHARACTER*1 +C Specifies the operation to be performed, as follows: +C = 'L': the order of rows of A is to be reversed by +C pre-multiplying A with P; +C = 'R': the order of columns of A is to be reversed by +C post-multiplying A with P; +C = 'B': both the order of rows and the order of columns +C of A is to be reversed by pre-multiplying and +C post-multiplying A with P. +C +C Input/Output Parameters +C +C M (input) INTEGER +C The number of rows of the matrix A. M >= 0. +C +C N (input) INTEGER +C The number of columns of the matrix A. N >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading M-by-N part of this array must +C contain the given matrix whose rows and/or columns are to +C be permuted. +C On exit, the leading M-by-N part of this array contains +C the matrix P*A if SIDE = 'L', or A*P if SIDE = 'R', or +C P*A*P if SIDE = 'B'. +C +C LDA INTEGER +C The leading dimension of the array A. LDA >= max(1,M). +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, +C DLR Oberpfaffenhofen, March 1998. +C Based on the RASP routine PAP. +C +C REVISIONS +C +C - +C +C ****************************************************************** +C +C .. Scalar Arguments .. + CHARACTER SIDE + INTEGER LDA, M, N +C .. Array Arguments .. + DOUBLE PRECISION A(LDA,*) +C .. Local Scalars .. + LOGICAL BSIDES + INTEGER I, J, K, M2, N2 +C .. External Functions .. + LOGICAL LSAME + EXTERNAL LSAME +C .. External Subroutines .. + EXTERNAL DSWAP +C .. Executable Statements .. +C + BSIDES = LSAME( SIDE, 'B' ) +C + IF( ( LSAME( SIDE, 'L' ) .OR. BSIDES ) .AND. M.GT.1 ) THEN +C +C Compute P*A. +C + M2 = M/2 + K = M - M2 + 1 + DO 10 J = 1, N + CALL DSWAP( M2, A(1,J), -1, A(K,J), 1 ) + 10 CONTINUE + END IF + IF( ( LSAME( SIDE, 'R' ) .OR. BSIDES ) .AND. N.GT.1 ) THEN +C +C Compute A*P. +C + N2 = N/2 + K = N - N2 + 1 + DO 20 I = 1, M + CALL DSWAP( N2, A(I,1), -LDA, A(I,K), LDA ) + 20 CONTINUE + END IF +C + RETURN +C *** Last line of MA02BD *** + END Added: trunk/octave-forge/main/control/src/MA02CD.f =================================================================== --- trunk/octave-forge/main/control/src/MA02CD.f (rev 0) +++ trunk/octave-forge/main/control/src/MA02CD.f 2010-09-17 21:19:37 UTC (rev 7749) @@ -0,0 +1,113 @@ + SUBROUTINE MA02CD( N, KL, KU, A, LDA ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To compute the pertranspose of a central band of a square matrix. +C +C ARGUMENTS +C +C Input/Output Parameters +C +C N (input) INTEGER +C The order of the square matrix A. N >= 0. +C +C KL (input) INTEGER +C The number of subdiagonals of A to be pertransposed. +C 0 <= KL <= N-1. +C +C KU (input) INTEGER +C The number of superdiagonals of A to be pertransposed. +C 0 <= KU <= N-1. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading N-by-N part of this array must +C contain a square matrix whose central band formed from +C the KL subdiagonals, the main diagonal and the KU +C superdiagonals will be pertransposed. +C On exit, the leading N-by-N part of this array contains +C the matrix A with its central band (the KL subdiagonals, +C the main diagonal and the KU superdiagonals) pertransposed +C (that is the elements of each antidiagonal appear in +C reversed order). This is equivalent to forming P*B'*P, +C where B is the matrix formed from the central band of A +C and P is a permutation matrix with ones down the secondary +C diagonal. +C +C LDA INTEGER +C The leading dimension of the array A. LDA >= max(1,N). +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, +C DLR Oberpfaffenhofen, March 1998. +C Based on the RASP routine DMPTR. +C +C REVISIONS +C +C A. Varga, December 2001. +C V. Sima, March 2004. +C +C ****************************************************************** +C +C .. Scalar Arguments .. + INTEGER KL, KU, LDA, N +C .. Array Arguments .. + DOUBLE PRECISION A(LDA,*) +C .. Local Scalars .. + INTEGER I, I1, LDA1 +C .. External Subroutines .. + EXTERNAL DSWAP +C .. Intrinsic Functions .. + INTRINSIC MIN +C .. Executable Statements .. +C +C Quick return if possible. +C + IF( N.LE.1 ) + $ RETURN +C + LDA1 = LDA + 1 +C +C Pertranspose the KL subdiagonals. +C + DO 10 I = 1, MIN( KL, N-2 ) + I1 = (N-I) / 2 + IF( I1.GT.0 ) + $ CALL DSWAP( I1, A(I+1,1), LDA1, A(N-I1+1,N-I1+1-I), -LDA1 ) + 10 CONTINUE +C +C Pertranspose the KU superdiagonals. +C + DO 20 I = 1, MIN( KU, N-2 ) + I1 = (N-I) / 2 + IF( I1.GT.0 ) + $ CALL DSWAP( I1, A(1,I+1), LDA1, A(N-I1+1-I,N-I1+1), -LDA1 ) + 20 CONTINUE +C +C Pertranspose the diagonal. +C + I1 = N / 2 + IF( I1.GT.0 ) + $ CALL DSWAP( I1, A(1,1), LDA1, A(N-I1+1,N-I1+1), -LDA1 ) +C + RETURN +C *** Last line of MA02CD *** + END Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-09-17 17:45:25 UTC (rev 7748) +++ trunk/octave-forge/main/control/src/Makefile 2010-09-17 21:19:37 UTC (rev 7749) @@ -1,7 +1,7 @@ all: slab08nd.oct slab13dd.oct slsb10hd.oct slsb10ed.oct slab13bd.oct \ slsb01bd.oct slsb10fd.oct slsb10dd.oct slsb03md.oct slsb04md.oct \ slsb04qd.oct slsg03ad.oct slsb02od.oct slab13ad.oct slab01od.oct \ - sltb01pd.oct slsb03od.oct slsg03bd.oct \ + sltb01pd.oct slsb03od.oct slsg03bd.oct slag08bd.oct \ is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ is_real_square_matrix.oct @@ -138,6 +138,12 @@ SG03BD.f SG03BV.f SG03BU.f SG03BW.f SG03BX.f \ SG03BY.f MB02UU.f MB02UV.f +# transmission zeros of descriptor state-space models +slag08bd.oct: slag08bd.cc + mkoctfile slag08bd.cc \ + AG08BD.f AG08BY.f TG01AD.f TB01XD.f MA02CD.f \ + TG01FD.f MA02BD.f MB03OY.f + # helpers is_real_scalar.oct: is_real_scalar.cc mkoctfile is_real_scalar.cc Added: trunk/octave-forge/main/control/src/TG01FD.f =================================================================== --- trunk/octave-forge/main/control/src/TG01FD.f (rev 0) +++ trunk/octave-forge/main/control/src/TG01FD.f 2010-09-17 21:19:37 UTC (rev 7749) @@ -0,0 +1,725 @@ + SUBROUTINE TG01FD( COMPQ, COMPZ, JOBA, L, N, M, P, A, LDA, E, LDE, + $ B, LDB, C, LDC, Q, LDQ, Z, LDZ, RANKE, RNKA22, + $ TOL, IWORK, DWORK, LDWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free s... [truncated message content] |
From: <par...@us...> - 2010-09-19 19:24:53
|
Revision: 7754 http://octave.svn.sourceforge.net/octave/?rev=7754&view=rev Author: paramaniac Date: 2010-09-19 19:24:46 +0000 (Sun, 19 Sep 2010) Log Message: ----------- control: tinker with dss gain Modified Paths: -------------- trunk/octave-forge/main/control/inst/@ss/__zero__.m trunk/octave-forge/main/control/inst/@ss/ss.m trunk/octave-forge/main/control/inst/__ss_dim__.m trunk/octave-forge/main/control/src/slab08nd.cc trunk/octave-forge/main/control/src/slag08bd.cc Modified: trunk/octave-forge/main/control/inst/@ss/__zero__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__zero__.m 2010-09-18 12:45:21 UTC (rev 7753) +++ trunk/octave-forge/main/control/inst/@ss/__zero__.m 2010-09-19 19:24:46 UTC (rev 7754) @@ -29,8 +29,8 @@ if (isempty (sys.e)) [zer, gain] = slab08nd (sys.a, sys.b, sys.c, sys.d); else - zer = slag08bd (sys.a, sys.e, sys.b, sys.c, sys.d); - gain = []; + [zer, gain] = slag08bd (sys.a, sys.e, sys.b, sys.c, sys.d); + ## FIXME: I'm not sure whether the gain is always correct endif endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@ss/ss.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/ss.m 2010-09-18 12:45:21 UTC (rev 7753) +++ trunk/octave-forge/main/control/inst/@ss/ss.m 2010-09-19 19:24:46 UTC (rev 7754) @@ -118,7 +118,7 @@ a = []; # avoid [](nx0) or [](0xn) endif - [m, n, p] = __ss_dim__ (a, b, c, d); + [p, m, n] = __ss_dim__ (a, b, c, d); stname = repmat ({""}, n, 1); Modified: trunk/octave-forge/main/control/inst/__ss_dim__.m =================================================================== --- trunk/octave-forge/main/control/inst/__ss_dim__.m 2010-09-18 12:45:21 UTC (rev 7753) +++ trunk/octave-forge/main/control/inst/__ss_dim__.m 2010-09-19 19:24:46 UTC (rev 7754) @@ -16,14 +16,14 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Number of inputs (m), states (n) and outputs (p) of state space matrices. +## Number of outputs (p), inputs (m) and states (n) of state space matrices. ## For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 ## Version: 0.2 -function [m, n, p] = __ss_dim__ (a, b, c, d, e = []) +function [p, m, n] = __ss_dim__ (a, b, c, d, e = []) ## TODO: create oct-file? Modified: trunk/octave-forge/main/control/src/slab08nd.cc =================================================================== --- trunk/octave-forge/main/control/src/slab08nd.cc 2010-09-18 12:45:21 UTC (rev 7753) +++ trunk/octave-forge/main/control/src/slab08nd.cc 2010-09-19 19:24:46 UTC (rev 7754) @@ -191,10 +191,10 @@ if (m == 1 && p == 1) { - if (nu == n) + if (nu < n) + gain = c * xpow (a, double (n-1-nu)) * b; + else gain = d; - else - gain = c * xpow (a, double (n-1-nu)) * b; } // assemble complex vector - adapted from DEFUN complex in data.cc Modified: trunk/octave-forge/main/control/src/slag08bd.cc =================================================================== --- trunk/octave-forge/main/control/src/slag08bd.cc 2010-09-18 12:45:21 UTC (rev 7753) +++ trunk/octave-forge/main/control/src/slag08bd.cc 2010-09-19 19:24:46 UTC (rev 7754) @@ -194,18 +194,23 @@ if (info2 != 0) error ("dss: zero: slag08bd: DGGEV returned info = %d", info2); -/* + // calculate gain octave_value gain = Matrix (0, 0);; - if (m == 1 && p == 1) + if (m == 1 && p == 1) // FIXME: I'm not sure of this { - if (nu == n) + if (nfz < n) + gain = args(3).matrix_value () * (args(1).matrix_value ()).inverse () * xpow (args(0).matrix_value (), double (n-1-nfz)) * args(2).matrix_value (); + // gain = args(3).matrix_value () * xpow (args(0).matrix_value (), double (n-1-nfz)) * (args(1).matrix_value ()).inverse () * args(2).matrix_value (); + // NOTE: content of matrices has changed + // c * inv (e) * a^(n-1-nfz) * b ? + // c * a^(n-1-nfz) * inv (e) * b ? + // good examples needed where a^(n-1-nfz) != eye (n) + else gain = d; - else - gain = c * xpow (a, double (n-1-nu)) * b; } -*/ + // assemble complex vector - adapted from DEFUN complex in data.cc // LAPACK DGGEV.f says: // @@ -231,7 +236,7 @@ // return values retval(0) = zero; - // retval(1) = gain; + retval(1) = gain; } return retval; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-09-24 18:29:43
|
Revision: 7764 http://octave.svn.sourceforge.net/octave/?rev=7764&view=rev Author: paramaniac Date: 2010-09-24 18:29:37 +0000 (Fri, 24 Sep 2010) Log Message: ----------- control: fix norm for descriptor models Modified Paths: -------------- trunk/octave-forge/main/control/inst/@lti/norm.m trunk/octave-forge/main/control/src/slab13dd.cc Modified: trunk/octave-forge/main/control/inst/@lti/norm.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/norm.m 2010-09-24 17:10:38 UTC (rev 7763) +++ trunk/octave-forge/main/control/inst/@lti/norm.m 2010-09-24 18:29:37 UTC (rev 7764) @@ -1,4 +1,4 @@ -## Copyright (C) 2009 Lukas F. Reichlin +## Copyright (C) 2009 - 2010 Lukas F. Reichlin ## ## This file is part of LTI Syncope. ## @@ -26,7 +26,7 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: November 2009 -## Version: 0.2 +## Version: 0.3 function [gain, varargout] = norm (sys, ntype = "2", tol = 0.01) @@ -86,11 +86,21 @@ function [gain, wpeak] = linfnorm (sys, tol = 0.01) - [a, b, c, d, tsam] = ssdata (sys); + [a, b, c, d, e, tsam] = dssdata (sys, []); discrete = ! isct (sys); tol = max (tol, 100*eps); - [fpeak, gpeak] = slab13dd (a, b, c, d, discrete, tol); + if (isempty (e)) + [fpeak, gpeak] = slab13dd (a, a, b, c, d, discrete, false, tol); # TODO: avoid dummy argument + else + if (rcond (e) < eps) + gain = inf; + wpeak = inf; + return; + else + [fpeak, gpeak] = slab13dd (a, e, b, c, d, discrete, true, tol); + endif + endif if (fpeak(2) > 0) if (discrete) Modified: trunk/octave-forge/main/control/src/slab13dd.cc =================================================================== --- trunk/octave-forge/main/control/src/slab13dd.cc 2010-09-24 17:10:38 UTC (rev 7763) +++ trunk/octave-forge/main/control/src/slab13dd.cc 2010-09-24 18:29:37 UTC (rev 7764) @@ -60,7 +60,7 @@ int nargin = args.length (); octave_value_list retval; - if (nargin != 6) + if (nargin != 8) { print_usage (); } @@ -68,32 +68,38 @@ { // arguments in char dico; - char jobe = 'I'; + char jobe; char equil = 'N'; char jobd = 'D'; Matrix a = args(0).matrix_value (); - Matrix b = args(1).matrix_value (); - Matrix c = args(2).matrix_value (); - Matrix d = args(3).matrix_value (); - double* e = 0; - int discrete = args(4).int_value (); - double tol = args(5).double_value (); + Matrix e = args(1).matrix_value (); + Matrix b = args(2).matrix_value (); + Matrix c = args(3).matrix_value (); + Matrix d = args(4).matrix_value (); + int discrete = args(5).int_value (); + int descriptor = args(6).int_value (); + double tol = args(7).double_value (); if (discrete == 0) dico = 'C'; else dico = 'D'; + + if (descriptor == 0) + jobe = 'I'; + else + jobe = 'G'; int n = a.rows (); // n: number of states int m = b.columns (); // m: number of inputs int p = c.rows (); // p: number of outputs - int lda = max (1, a.rows ()); - int ldb = max (1, b.rows ()); - int ldc = max (1, c.rows ()); - int ldd = max (1, d.rows ()); - int lde = 1; + int lda = max (1, n); + int lde = max (1, n); + int ldb = max (1, n); + int ldc = max (1, p); + int ldd = max (1, p); ColumnVector fpeak (2); ColumnVector gpeak (2); @@ -121,7 +127,7 @@ n, m, p, fpeak.fortran_vec (), a.fortran_vec (), lda, - e, lde, + e.fortran_vec (), lde, b.fortran_vec (), ldb, c.fortran_vec (), ldc, d.fortran_vec (), ldd, This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-09-25 13:05:07
|
Revision: 7765 http://octave.svn.sourceforge.net/octave/?rev=7765&view=rev Author: paramaniac Date: 2010-09-25 13:04:59 +0000 (Sat, 25 Sep 2010) Log Message: ----------- control: minimal realization of descriptor state-space models Modified Paths: -------------- trunk/octave-forge/main/control/inst/@ss/__minreal__.m trunk/octave-forge/main/control/inst/ltimodels.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/makefile_minreal.m Added Paths: ----------- trunk/octave-forge/main/control/src/TG01HX.f trunk/octave-forge/main/control/src/TG01JD.f trunk/octave-forge/main/control/src/sltg01jd.cc Modified: trunk/octave-forge/main/control/inst/@ss/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-09-24 18:29:37 UTC (rev 7764) +++ trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-09-25 13:04:59 UTC (rev 7765) @@ -17,27 +17,29 @@ ## -*- texinfo -*- ## Minimal realization of SS models. The physical meaning of states is lost. -## Uses SLICOT TB01PD by courtesy of NICONET e.V. <http://www.slicot.org> +## Uses SLICOT TB01PD and TG01JD by courtesy of NICONET e.V. +## <http://www.slicot.org> ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 -## Version: 0.2 +## Version: 0.3 function retsys = __minreal__ (sys, tol) - if (! isempty (sys.e)) - error ("ss: minreal: dss models not supported yet"); - endif - if (tol == "def") tol = 0; elseif (tol > 1) error ("ss: minreal: require tol <= 1"); endif - [a, b, c, nr] = sltb01pd (sys.a, sys.b, sys.c, tol); + if (isempty (sys.e)) + [a, b, c, nr] = sltb01pd (sys.a, sys.b, sys.c, tol); + retsys = ss (a, b, c, sys.d); + else + [a, e, b, c, nr] = sltg01jd (sys.a, sys.e, sys.b, sys.c, tol); + retsys = dss (a, b, c, sys.d, e); + endif - retsys = ss (a, b, c, sys.d); retsys.lti = sys.lti; # retain i/o names and tsam endfunction Modified: trunk/octave-forge/main/control/inst/ltimodels.m =================================================================== --- trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-24 18:29:37 UTC (rev 7764) +++ trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-25 13:04:59 UTC (rev 7765) @@ -295,6 +295,83 @@ %!assert (M, Me, 1e-4); +## dss: minreal (SLICOT TG01JD) +%!shared Ar, Br, Cr, Dr, Er, Ae, Be, Ce, De, Ee +%! A = [ -2 -3 0 0 0 0 0 0 0 +%! 1 0 0 0 0 0 0 0 0 +%! 0 0 -2 -3 0 0 0 0 0 +%! 0 0 1 0 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 1 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 +%! 0 0 0 0 0 0 0 0 1 ]; +%! +%! E = [ 1 0 0 0 0 0 0 0 0 +%! 0 1 0 0 0 0 0 0 0 +%! 0 0 1 0 0 0 0 0 0 +%! 0 0 0 1 0 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 ]; +%! +%! B = [ 1 0 +%! 0 0 +%! 0 1 +%! 0 0 +%! -1 0 +%! 0 0 +%! 0 -1 +%! 0 0 +%! 0 0 ]; +%! +%! C = [ 1 0 1 -3 0 1 0 2 0 +%! 0 1 1 3 0 1 0 0 1 ]; +%! +%! D = zeros (2, 2); +%! +%! sys = dss (A, B, C, D, E); +%! sysmin = minreal (sys, 0.0); +%! [Ar, Br, Cr, Dr, Er] = dssdata (sysmin); +%! +%! Ae = [ 1.0000 -0.0393 -0.0980 -0.1066 0.0781 -0.2330 0.0777 +%! 0.0000 1.0312 0.2717 0.2609 -0.1533 0.6758 -0.3553 +%! 0.0000 0.0000 1.3887 0.6699 -0.4281 1.6389 -0.7615 +%! 0.0000 0.0000 0.0000 -1.2147 0.2423 -0.9792 0.4788 +%! 0.0000 0.0000 0.0000 0.0000 -1.0545 0.5035 -0.2788 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.6355 -0.4323 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%! Ee = [ 0.4100 0.2590 0.5080 -0.3109 0.0705 0.1429 -0.1477 +%! -0.7629 -0.3464 0.0992 -0.3007 0.0619 0.2483 -0.0152 +%! 0.1120 -0.2124 -0.4184 -0.1288 0.0569 -0.4213 -0.6182 +%! 0.0000 0.1122 -0.0039 0.2771 -0.0758 0.0975 0.3923 +%! 0.0000 0.0000 0.3708 -0.4290 0.1006 0.1402 -0.2699 +%! 0.0000 0.0000 0.0000 0.0000 0.9458 -0.2211 0.2378 +%! 0.0000 0.0000 0.0000 0.5711 0.2648 0.5948 -0.5000 ]; +%! +%! Be = [ -0.5597 0.2363 +%! -0.4843 -0.0498 +%! -0.4727 -0.1491 +%! 0.1802 1.1574 +%! 0.5995 0.1556 +%! -0.1729 -0.3999 +%! 0.0000 0.2500 ]; +%! +%! Ce = [ 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 4.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 3.1524 -1.7500 ]; +%! +%! De = zeros (2, 2); +%! +%!assert (Ar, Ae, 1e-4); +%!assert (Br, Be, 1e-4); +%!assert (Cr, Ce, 1e-4); +%!assert (Dr, De, 1e-4); +%!assert (Er, Ee, 1e-4); + + ## ss: sminreal %!shared B, C %! Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-09-24 18:29:37 UTC (rev 7764) +++ trunk/octave-forge/main/control/src/Makefile 2010-09-25 13:04:59 UTC (rev 7765) @@ -1,7 +1,7 @@ all: slab08nd.oct slab13dd.oct slsb10hd.oct slsb10ed.oct slab13bd.oct \ slsb01bd.oct slsb10fd.oct slsb10dd.oct slsb03md.oct slsb04md.oct \ slsb04qd.oct slsg03ad.oct slsb02od.oct slab13ad.oct slab01od.oct \ - sltb01pd.oct slsb03od.oct slsg03bd.oct slag08bd.oct \ + sltb01pd.oct slsb03od.oct slsg03bd.oct slag08bd.oct sltg01jd.oct \ is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ is_real_square_matrix.oct @@ -144,6 +144,11 @@ AG08BD.f AG08BY.f TG01AD.f TB01XD.f MA02CD.f \ TG01FD.f MA02BD.f MB03OY.f +# minimal realization of descriptor state-space models +sltg01jd.oct: sltg01jd.cc + mkoctfile sltg01jd.cc \ + TG01JD.f TG01AD.f TB01XD.f MA02CD.f TG01HX.f + # helpers is_real_scalar.oct: is_real_scalar.cc mkoctfile is_real_scalar.cc Added: trunk/octave-forge/main/control/src/TG01HX.f =================================================================== --- trunk/octave-forge/main/control/src/TG01HX.f (rev 0) +++ trunk/octave-forge/main/control/src/TG01HX.f 2010-09-25 13:04:59 UTC (rev 7765) @@ -0,0 +1,694 @@ + SUBROUTINE TG01HX( COMPQ, COMPZ, L, N, M, P, N1, LBE, A, LDA, + $ E, LDE, B, LDB, C, LDC, Q, LDQ, Z, LDZ, NR, + $ NRBLCK, RTAU, TOL, IWORK, DWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C Given the descriptor system (A-lambda*E,B,C) with the system +C matrices A, E and B of the form +C +C ( A1 X1 ) ( E1 Y1 ) ( B1 ) +C A = ( ) , E = ( ) , B = ( ) , +C ( 0 X2 ) ( 0 Y2 ) ( 0 ) +C +C where +C - B is an L-by-M matrix, with B1 an N1-by-M submatrix +C - A is an L-by-N matrix, with A1 an N1-by-N1 submatrix +C - E is an L-by-N matrix, with E1 an N1-by-N1 submatrix +C with LBE nonzero sub-diagonals, +C this routine reduces the pair (A1-lambda*E1,B1) to the form +C +C Qc'*[A1-lambda*E1 B1]*diag(Zc,I) = +C +C ( Bc Ac-lambda*Ec * ) +C ( ) , +C ( 0 0 Anc-lambda*Enc ) +C +C where: +C 1) the pencil ( Bc Ac-lambda*Ec ) has full row rank NR for +C all finite lambda and is in a staircase form with +C _ _ _ _ +C ( A1,0 A1,1 ... A1,k-1 A1,k ) +C ( _ _ _ ) +C ( Bc Ac ) = ( 0 A2,1 ... A2,k-1 A2,k ) , (1) +C ( ... _ _ ) +C ( 0 0 ... Ak,k-1 Ak,k ) +C +C _ _ _ +C ( E1,1 ... E1,k-1 E1,k ) +C ( _ _ ) +C Ec = ( 0 ... E2,k-1 E2,k ) , (2) +C ( ... _ ) +C ( 0 ... 0 Ek,k ) +C _ +C where Ai,i-1 is an rtau(i)-by-rtau(i-1) full row rank +C _ +C matrix (with rtau(0) = M) and Ei,i is an rtau(i)-by-rtau(i) +C upper triangular matrix. +C +C 2) the pencil Anc-lambda*Enc is regular of order N1-NR with Enc +C upper triangular; this pencil contains the uncontrollable +C finite eigenvalues of the pencil (A1-lambda*E1). +C +C The transformations are applied to the whole matrices A, E, B +C and C. The left and/or right orthogonal transformations Qc and Zc +C performed to reduce the pencil S(lambda) can be optionally +C accumulated in the matrices Q and Z, respectivelly. +C +C The reduced order descriptor system (Ac-lambda*Ec,Bc,Cc) has no +C uncontrollable finite eigenvalues and has the same +C transfer-function matrix as the original system (A-lambda*E,B,C). +C +C ARGUMENTS +C +C Mode Parameters +C +C COMPQ CHARACTER*1 +C = 'N': do not compute Q; +C = 'I': Q is initialized to the unit matrix, and the +C orthogonal matrix Q is returned; +C = 'U': Q must contain an orthogonal matrix Q1 on entry, +C and the product Q1*Q is returned. +C +C COMPZ CHARACTER*1 +C = 'N': do not compute Z; +C = 'I': Z is initialized to the unit matrix, and the +C orthogonal matrix Z is returned; +C = 'U': Z must contain an orthogonal matrix Z1 on entry, +C and the product Z1*Z is returned. +C +C Input/Output Parameters +C +C L (input) INTEGER +C The number of descriptor state equations; also the number +C of rows of matrices A, E and B. L >= 0. +C +C N (input) INTEGER +C The dimension of the descriptor state vector; also the +C number of columns of matrices A, E and C. N >= 0. +C +C M (input) INTEGER +C The dimension of descriptor system input vector; also the +C number of columns of matrix B. M >= 0. +C +C P (input) INTEGER +C The dimension of descriptor system output; also the +C number of rows of matrix C. P >= 0. +C +C N1 (input) INTEGER +C The order of subsystem (A1-lambda*E1,B1,C1) to be reduced. +C MIN(L,N) >= N1 >= 0. +C +C LBE (input) INTEGER +C The number of nonzero sub-diagonals of submatrix E1. +C MAX(0,N1-1) >= LBE >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading L-by-N part of this array must +C contain the L-by-N state matrix A in the partitioned +C form +C ( A1 X1 ) +C A = ( ) , +C ( 0 X2 ) +C +C where A1 is N1-by-N1. +C On exit, the leading L-by-N part of this array contains +C the transformed state matrix, +C +C ( Ac * * ) +C Qc'*A*Zc = ( 0 Anc * ) , +C ( 0 0 * ) +C +C where Ac is NR-by-NR and Anc is (N1-NR)-by-(N1-NR). +C The matrix ( Bc Ac ) is in the controlability +C staircase form (1). +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,L). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading L-by-N part of this array must +C contain the L-by-N descriptor matrix E in the partitioned +C form +C ( E1 Y1 ) +C E = ( ) , +C ( 0 Y2 ) +C +C where E1 is N1-by-N1 matrix with LBE nonzero +C sub-diagonals. +C On exit, the leading L-by-N part of this array contains +C the transformed descriptor matrix +C +C ( Ec * * ) +C Qc'*E*Zc = ( 0 Enc * ) , +C ( 0 0 * ) +C +C where Ec is NR-by-NR and Enc is (N1-NR)-by-(N1-NR). +C Both Ec and Enc are upper triangular and Enc is +C nonsingular. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,L). +C +C B (input/output) DOUBLE PRECISION array, dimension (LDB,M) +C On entry, the leading L-by-M part of this array must +C contain the L-by-M input matrix B in the partitioned +C form +C ( B1 ) +C B = ( ) , +C ( 0 ) +C +C where B1 is N1-by-M. +C On exit, the leading L-by-M part of this array contains +C the transformed input matrix +C +C ( Bc ) +C Qc'*B = ( ) , +C ( 0 ) +C +C where Bc is NR-by-M. +C The matrix ( Bc Ac ) is in the controlability +C staircase form (1). +C +C LDB INTEGER +C The leading dimension of array B. LDB >= MAX(1,L). +C +C C (input/output) DOUBLE PRECISION array, dimension (LDC,N) +C On entry, the leading P-by-N part of this array must +C contain the state/output matrix C. +C On exit, the leading P-by-N part of this array contains +C the transformed matrix C*Zc. +C +C LDC INTEGER +C The leading dimension of array C. LDC >= MAX(1,P). +C +C Q (input/output) DOUBLE PRECISION array, dimension (LDQ,L) +C If COMPQ = 'N': Q is not referenced. +C If COMPQ = 'I': on entry, Q need not be set; +C on exit, the leading L-by-L part of this +C array contains the orthogonal matrix Q, +C where Q' is the product of transformations +C which are applied to A, E, and B on +C the left. +C If COMPQ = 'U': on entry, the leading L-by-L part of this +C array must contain an orthogonal matrix +C Qc; +C on exit, the leading L-by-L part of this +C array contains the orthogonal matrix +C Qc*Q. +C +C LDQ INTEGER +C The leading dimension of array Q. +C LDQ >= 1, if COMPQ = 'N'; +C LDQ >= MAX(1,L), if COMPQ = 'U' or 'I'. +C +C Z (input/output) DOUBLE PRECISION array, dimension (LDZ,N) +C If COMPZ = 'N': Z is not referenced. +C If COMPZ = 'I': on entry, Z need not be set; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix Z, +C which is the product of transformations +C applied to A, E, and C on the right. +C If COMPZ = 'U': on entry, the leading N-by-N part of this +C array must contain an orthogonal matrix +C Zc; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix +C Zc*Z. +C +C LDZ INTEGER +C The leading dimension of array Z. +C LDZ >= 1, if COMPZ = 'N'; +C LDZ >= MAX(1,N), if COMPZ = 'U' or 'I'. +C +C NR (output) INTEGER +C The order of the reduced matrices Ac and Ec, and the +C number of rows of the reduced matrix Bc; also the order of +C the controllable part of the pair (B, A-lambda*E). +C +C NRBLCK (output) INTEGER _ +C The number k, of full row rank blocks Ai,i in the +C staircase form of the pencil (Bc Ac-lambda*Ec) (see (1) +C and (2)). +C +C RTAU (output) INTEGER array, dimension (N1) +C RTAU(i), for i = 1, ..., NRBLCK, is the row dimension of +C _ +C the full row rank block Ai,i-1 in the staircase form (1). +C +C Tolerances +C +C TOL DOUBLE PRECISION +C The tolerance to be used in rank determinations when +C transforming (A-lambda*E, B). If the user sets TOL > 0, +C then the given value of TOL is used as a lower bound for +C reciprocal condition numbers in rank determinations; a +C (sub)matrix whose estimated condition number is less than +C 1/TOL is considered to be of full rank. If the user sets +C TOL <= 0, then an implicitly computed, default tolerance, +C defined by TOLDEF = L*N*EPS, is used instead, where +C EPS is the machine precision (see LAPACK Library routine +C DLAMCH). TOL < 1. +C +C Workspace +C +C IWORK INTEGER array, dimension (M) +C +C DWORK DOUBLE PRECISION array, dimension MAX(N,L,2*M) +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The subroutine is based on the reduction algorithm of [1]. +C +C REFERENCES +C +C [1] A. Varga +C Computation of Irreducible Generalized State-Space +C Realizations. +C Kybernetika, vol. 26, pp. 89-106, 1990. +C +C NUMERICAL ASPECTS +C +C The algorithm is numerically backward stable and requires +C 0( N*N1**2 ) floating point operations. +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C March 1999. Based on the RASP routine RPDS05. +C +C REVISIONS +C +C V. Sima, Research Institute for Informatics, Bucharest, July 1999, +C May 2003, Nov. 2003. +C A. Varga, German Aerospace Center, Oberpfaffenhofen, Nov. 2003. +C +C KEYWORDS +C +C Controllability, minimal realization, orthogonal canonical form, +C orthogonal transformation. +C +C ****************************************************************** +C +C .. Parameters .. + INTEGER IMAX, IMIN + PARAMETER ( IMAX = 1, IMIN = 2 ) + DOUBLE PRECISION ONE, P05, ZERO + PARAMETER ( ONE = 1.0D0, P05 = 0.05D0, ZERO = 0.0D0 ) +C .. Scalar Arguments .. + CHARACTER COMPQ, COMPZ + INTEGER INFO, L, LBE, LDA, LDB, LDC, LDE, LDQ, LDZ, M, + $ N, N1, NR, NRBLCK, P + DOUBLE PRECISION TOL +C .. Array Arguments .. + INTEGER IWORK( * ), RTAU( * ) + DOUBLE PRECISION A( LDA, * ), B( LDB, * ), C( LDC, * ), + $ DWORK( * ), E( LDE, * ), Q( LDQ, * ), + $ Z( LDZ, * ) +C .. Local Scalars .. + LOGICAL ILQ, ILZ, WITHC + INTEGER I, IC, ICOL, ICOMPQ, ICOMPZ, IROW, ISMAX, + $ ISMIN, J, K, MN, NF, NR1, RANK, TAUIM1 + DOUBLE PRECISION CO, C1, C2, RCOND, SMAX, SMAXPR, SMIN, SMINPR, + $ SVLMAX, S1, S2, SI, T, TT +C .. External Functions .. + LOGICAL LSAME + INTEGER IDAMAX + DOUBLE PRECISION DLAMCH, DLANGE, DLAPY2, DNRM2 + EXTERNAL DLAMCH, DLANGE, DLAPY2, DNRM2, IDAMAX, LSAME +C .. External Subroutines .. + EXTERNAL DLACPY, DLARF, DLARFG, DLARTG, DLASET, DROT, + $ DSWAP, XERBLA +C .. Intrinsic Functions .. + INTRINSIC ABS, DBLE, MAX, MIN, SQRT +C +C .. Executable Statements .. +C +C Decode COMPQ. +C + IF( LSAME( COMPQ, 'N' ) ) THEN + ILQ = .FALSE. + ICOMPQ = 1 + ELSE IF( LSAME( COMPQ, 'U' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 2 + ELSE IF( LSAME( COMPQ, 'I' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 3 + ELSE + ICOMPQ = 0 + END IF +C +C Decode COMPZ. +C + IF( LSAME( COMPZ, 'N' ) ) THEN + ILZ = .FALSE. + ICOMPZ = 1 + ELSE IF( LSAME( COMPZ, 'U' ) ) THEN + ILZ = .TRUE. + ICOMPZ = 2 + ELSE IF( LSAME( COMPZ, 'I' ) ) THEN + ILZ = .TRUE. + ICOMPZ = 3 + ELSE + ICOMPZ = 0 + END IF +C +C Test the input scalar parameters. +C + INFO = 0 + IF( ICOMPQ.LE.0 ) THEN + INFO = -1 + ELSE IF( ICOMPZ.LE.0 ) THEN + INFO = -2 + ELSE IF( L.LT.0 ) THEN + INFO = -3 + ELSE IF( N.LT.0 ) THEN + INFO = -4 + ELSE IF( M.LT.0 ) THEN + INFO = -5 + ELSE IF( P.LT.0 ) THEN + INFO = -6 + ELSE IF( N1.LT.0 .OR. N1.GT.MIN( L, N ) ) THEN + INFO = -7 + ELSE IF( LBE.LT.0 .OR. LBE.GT.MAX( 0, N1-1 ) ) THEN + INFO = -8 + ELSE IF( LDA.LT.MAX( 1, L ) ) THEN + INFO = -10 + ELSE IF( LDE.LT.MAX( 1, L ) ) THEN + INFO = -12 + ELSE IF( LDB.LT.MAX( 1, L ) ) THEN + INFO = -14 + ELSE IF( LDC.LT.MAX( 1, P ) ) THEN + INFO = -16 + ELSE IF( ( ILQ .AND. LDQ.LT.L ) .OR. LDQ.LT.1 ) THEN + INFO = -18 + ELSE IF( ( ILZ .AND. LDZ.LT.N ) .OR. LDZ.LT.1 ) THEN + INFO = -20 + ELSE IF( TOL.GE.ONE ) THEN + INFO = -24 + END IF + IF( INFO.NE.0 ) THEN + CALL XERBLA( 'TG01HX', -INFO ) + RETURN + END IF +C +C Initialize Q and Z if necessary. +C + IF( ICOMPQ.EQ.3 ) + $ CALL DLASET( 'Full', L, L, ZERO, ONE, Q, LDQ ) + IF( ICOMPZ.EQ.3 ) + $ CALL DLASET( 'Full', N, N, ZERO, ONE, Z, LDZ ) +C +C Initialize output variables. +C + NR = 0 + NRBLCK = 0 +C +C Quick return if possible. +C + IF( M.EQ.0 .OR. N1.EQ.0 ) THEN + RETURN + END IF +C + WITHC = P.GT.0 + SVLMAX = DLAPY2( DLANGE( 'F', L, M, B, LDB, DWORK ), + $ DLANGE( 'F', L, N, A, LDA, DWORK ) ) + RCOND = TOL + IF ( RCOND.LE.ZERO ) THEN +C +C Use the default tolerance in controllability determination. +C + RCOND = DBLE( L*N )*DLAMCH( 'EPSILON' ) + END IF +C + IF ( SVLMAX.LT.RCOND ) + $ SVLMAX = ONE +C +C Reduce E to upper triangular form if necessary. +C + IF( LBE.GT.0 ) THEN + DO 10 I = 1, N1-1 +C +C Generate elementary reflector H(i) to annihilate +C E(i+1:i+lbe,i). +C + K = MIN( LBE, N1-I ) + 1 + CALL DLARFG( K, E(I,I), E(I+1,I), 1, TT ) + T = E(I,I) + E(I,I) = ONE +C +C Apply H(i) to E(i:n1,i+1:n) from the left. +C + CALL DLARF( 'Left', K, N-I, E(I,I), 1, TT, + $ E(I,I+1), LDE, DWORK ) +C +C Apply H(i) to A(i:n1,1:n) from the left. +C + CALL DLARF( 'Left', K, N, E(I,I), 1, TT, + $ A(I,1), LDA, DWORK ) +C +C Apply H(i) to B(i:n1,1:m) from the left. +C + CALL DLARF( 'Left', K, M, E(I,I), 1, TT, + $ B(I,1), LDB, DWORK ) + IF( ILQ ) THEN +C +C Apply H(i) to Q(1:l,i:n1) from the right. +C + CALL DLARF( 'Right', L, K, E(I,I), 1, TT, + $ Q(1,I), LDQ, DWORK ) + END IF + E(I,I) = T + 10 CONTINUE + IF( N1.GT.1 ) + $ CALL DLASET( 'Lower', N1-1, N1-1, ZERO, ZERO, E(2,1), LDE ) + END IF +C + ISMIN = 1 + ISMAX = ISMIN + M + IC = -M + TAUIM1 = M + NF = N1 +C + 20 CONTINUE + NRBLCK = NRBLCK + 1 + RANK = 0 + IF( NF.GT.0 ) THEN +C +C IROW will point to the current pivot line in B, +C ICOL+1 will point to the first active columns of A. +C + ICOL = IC + TAUIM1 + IROW = NR + NR1 = NR + 1 + IF( NR.GT.0 ) + $ CALL DLACPY( 'Full', NF, TAUIM1, A(NR1,IC+1), LDA, + $ B(NR1,1), LDB ) +C +C Perform QR-decomposition with column pivoting on the current B +C while keeping E upper triangular. +C The current B is at first iteration B and for subsequent +C iterations the NF-by-TAUIM1 matrix delimited by rows +C NR + 1 to N1 and columns IC + 1 to IC + TAUIM1 of A. +C The rank of current B is computed in RANK. +C + IF( TAUIM1.GT.1 ) THEN +C +C Compute column norms. +C + DO 30 J = 1, TAUIM1 + DWORK(J) = DNRM2( NF, B(NR1,J), 1 ) + DWORK(M+J) = DWORK(J) + IWORK(J) = J + 30 CONTINUE + END IF +C + MN = MIN( NF, TAUIM1 ) +C + 40 CONTINUE + IF( RANK.LT.MN ) THEN + J = RANK + 1 + IROW = IROW + 1 +C +C Pivot if necessary. +C + IF( J.NE.TAUIM1 ) THEN + K = ( J - 1 ) + IDAMAX( TAUIM1-J+1, DWORK(J), 1 ) + IF( K.NE.J ) THEN + CALL DSWAP( NF, B(NR1,J), 1, B(NR1,K), 1 ) + I = IWORK(K) + IWORK(K) = IWORK(J) + IWORK(J) = I + DWORK(K) = DWORK(J) + DWORK(M+K) = DWORK(M+J) + END IF + END IF +C +C Zero elements below the current diagonal element of B. +C + DO 50 I = N1-1, IROW, -1 +C +C Rotate rows I and I+1 to zero B(I+1,J). +C + T = B(I,J) + CALL DLARTG( T, B(I+1,J), CO, SI, B(I,J) ) + B(I+1,J) = ZERO + CALL DROT( N-I+1, E(I,I), LDE, E(I+1,I), LDE, CO, SI ) + IF( J.LT.TAUIM1 ) + $ CALL DROT( TAUIM1-J, B(I,J+1), LDB, + $ B(I+1,J+1), LDB, CO, SI ) + CALL DROT( N-ICOL, A(I,ICOL+1), LDA, + $ A(I+1,ICOL+1), LDA, CO, SI ) + IF( ILQ ) CALL DROT( L, Q(1,I), 1, Q(1,I+1), 1, CO, SI ) +C +C Rotate columns I, I+1 to zero E(I+1,I). +C + T = E(I+1,I+1) + CALL DLARTG( T, E(I+1,I), CO, SI, E(I+1,I+1) ) + E(I+1,I) = ZERO + CALL DROT( I, E(1,I+1), 1, E(1,I), 1, CO, SI ) + CALL DROT( N1, A(1,I+1), 1, A(1,I), 1, CO, SI ) + IF( ILZ ) CALL DROT( N, Z(1,I+1), 1, Z(1,I), 1, CO, SI ) + IF( WITHC ) + $ CALL DROT( P, C(1,I+1), 1, C(1,I), 1, CO, SI ) + 50 CONTINUE +C + IF( RANK.EQ.0 ) THEN +C +C Initialize; exit if matrix is zero (RANK = 0). +C + SMAX = ABS( B(NR1,1) ) + IF ( SMAX.EQ.ZERO ) GO TO 80 + SMIN = SMAX + SMAXPR = SMAX + SMINPR = SMIN + C1 = ONE + C2 = ONE + ELSE +C +C One step of incremental condition estimation. +C + CALL DLAIC1( IMIN, RANK, DWORK(ISMIN), SMIN, + $ B(NR1,J), B(IROW,J), SMINPR, S1, C1 ) + CALL DLAIC1( IMAX, RANK, DWORK(ISMAX), SMAX, + $ B(NR1,J), B(IROW,J), SMAXPR, S2, C2 ) + END IF +C +C Check the rank; finish the loop if rank loss occurs. +C + IF( SVLMAX*RCOND.LE.SMAXPR ) THEN + IF( SVLMAX*RCOND.LE.SMINPR ) THEN + IF( SMAXPR*RCOND.LE.SMINPR ) THEN +C +C Finish the loop if last row. +C + IF( IROW.EQ.N1 ) THEN + RANK = RANK + 1 + GO TO 80 + END IF +C +C Update partial column norms. +C + DO 60 I = J + 1, TAUIM1 + IF( DWORK(I).NE.ZERO ) THEN + T = ONE - ( ABS( B(IROW,I) )/DWORK(I) )**2 + T = MAX( T, ZERO ) + TT = ONE + P05*T*( DWORK(I)/DWORK(M+I) )**2 + IF( TT.NE.ONE ) THEN + DWORK(I) = DWORK(I)*SQRT( T ) + ELSE + DWORK(I) = DNRM2( NF-J, B(IROW+1,I), 1 ) + DWORK(M+I) = DWORK(I) + END IF + END IF + 60 CONTINUE +C + DO 70 I = 1, RANK + DWORK(ISMIN+I-1) = S1*DWORK(ISMIN+I-1) + DWORK(ISMAX+I-1) = S2*DWORK(ISMAX+I-1) + 70 CONTINUE +C + DWORK(ISMIN+RANK) = C1 + DWORK(ISMAX+RANK) = C2 + SMIN = SMINPR + SMAX = SMAXPR + RANK = RANK + 1 + GO TO 40 + END IF + END IF + END IF + IF( NR.GT.0 ) THEN + CALL DLASET( 'Full', N1-IROW+1, TAUIM1-J+1, ZERO, ZERO, + $ B(IROW,J), LDB ) + END IF + GO TO 80 + END IF + END IF +C + 80 IF( RANK.GT.0 ) THEN + RTAU(NRBLCK) = RANK +C +C Back permute interchanged columns. +C + IF( TAUIM1.GT.1 ) THEN + DO 100 J = 1, TAUIM1 + IF( IWORK(J).GT.0 ) THEN + K = IWORK(J) + IWORK(J) = -K + 90 CONTINUE + IF( K.NE.J ) THEN + CALL DSWAP( RANK, B(NR1,J), 1, B(NR1,K), 1 ) + IWORK(K) = -IWORK(K) + K = -IWORK(K) + GO TO 90 + END IF + END IF + 100 CONTINUE + END IF + END IF + IF( NR.GT.0 ) + $ CALL DLACPY( 'Full', NF, TAUIM1, B(NR1,1), LDB, + $ A(NR1,IC+1), LDA ) + IF( RANK.GT.0 ) THEN + NR = NR + RANK + NF = NF - RANK + IC = IC + TAUIM1 + TAUIM1 = RANK + GO TO 20 + ELSE + NRBLCK = NRBLCK - 1 + END IF +C + IF( NRBLCK.GT.0 ) RANK = RTAU(1) + IF( RANK.LT.N1 ) + $ CALL DLASET( 'Full', N1-RANK, M, ZERO, ZERO, B(RANK+1,1), LDB ) +C + RETURN +C *** Last line of TG01HX *** + END Added: trunk/octave-forge/main/control/src/TG01JD.f =================================================================== --- trunk/octave-forge/main/control/src/TG01JD.f (rev 0) +++ trunk/octave-forge/main/control/src/TG01JD.f 2010-09-25 13:04:59 UTC (rev 7765) @@ -0,0 +1,613 @@ + SUBROUTINE TG01JD( JOB, SYSTYP, EQUIL, N, M, P, A, LDA, E, LDE, + $ B, LDB, C, LDC, NR, INFRED, TOL, IWORK, DWORK, + $ LDWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To find a reduced (controllable, observable, or irreducible) +C descriptor representation (Ar-lambda*Er,Br,Cr) for an original +C descriptor representation (A-lambda*E,B,C). +C The pencil Ar-lambda*Er is in an upper block Hessenberg form, with +C either Ar or Er upper triangular. +C +C ARGUMENTS +C +C Mode Parameters +C +C JOB CHARACTER*1 +C Indicates whether the user wishes to remove the +C uncontrollable and/or unobservable parts as follows: +C = 'I': Remove both the uncontrollable and unobservable +C parts to get an irreducible descriptor +C representation; +C = 'C': Remove the uncontrollable part only to get a +C controllable descriptor representation; +C = 'O': Remove the unobservable part only to get an +C observable descriptor representation. +C +C SYSTYP CHARACTER*1 +C Indicates the type of descriptor system algorithm +C to be applied according to the assumed +C transfer-function matrix as follows: +C = 'R': Rational transfer-function matrix; +C = 'S': Proper (standard) transfer-function matrix; +C = 'P': Polynomial transfer-function matrix. +C +C EQUIL CHARACTER*1 +C Specifies whether the user wishes to preliminarily scale +C the system (A-lambda*E,B,C) as follows: +C = 'S': Perform scaling; +C = 'N': Do not perform scaling. +C +C Input/Output Parameters +C +C N (input) INTEGER +C The dimension of the descriptor state vector; also the +C order of square matrices A and E, the number of rows of +C matrix B, and the number of columns of matrix C. N >= 0. +C +C M (input) INTEGER +C The dimension of descriptor system input vector; also the +C number of columns of matrix B. M >= 0. +C +C P (input) INTEGER +C The dimension of descriptor system output vector; also the +C number of rows of matrix C. P >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading N-by-N part of this array must +C contain the original state matrix A. +C On exit, the leading NR-by-NR part of this array contains +C the reduced order state matrix Ar of an irreducible, +C controllable, or observable realization for the original +C system, depending on the value of JOB, JOB = 'I', +C JOB = 'C', or JOB = 'O', respectively. +C The matrix Ar is upper triangular if SYSTYP = 'R' or 'P'. +C If SYSTYP = 'S' and JOB = 'C', the matrix [Br Ar] +C is in a controllable staircase form (see TG01HD). +C If SYSTYP = 'S' and JOB = 'I' or 'O', the matrix ( Ar ) +C ( Cr ) +C is in an observable staircase form (see TG01HD). +C The block structure of staircase forms is contained +C in the leading INFRED(7) elements of IWORK. +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,N). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading N-by-N part of this array must +C contain the original descriptor matrix E. +C On exit, the leading NR-by-NR part of this array contains +C the reduced order descriptor matrix Er of an irreducible, +C controllable, or observable realization for the original +C system, depending on the value of JOB, JOB = 'I', +C JOB = 'C', or JOB = 'O', respectively. +C The resulting Er has INFRED(6) nonzero sub-diagonals. +C If at least for one k = 1,...,4, INFRED(k) >= 0, then the +C resulting Er is structured being either upper triangular +C or block Hessenberg, in accordance to the last +C performed order reduction phase (see METHOD). +C The block structure of staircase forms is contained +C in the leading INFRED(7) elements of IWORK. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,N). +C +C B (input/output) DOUBLE PRECISION array, dimension (LDB,M), +C if JOB = 'C', or (LDB,MAX(M,P)), otherwise. +C On entry, the leading N-by-M part of this array must +C contain the original input matrix B; if JOB = 'I', +C or JOB = 'O', the remainder of the leading N-by-MAX(M,P) +C part is used as internal workspace. +C On exit, the leading NR-by-M part of this array contains +C the reduced input matrix Br of an irreducible, +C controllable, or observable realization for the original +C system, depending on the value of JOB, JOB = 'I', +C JOB = 'C', or JOB = 'O', respectively. +C If JOB = 'C', only the first IWORK(1) rows of B are +C nonzero. +C +C LDB INTEGER +C The leading dimension of array B. LDB >= MAX(1,N). +C +C C (input/output) DOUBLE PRECISION array, dimension (LDC,N) +C On entry, the leading P-by-N part of this array must +C contain the original output matrix C; if JOB = 'I', +C or JOB = 'O', the remainder of the leading MAX(M,P)-by-N +C part is used as internal workspace. +C On exit, the leading P-by-NR part of this array contains +C the transformed state/output matrix Cr of an irreducible, +C controllable, or observable realization for the original +C system, depending on the value of JOB, JOB = 'I', +C JOB = 'C', or JOB = 'O', respectively. +C If JOB = 'I', or JOB = 'O', only the last IWORK(1) columns +C (in the first NR columns) of C are nonzero. +C +C LDC INTEGER +C The leading dimension of array C. +C LDC >= MAX(1,M,P) if N > 0. +C LDC >= 1 if N = 0. +C +C NR (output) INTEGER +C The order of the reduced descriptor representation +C (Ar-lambda*Er,Br,Cr) of an irreducible, controllable, +C or observable realization for the original system, +C depending on JOB = 'I', JOB = 'C', or JOB = 'O', +C respectively. +C +C INFRED (output) INTEGER array, dimension 7 +C This array contains information on performed reduction +C and on structure of resulting system matrices as follows: +C INFRED(k) >= 0 (k = 1, 2, 3, or 4) if Phase k of reduction +C (see METHOD) has been performed. In this +C case, INFRED(k) is the achieved order +C reduction in Phase k. +C INFRED(k) < 0 (k = 1, 2, 3, or 4) if Phase k was not +C performed. +C INFRED(5) - the number of nonzero sub-diagonals of A. +C INFRED(6) - the number of nonzero sub-diagonals of E. +C INFRED(7) - the number of blocks in the resulting +C staircase form at last performed reduction +C phase. The block dimensions are contained +C in the first INFRED(7) elements of IWORK. +C +C Tolerances +C +C TOL DOUBLE PRECISION +C The tolerance to be used in rank determinations when +C transforming (A-lambda*E,B,C). If the user sets TOL > 0, +C then the given value of TOL is used as a lower bound for +C reciprocal condition numbers in rank determinations; a +C (sub)matrix whose estimated condition number is less than +C 1/TOL is considered to be of full rank. If the user sets +C TOL <= 0, then an implicitly computed, default tolerance, +C defined by TOLDEF = N*N*EPS, is used instead, where +C EPS is the machine precision (see LAPACK Library routine +C DLAMCH). TOL < 1. +C +C Workspace +C +C IWORK INTEGER array, dimension N+MAX(M,P) +C On exit, if INFO = 0, the leading INFRED(7) elements of +C IWORK contain the orders of the diagonal blocks of +C Ar-lambda*Er. +C +C DWORK DOUBLE PRECISION array, dimension LDWORK +C +C LDWORK INTEGER +C The length of the array DWORK. +C LDWORK >= MAX(8*N,2*M,2*P), if EQUIL = 'S'; +C LDWORK >= MAX(N,2*M,2*P), if EQUIL = 'N'. +C If LDWORK >= MAX(2*N*N+N*M+N*P)+MAX(N,2*M,2*P) then more +C accurate results are to be expected by performing only +C those reductions phases (see METHOD), where effective +C order reduction occurs. This is achieved by saving the +C system matrices before each phase and restoring them if no +C order reduction took place. +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The subroutine is based on the reduction algorithms of [1]. +C The order reduction is performed in 4 phases: +C Phase 1: Eliminate all finite uncontrolable eigenvalues. +C The resulting matrix ( Br Ar ) is in a controllable +C staircase form (see SLICOT Library routine TG01HD), and +C Er is upper triangular. +C This phase is performed if JOB = 'I' or 'C' and +C SYSTYP = 'R' or 'S'. +C Phase 2: Eliminate all infinite and finite nonzero uncontrollable +C eigenvalues. The resulting matrix ( Br Er ) is in a +C controllable staircase form (see TG01HD), and Ar is +C upper triangular. +C This phase is performed if JOB = 'I' or 'C' and +C SYSTYP = 'R' or 'P'. +C Phase 3: Eliminate all finite unobservable eigenvalues. +C The resulting matrix ( Ar ) is in an observable +C ( Cr ) +C staircase form (see SLICOT Library routine TG01ID), and +C Er is upper triangular. +C This phase is performed if JOB = 'I' or 'O' and +C SYSTYP = 'R' or 'S'. +C Phase 4: Eliminate all infinite and finite nonzero unobservable +C eigenvalues. The resulting matrix ( Er ) is in an +C ( Cr ) +C observable staircase form (see TG01ID), and Ar is +C upper triangular. +C This phase is performed if JOB = 'I' or 'O' and +C SYSTYP = 'R' or 'P'. +C +C REFERENCES +C +C [1] A. Varga +C Computation of Irreducible Generalized State-Space +C Realizations. +C Kybernetika, vol. 26, pp. 89-106, 1990. +C +C NUMERICAL ASPECTS +C +C The algorithm is numerically backward stable and requires +C 0( N**3 ) floating point operations. +C +C FURTHER COMMENTS +C +C If the pencil (A-lambda*E) has no zero eigenvalues, then an +C irreducible realization can be computed skipping Phases 1 and 3 +C by using the setting: JOB = 'I' and SYSTYP = 'P'. +C +C CONTRIBUTOR +C +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C April 1999. Based on the RASP routine RPDSIR. +C +C REVISIONS +C +C July 1999, V. Sima, Research Institute for Informatics, Bucharest. +C May 2003, A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C May 2003, March 2004, V. Sima. +C +C KEYWORDS +C +C Controllability, irreducible realization, observability, +C orthogonal canonical form, orthogonal transformation. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ONE, ZERO + PARAMETER ( ONE = 1.0D0, ZERO = 0.0D0 ) +C .. Scalar Arguments .. + CHARACTER EQUIL, JOB, SYSTYP + INTEGER INFO, LDA, LDB, LDC, LDE, LDWORK, M, N, NR, P + DOUBLE PRECISION TOL +C .. Array Arguments .. + INTEGER INFRED(*), IWORK(*) + DOUBLE PRECISION A(LDA,*), B(LDB,*), C(LDC,*), DWORK(*), E(LDE,*) +C .. Local Scalars .. + CHARACTER JOBQ, JOBZ + LOGICAL FINCON, FINOBS, INFCON, INFOBS, LEQUIL, LJOBC, + $ LJOBIR, LJOBO, LSPACE, LSYSP, LSYSR, LSYSS + INTEGER KWA, KWB, KWC, KWE, LBA, LBE, LDM, LDP, LDQ, + $ LDZ, M1, MAXMP, N1, NBLCK, NC, P1 +C .. Local Arrays .. + DOUBLE PRECISION DUM(1) +C .. External Functions .. + LOGICAL LSAME + EXTERNAL LSAME +C .. External Subroutines .. + EXTERNAL DLACPY, MA02CD, TB01XD, TG01AD, TG01HX, XERBLA +C .. Intrinsic Functions .. + INTRINSIC MAX +C .. Executable Statements .. +C + INFO = 0 + MAXMP = MAX( M, P ) + N1 = MAX( 1, N ) +C +C Decode JOB. +C + LJOBIR = LSAME( JOB, 'I' ) + LJOBC = LJOBIR .OR. LSAME( JOB, 'C' ) + LJOBO = LJOBIR .OR. LSAME( JOB, 'O' ) +C +C Decode SYSTYP. +C + LSYSR = LSAME( SYSTYP, 'R' ) + LSYSS = LSYSR .OR. LSAME( SYSTYP, 'S' ) + LSYSP = LSYSR .OR. LSAME( SYSTYP, 'P' ) +C + LEQUIL = LSAME( EQUIL, 'S' ) +C +C Test the input scalar arguments. +C + IF( .NOT.LJOBC .AND. .NOT.LJOBO ) THEN + INFO = -1 + ELSE IF( .NOT.LSYSS .AND. .NOT.LSYSP ) THEN + INFO = -2 + ELSE IF( .NOT.LEQUIL .AND. .NOT.LSAME( EQUIL, 'N' ) ) THEN + INFO = -3 + ELSE IF( N.LT.0 ) THEN + INFO = -4 + ELSE IF( M.LT.0 ) THEN + INFO = -5 + ELSE IF( P.LT.0 ) THEN + INFO = -6 + ELSE IF( LDA.LT.N1 ) THEN + INFO = -8 + ELSE IF( LDE.LT.N1 ) THEN + INFO = -10 + ELSE IF( LDB.LT.N1 ) THEN + INFO = -12 + ELSE IF( LDC.LT.1 .OR. ( N.GT.0 .AND. LDC.LT.MAXMP ) ) THEN + INFO = -14 + ELSE IF( TOL.GE.ONE ) THEN + INFO = -17 + ELSE IF( ( .NOT.LEQUIL .AND. LDWORK.LT.MAX( N, 2*MAXMP ) ) .OR. + $ ( LEQUIL .AND. LDWORK.LT.MAX( 8*N, 2*MAXMP ) ) ) THEN + INFO = -20 + END IF +C + IF ( INFO.NE.0 ) THEN +C +C Error return. +C + CALL XERBLA( 'TG01JD', -INFO ) + RETURN + END IF +C +C Quick return if possible. +C + INFRED(1) = -1 + INFRED(2) = -1 + INFRED(3) = -1 + INFRED(4) = -1 + INFRED(5) = 0 + INFRED(6) = 0 + INFRED(7) = 0 +C + IF( MAX( N, MAXMP ).EQ.0 ) THEN + NR = 0 + RETURN + END IF +C + M1 = MAX( 1, M ) + P1 = MAX( 1, P ) + LDM = MAX( LDC, M ) + LDP = MAX( LDC, P ) +C +C Set controllability/observability determination options. +C + FINCON = LJOBC .AND. LSYSS + INFCON = LJOBC .AND. LSYSP + FINOBS = LJOBO .AND. LSYSS + INFOBS = LJOBO .AND. LSYSP +C +C Set large workspace option and determine offsets. +C + LSPACE = LDWORK.GE.N*( 2*N + M + P ) + MAX( N, 2*MAXMP ) + KWA = MAX( N, 2*MAXMP ) + 1 + KWE = KWA + N*N + KWB = KWE + N*N + KWC = KWB + N*M +C +C If required, scale the system (A-lambda*E,B,C). +C Workspace: need 8*N. +C + IF( LEQUIL ) THEN + CALL TG01AD( 'All', N, N, M, P, ZERO, A, LDA, E, LDE, B, LDB, + $ C, LDP, DWORK(1), DWORK(N+1), DWORK(2*N+1), INFO ) + END IF +C + JOBQ = 'N' + JOBZ = 'N' + LDQ = 1 + LDZ = 1 + LBA = MAX( 0, N-1 ) + LBE = LBA + NC = N + NR = N +C + IF( FINCON ) THEN +C +C Phase 1: Eliminate all finite uncontrolable eigenvalues. +C + IF( LSPACE) THEN +C +C Save system matrices. +C + CALL DLACPY( 'Full', NC, NC, A, LDA, DWORK(KWA), N1 ) + CALL DLACPY( 'Full', NC, NC, E, LDE, DWORK(KWE), N1 ) + CALL DLACPY( 'Full', NC, M, B, LDB, DWORK(KWB), N1 ) + CALL DLACPY( 'Full', P, NC, C, LDC, DWORK(KWC), P1 ) + END IF +C +C Perform finite controllability form reduction. +C Workspace: need MAX(N,2*M). +C + CALL TG01HX( JOBQ, JOBZ, NC, NC, M, P, NC, LBE, A, LDA, + $ E, LDE, B, LDB, C, LDP, DUM, LDQ, DUM, LDZ, NR, + $ NBLCK, IWORK, TOL, IWORK(N+1), DWORK, INFO ) + IF( NR.LT.NC .OR. .NOT.LSPACE ) THEN + IF( NBLCK.GT.1 ) THEN + LBA = IWORK(1) + IWORK(2) - 1 + ELSE IF( NBLCK.EQ.1 ) THEN + LBA = IWORK(1) - 1 + ELSE + LBA = 0 + END IF + LBE = 0 + INFRED(1) = NC - NR + INFRED(7) = NBLCK + NC = NR + ELSE +C +C Restore system matrices. +C + CALL DLACPY( 'Full', NC, NC, DWORK(KWA), N1, A, LDA ) + CALL DLACPY( 'Full', NC, NC, DWORK(KWE), N1, E, LDE ) + CALL DLACPY( 'Full', NC, M, DWORK(KWB), N1, B, LDB ) + CALL DLACPY( 'Full', P, NC, DWORK(KWC), P1, C, LDC ) + END IF + END IF +C + IF( INFCON ) THEN +C +C Phase 2: Eliminate all infinite and all finite nonzero +C uncontrolable eigenvalues. +C + IF( LSPACE ) THEN +C +C Save system matrices. +C + CALL DLACPY( 'Full', NC, NC, A, LDA, DWORK(KWA), N1 ) + CALL DLACPY( 'Full', NC, NC, E, LDE, DWORK(KWE), N1 ) + CALL DLACPY( 'Full', NC, M, B, LDB, DWORK(KWB), N1 ) + CALL DLACPY( 'Full', P, NC, C, LDC, DWORK(KWC), P1 ) + END IF +C +C Perform infinite controllability form reduction. +C Workspace: need MAX(N,2*M). +C + CALL TG01HX( JOBQ, JOBZ, NC, NC, M, P, NC, LBA, E, LDE, + $ A, LDA, B, LDB, C, LDP, DUM, LDQ, DUM, LDZ, NR, + $ NBLCK, IWORK, TOL, IWORK(N+1), DWORK, INFO ) + IF( NR.LT.NC .OR. .NOT.LSPACE ) THEN + IF( NBLCK.GT.1 ) THEN + LBE = IWORK(1) + IWORK(2) - 1 + ELSE IF( NBLCK.EQ.1 ) THEN + LBE = IWORK(1) - 1 + ELSE + LBE = 0 + END IF + LBA = 0 + INFRED(2) = NC - NR + INFRED(7) = NBLCK + NC = NR + ELSE +C +C Restore system matrices. +C + CALL DLACPY( 'Full', NC, NC, DWORK(KWA), N1, A, LDA ) + CALL DLACPY( 'Full', NC, NC, DWORK(KWE), N1, E, LDE ) + CALL DLACPY( 'Full', NC, M, DWORK(KWB), N1, B, LDB ) + CALL DLACPY( 'Full', P, NC, DWORK(KWC), P1, C, LDC ) + END IF + END IF +C + IF( FINOBS .OR. INFOBS) THEN +C +C Compute the pertransposed dual system exploiting matrix shapes. +C + CALL TB01XD( 'Z', NC, M, P, LBA, MAX( 0, NC-1 ), A, LDA, + $ B, LDB, C, LDC, DUM, 1, INFO ) + CALL MA02CD( NC, LBE, MAX( 0, NC-1 ), E, LDE ) + END IF +C + IF( FINOBS ) THEN +C +C Phase 3: Eliminate all finite unobservable eigenvalues. +C + IF( LSPACE ) THEN +C +C Save system matrices. +C + CALL DLACPY( 'Full', NC, NC, A, LDA, DWORK(KWA), N1 ) + CALL DLACPY( 'Full', NC, NC, E, LDE, DWORK(KWE), N1 ) + CALL DLACPY( 'Full', NC, P, B, LDB, DWORK(KWC), N1 ) + CALL DLACPY( 'Full', M, NC, C, LDC, DWORK(KWB), M1 ) + END IF +C +C Perform finite observability form reduction. +C Workspace: need MAX(N,2*P). +C + CALL TG01HX( JOBZ, JOBQ, NC, NC, P, M, NC, LBE, A, LDA, + $ E, LDE, B, LDB, C, LDM, DUM, LDZ, DUM, LDQ, NR, + $ NBLCK, IWORK, TOL, IWORK(N+1), DWORK, INFO ) + IF( NR.LT.NC .OR. .NOT.LSPACE ) THEN + IF( NBLCK.GT.1 ) THEN + LBA = IWORK(1) + IWORK(2) - 1 + ELSE IF( NBLCK.EQ.1 ) THEN + LBA = IWORK(1) - 1 + ELSE + LBA = 0 + END IF + LBE = 0 + INFRED(3) = NC - NR + INFRED(7) = NBLCK + NC = NR + ELSE +C +C Restore system matrices. +C + CALL DLACPY( 'Full', NC, NC, DWORK(KWA), N1, A, LDA ) + CALL DLACPY( 'Full', NC, NC, DWORK(KWE), N1, E, LDE ) + CALL DLACPY( 'Full', NC, P, DWORK(KWC), N1, B, LDB ) + CALL DLACPY( 'Full', M, NC, DWORK(KWB), M1, C, LDC ) + END IF + END IF +C + IF( INFOBS ) THEN +C +C Phase 4: Eliminate all infinite and all finite nonzero +C unobservable eigenvalues. +C + IF( LSPACE) THEN +C +C Save system matrices. +C + CALL DLACPY( 'Full', NC, NC, A, LDA, DWORK(KWA), N1 ) + CALL DLACPY( 'Full', NC, NC, E, LDE, DWORK(KWE), N1 ) + CALL DLACPY( 'Full', NC, P, B, LDB, DWORK(KWC), N1 ) + CALL DLACPY( 'Full', M, NC, C, LDC, DWORK(KWB), M1 ) + END IF +C +C Perform infinite observability form reduction. +C Workspace: need MAX(N,2*P). +C + CALL TG01HX( JOBZ, JOBQ, NC, NC, P, M, NC, LBA, E, LDE, + $ A, LDA, B, LDB, C, LDM, DUM, LDZ, DUM, LDQ, NR, + $ NBLCK, IWORK, TOL, IWORK(N+1), DWORK, INFO ) + IF( NR.LT.NC .OR. .NOT.LSPACE ) THEN + IF( NBLCK.GT.1 ) THEN + LBE = IWORK(1) + IWORK(2) - 1 + ELSE IF( NBLCK.EQ.1 ) THEN + LBE = IWORK(1) - 1 + ELSE + LBE = 0 + END IF + LBA = 0 + INFRED(4) = NC - NR + INFRED(7) = NBLCK + NC = NR + ELSE +C +C Restore system matrices. +C + CALL DLACPY( 'Full', NC, NC, DWORK(KWA), N1, A, LDA ) + CALL DLACPY( 'Full', NC, NC, DWORK(KWE), N1, E, LDE ) + CALL DLACPY( 'Full', NC, P, DWORK(KWC), N1, B, LDB ) + CALL DLACPY( 'Full', M, NC, DWORK(KWB), M1, C, LDC ) + END IF + END IF +C + IF( FINOBS .OR. INFOBS ) THEN +C +C Compute the pertransposed dual system exploiting matrix shapes. +C + CALL TB01XD( 'Z', NC, P, M, LBA, MAX( 0, NC-1 ), A, LDA, + $ B, LDB, C, LDC, DUM, 1, INFO ) + CALL MA02CD( NC, LBE, MAX( 0, NC-1 ), E, LDE ) + END IF +C +C Set structural information on A and E. +C + INFRED(5) = LBA + INFRED(6) = LBE +C + RETURN +C *** Last line of TG01JD *** + END Modified: trunk/octave-forge/main/control/src/makefile_minreal.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_minreal.m 2010-09-24 18:29:37 UTC (rev 7764) +++ trunk/octave-forge/main/control/src/makefile_minreal.m 2010-09-25 13:04:59 UTC (rev 7765) @@ -15,4 +15,8 @@ TB01PD.f TB01XD.f TB01ID.f AB07MD.f TB01UD.f \ MB03OY.f MB01PD.f MB01QD.f +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + sltg01jd.cc \ + TG01JD.f TG01AD.f TB01XD.f MA02CD.f TG01HX.f + cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/src/sltg01jd.cc =================================================================== --- trunk/octave-forge/main/control/src/sltg01jd.cc (rev 0) +++ trunk/octave-forge/main/control/src/sltg01jd.cc 2010-09-25 13:04:59 UTC (rev 7765) @@ -0,0 +1,161 @@ +/* + +Copyright (C) 2010 Lukas F. Reichlin + +This file is part of LTI Syncope. + +LTI Syncope is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +LTI Syncope is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see <http://www.gnu.org/licenses/>. + +Minimal realization of descriptor state-space models. +Uses SLICOT TG01JD by courtesy of NICONET e.V. +<http://www.slicot.org> + +Author: Lukas Reichlin <luk...@gm...> +Created: September 2010 +Version: 0.1 + +*/ + +#include <octave/oct.h> +#include <f77-fcn.h> +#include "common.cc" + +extern "C" +{ + int F77_FUNC (tg01jd, TG01JD) + (char& JOB, char& SYSTYP, char& EQUIL, + int& N, int& M, int& P, + double* A, int& LDA, + double* E, int& LDE, + double* B, int& LDB, + double* C, int& LDC, + int& NR, + int* INFRED, + double& TOL, + int* IWORK, + double* DWORK, int& LDWORK, + int& INFO); +} + +DEFUN_DLD (sltg01jd, args, nargout, + "-*- texinfo -*-\n\ +Slicot TG01JD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") +{ + int nargin = args.length (); + octave_value_list retval; + + if (nargin != 5) + { + print_usage (); + } + else + { + // arguments in + char job = 'I'; + char systyp = 'R'; + char equil = 'N'; + + Matrix a = args(0).matrix_value (); + Matrix e = args(1).matrix_value (); + Matrix b = args(2).matrix_value (); + Matrix c = args(3).matrix_value (); + double tol = args(4).double_value (); + + int n = a.rows (); // n: number of states + int m = b.columns (); // m: number of inputs + int p = c.rows (); // p: number of outputs + + int lda = max (1, n); + int lde = max (1, n); + int ldb = max (1, n); + int ldc; + + if (n == 0) + ldc = 1; + else + ldc = max (1, m, p); + + b.resize (ldb, max (m, p)); + + // arguments out + int nr; + int infred[7]; + + // workspace + int liwork = n + max (m, p); + int ldwork = max (n, 2*m, 2*p); + // int ldwork = n * (2*n + m + p) + max (n, 2*m, 2*p); + + // FIXME: larger ldwork should give better results, + // but it breaks the test that Slicot provides. + + /* + LDWORK INTEGER + The length of the array DWORK. + LDWORK >= MAX(8*N,2*M,2*P), if EQUIL = 'S'; + LDWORK >= MAX(N,2*M,2*P), if EQUIL = 'N'. + If LDWORK >= MAX(2*N*N+N*M+N*P)+MAX(N,2*M,2*P) then more + accurate results are to be expected by performing only + those reductions phases (see METHOD), where effective + order reduction occurs. This is achieved by saving the + system matrices before each phase and restoring t... [truncated message content] |
From: <par...@us...> - 2010-09-25 14:35:33
|
Revision: 7766 http://octave.svn.sourceforge.net/octave/?rev=7766&view=rev Author: paramaniac Date: 2010-09-25 14:35:25 +0000 (Sat, 25 Sep 2010) Log Message: ----------- control: support for descriptor models Modified Paths: -------------- trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/isdetectable.m trunk/octave-forge/main/control/inst/isstabilizable.m trunk/octave-forge/main/control/inst/ltimodels.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/makefile_staircase.m Added Paths: ----------- trunk/octave-forge/main/control/src/TG01HD.f trunk/octave-forge/main/control/src/TG01ID.f trunk/octave-forge/main/control/src/sltg01hd.cc trunk/octave-forge/main/control/src/sltg01id.cc Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/inst/care.m 2010-09-25 14:35:25 UTC (rev 7766) @@ -99,7 +99,7 @@ endif ## check stabilizability - if (! isstabilizable (a, b, [], 0)) + if (! isstabilizable (a, b, [], [], 0)) error ("care: (a, b) not stabilizable"); endif Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/inst/dare.m 2010-09-25 14:35:25 UTC (rev 7766) @@ -99,7 +99,7 @@ endif ## check stabilizability - if (! isstabilizable (a, b, [], 1)) + if (! isstabilizable (a, b, [], [], 1)) error ("dare: (a, b) not stabilizable"); endif Modified: trunk/octave-forge/main/control/inst/isdetectable.m =================================================================== --- trunk/octave-forge/main/control/inst/isdetectable.m 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/inst/isdetectable.m 2010-09-25 14:35:25 UTC (rev 7766) @@ -19,11 +19,15 @@ ## @deftypefn {Function File} {@var{bool} =} isdetectable (@var{sys}) ## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{sys}, @var{tol}) ## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}) -## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{tol}) -## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{[]}, @var{dflg}) -## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{tol}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{[]}, @var{tol}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}, @var{tol}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{[]}, @var{[]}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}, @var{[]}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{[]}, @var{tol}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}, @var{tol}, @var{dflg}) ## Logical test for system detectability. All unstable modes must be observable or -## all unobservable states must be stable. Uses SLICOT AB01OD by courtesy of NICONET e.V. +## all unobservable states must be stable. Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. ## <http://www.slicot.org> ## ## @strong{Inputs} @@ -34,6 +38,8 @@ ## State transition matrix. ## @item c ## Measurement matrix. +## @item e +## Descriptor matrix. ## @item tol ## Optional tolerance for stability. Default value is 0. ## @item dflg = 0 @@ -58,7 +64,7 @@ ## Created: October 2009 ## Version: 0.3 -function bool = isdetectable (a, c = [], tol = [], dflg = 0) +function bool = isdetectable (a, c = [], e = [], tol = [], dflg = 0) if (nargin == 0) print_usage (); @@ -67,10 +73,10 @@ print_usage (); endif bool = isstabilizable (a.', c); # transpose is overloaded - elseif (nargin < 2 || nargin > 4) + elseif (nargin < 2 || nargin > 5) print_usage (); else # isdetectable (a, c, ...) - bool = isstabilizable (a.', c.', tol, dflg); # arguments checked inside + bool = isstabilizable (a.', c.', e.', tol, dflg); # arguments checked inside endif endfunction Modified: trunk/octave-forge/main/control/inst/isstabilizable.m =================================================================== --- trunk/octave-forge/main/control/inst/isstabilizable.m 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/inst/isstabilizable.m 2010-09-25 14:35:25 UTC (rev 7766) @@ -19,11 +19,15 @@ ## @deftypefn {Function File} {@var{bool} =} isstabilizable (@var{sys}) ## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{sys}, @var{tol}) ## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}) -## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{tol}) -## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{[]}, @var{dflg}) -## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{tol}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{[]}, @var{tol}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}, @var{tol}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{[]}, @var{[]}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}, @var{[]}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{[]}, @var{tol}, @var{dflg}) +## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}, @var{tol}, @var{dflg}) ## Logical check for system stabilizability. All unstable modes must be controllable or -## all uncontrollable states must be stable. Uses SLICOT AB01OD by courtesy of NICONET e.V. +## all uncontrollable states must be stable. Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. ## <http://www.slicot.org> ## ## @strong{Inputs} @@ -34,6 +38,8 @@ ## State transition matrix. ## @item b ## Input matrix. +## @item e +## Descriptor matrix. ## @item tol ## Optional tolerance for stability. Default value is 0. ## @item dflg = 0 @@ -53,10 +59,10 @@ ## @example ## @group ## Method -## - Calculate staircase form (SLICOT AB01OD) -## - Extract unobservable part of state transition matrix -## - Calculate eigenvalues of unobservable part -## - Check whether +## * Calculate staircase form (SLICOT AB01OD) +## * Extract unobservable part of state transition matrix +## * Calculate eigenvalues of unobservable part +## * Check whether ## real (ev) < -tol*(1 + abs (ev)) continuous-time ## abs (ev) < 1 - tol discrete-time ## @end group @@ -66,11 +72,11 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 -## Version: 0.2.1 +## Version: 0.3 -function bool = isstabilizable (a, b = [], tol = [], dflg = 0) +function bool = isstabilizable (a, b = [], e = [], tol = [], dflg = 0) - if (nargin < 1 || nargin > 4) + if (nargin < 1 || nargin > 5) print_usage (); elseif (isa (a, "lti")) # isstabilizable (sys), isstabilizable (sys, tol) if (nargin > 2) @@ -78,11 +84,13 @@ endif tol = b; dflg = ! isct (a); - [a, b] = ssdata (a); + [a, b, c, d, e] = dssdata (a, []); elseif (nargin == 1) # isstabilizable (a, b, ...) print_usage (); - elseif (! issquare (a) || rows (a) != rows (b)) - error ("isstabilizable: a must be square and conformal to b") + elseif (! is_real_square_matrix (a) || rows (a) != rows (b)) + error ("isstabilizable: a must be square and conformal to b"); + elseif (! isempty (e) && (! is_real_square_matrix (e) || ! size_equal (a, e))) + error ("isstabilizable: e must be square and conformal to a"); endif if (isempty (tol)) @@ -91,16 +99,29 @@ error ("isstabilizable: tol must be a real scalar"); endif - ## controllability staircase form - [ac, bc, u, ncont] = slab01od (a, b, tol); + if (isempty (e)) + ## controllability staircase form + [ac, bc, u, ncont] = slab01od (a, b, tol); - ## extract uncontrollable part of staircase form - uncont_idx = ncont+1 : rows (a); - auncont = ac(uncont_idx, uncont_idx); + ## extract uncontrollable part of staircase form + uncont_idx = ncont+1 : rows (a); + auncont = ac(uncont_idx, uncont_idx); - ## calculate poles of uncontrollable part - eigw = eig (auncont); + ## calculate poles of uncontrollable part + eigw = eig (auncont); + else + ## controllability staircase form - output matrix c has no influence + [ac, ec, bc, cc, q, z, ncont] = sltg01hd (a, e, b, zeros (1, columns (a)), tol); + ## extract uncontrollable part of staircase form + uncont_idx = ncont+1 : rows (a); + auncont = ac(uncont_idx, uncont_idx); + euncont = ec(uncont_idx, uncont_idx); + + ## calculate poles of uncontrollable part + eigw = eig (auncont, euncont); + endif + ## check whether uncontrollable poles are stable if (dflg) bool = all (abs (eigw) < 1 - tol); Modified: trunk/octave-forge/main/control/inst/ltimodels.m =================================================================== --- trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/inst/ltimodels.m 2010-09-25 14:35:25 UTC (rev 7766) @@ -501,6 +501,184 @@ %!assert (Bc, Bce, 1e-4); +## controllability staircase form of descriptor state-space models (SLICOT TG01HD) +%!shared ac, ec, bc, cc, q, z, ncont, ac_e, ec_e, bc_e, cc_e, q_e, z_e, ncont_e +%! +%! a = [ 2 0 2 0 -1 3 1 +%! 0 1 0 0 1 0 0 +%! 0 0 0 1 0 0 1 +%! 0 0 2 0 -1 3 1 +%! 0 0 0 1 0 0 1 +%! 0 1 0 0 1 0 0 +%! 0 0 0 1 0 0 1 ]; +%! +%! e = [ 0 0 1 0 0 0 0 +%! 0 0 0 0 0 1 0 +%! 0 0 0 0 0 0 1 +%! 0 0 0 0 0 0 1 +%! 0 0 0 1 0 0 0 +%! 0 0 1 0 -1 0 0 +%! 1 3 0 2 0 0 0 ]; +%! +%! b = [ 2 1 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 1 2 3 ]; +%! +%! c = [ 1 0 0 1 0 0 1 +%! 0 -1 1 0 -1 1 0 ]; +%! +%! tol = 0; +%! +%! [ac, ec, bc, cc, q, z, ncont] = sltg01hd (a, e, b, c, tol); +%! +%! ncont_e = 3; +%! +%! ac_e = [ 0.0000 0.0000 0.0000 0.0000 -1.2627 0.4334 0.4666 +%! 0.0000 2.0000 0.0000 -3.7417 -0.8520 0.2924 -0.4342 +%! 0.0000 0.0000 1.7862 0.3780 -0.2651 -0.7723 0.0000 +%! 0.0000 0.0000 0.0000 3.7417 0.8520 -0.2924 0.4342 +%! 0.0000 0.0000 0.0000 0.0000 -1.5540 0.5334 0.5742 +%! 0.0000 0.0000 0.0000 0.0000 -0.6533 0.2242 0.2414 +%! 0.0000 0.0000 0.0000 0.0000 -0.5892 0.2022 0.2177 ]; +%! +%! ec_e = [ -1.8325 1.0000 2.3752 0.0000 -0.8214 0.2819 1.8016 +%! 0.4887 0.0000 0.3770 -0.5345 0.1874 0.5461 0.0000 +%! -0.1728 0.0000 -0.1333 -1.1339 0.1325 0.3861 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.8520 -0.2924 0.4342 +%! 0.0000 0.0000 0.0000 0.0000 -1.0260 -0.1496 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.1937 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%! bc_e = [ 1.0000 2.0000 3.0000 +%! 2.0000 1.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 ]; +%! +%! cc_e = [ 0.0000 1.0000 0.0000 0.0000 -1.2627 0.4334 0.4666 +%! 0.3665 0.0000 -0.9803 -1.6036 0.1874 0.5461 0.0000 ]; +%! +%! q_e = [ 0.0000 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.7071 0.0000 0.2740 -0.6519 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.8304 0.3491 -0.4342 +%! 0.0000 0.0000 0.0000 -1.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.4003 0.1683 0.9008 +%! 0.0000 0.0000 0.7071 0.0000 -0.2740 0.6519 0.0000 +%! 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! z_e = [ 0.0000 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 +%! -0.6108 0.0000 0.7917 0.0000 0.0000 0.0000 0.0000 +%! 0.4887 0.0000 0.3770 -0.5345 0.1874 0.5461 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.4107 0.1410 0.9008 +%! 0.6108 0.0000 0.4713 0.2673 -0.1874 -0.5461 0.0000 +%! -0.1222 0.0000 -0.0943 -0.8018 -0.1874 -0.5461 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.8520 0.2924 -0.4342 ]; +%! +%!assert (ac, ac_e, 1e-4); +%!assert (ec, ec_e, 1e-4); +%!assert (bc, bc_e, 1e-4); +%!assert (cc, cc_e, 1e-4); +%!assert (q, q_e, 1e-4); +%!assert (z, z_e, 1e-4); +%!assert (ncont, ncont_e); + + +## observability staircase form of descriptor state-space models (SLICOT TG01ID) +%!shared ao, eo, bo, co, q, z, nobsv, ao_e, eo_e, bo_e, co_e, q_e, z_e, nobsv_e +%! +%! a = [ 2 0 0 0 0 0 0 +%! 0 1 0 0 0 1 0 +%! 2 0 0 2 0 0 0 +%! 0 0 1 0 1 0 1 +%! -1 1 0 -1 0 1 0 +%! 3 0 0 3 0 0 0 +%! 1 0 1 1 1 0 1 ]; +%! +%! e = [ 0 0 0 0 0 0 1 +%! 0 0 0 0 0 0 3 +%! 1 0 0 0 0 1 0 +%! 0 0 0 0 1 0 2 +%! 0 0 0 0 0 -1 0 +%! 0 1 0 0 0 0 0 +%! 0 0 1 1 0 0 0 ]; +%! +%! b = [ 1 0 +%! 0 -1 +%! 0 1 +%! 1 0 +%! 0 -1 +%! 0 1 +%! 1 0 ]; +%! +%! c = [ 2 0 0 0 0 0 1 +%! 1 0 0 0 0 0 2 +%! 0 0 0 0 0 0 3 ]; +%! +%! tol = 0; +%! +%! [ao, eo, bo, co, q, z, nobsv] = sltg01id (a, e, b, c, tol); +%! +%! nobsv_e = 3; +%! +%! ao_e = [ 0.2177 0.2414 0.5742 0.4342 0.0000 -0.4342 0.4666 +%! 0.2022 0.2242 0.5334 -0.2924 -0.7723 0.2924 0.4334 +%! -0.5892 -0.6533 -1.5540 0.8520 -0.2651 -0.8520 -1.2627 +%! 0.0000 0.0000 0.0000 3.7417 0.3780 -3.7417 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 1.7862 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 2.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! eo_e = [ 1.0000 0.0000 0.0000 0.4342 0.0000 0.0000 1.8016 +%! 0.0000 1.1937 -0.1496 -0.2924 0.3861 0.5461 0.2819 +%! 0.0000 0.0000 -1.0260 0.8520 0.1325 0.1874 -0.8214 +%! 0.0000 0.0000 0.0000 0.0000 -1.1339 -0.5345 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.1333 0.3770 2.3752 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.1728 0.4887 -1.8325 ]; +%! +%! bo_e = [ 0.4666 0.0000 +%! 0.4334 0.5461 +%! -1.2627 0.1874 +%! 0.0000 -1.6036 +%! 0.0000 -0.9803 +%! 1.0000 0.0000 +%! 0.0000 0.3665 ]; +%! +%! co_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 2.0000 1.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 2.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 3.0000 ]; +%! +%! q_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.7917 0.0000 -0.6108 +%! 0.0000 0.5461 0.1874 -0.5345 0.3770 0.0000 0.4887 +%! 0.9008 0.1410 -0.4107 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 -0.5461 -0.1874 0.2673 0.4713 0.0000 0.6108 +%! 0.0000 -0.5461 -0.1874 -0.8018 -0.0943 0.0000 -0.1222 +%! -0.4342 0.2924 -0.8520 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! z_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 0.0000 +%! 0.0000 -0.6519 0.2740 0.0000 0.7071 0.0000 0.0000 +%! -0.4342 0.3491 0.8304 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 -1.0000 0.0000 0.0000 0.0000 +%! 0.9008 0.1683 0.4003 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.6519 -0.2740 0.0000 0.7071 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%!assert (ao, ao_e, 1e-4); +%!assert (eo, eo_e, 1e-4); +%!assert (bo, bo_e, 1e-4); +%!assert (co, co_e, 1e-4); +%!assert (q, q_e, 1e-4); +%!assert (z, z_e, 1e-4); +%!assert (nobsv, nobsv_e); + + ## Cascade inter-connection of two systems in state-space form ## Test from SLICOT AB05MD ## TODO: order of united state vector: consistency vs. compatibility? Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-09-25 13:04:59 UTC (rev 7765) +++ trunk/octave-forge/main/control/src/Makefile 2010-09-25 14:35:25 UTC (rev 7766) @@ -2,6 +2,7 @@ slsb01bd.oct slsb10fd.oct slsb10dd.oct slsb03md.oct slsb04md.oct \ slsb04qd.oct slsg03ad.oct slsb02od.oct slab13ad.oct slab01od.oct \ sltb01pd.oct slsb03od.oct slsg03bd.oct slag08bd.oct sltg01jd.oct \ + sltg01hd.oct sltg01id.oct \ is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ is_real_square_matrix.oct @@ -149,6 +150,17 @@ mkoctfile sltg01jd.cc \ TG01JD.f TG01AD.f TB01XD.f MA02CD.f TG01HX.f +# controllability staircase form of descriptor state-space models +sltg01hd.oct: sltg01hd.cc + mkoctfile sltg01hd.cc \ + TG01HD.f TG01HX.f + +# observability staircase form of descriptor state-space models +sltg01id.oct: sltg01id.cc + mkoctfile sltg01id.cc \ + TG01ID.f TB01XD.f MA02CD.f AB07MD.f TG01HX.f \ + MA02BD.f + # helpers is_real_scalar.oct: is_real_scalar.cc mkoctfile is_real_scalar.cc Added: trunk/octave-forge/main/control/src/TG01HD.f =================================================================== --- trunk/octave-forge/main/control/src/TG01HD.f (rev 0) +++ trunk/octave-forge/main/control/src/TG01HD.f 2010-09-25 14:35:25 UTC (rev 7766) @@ -0,0 +1,545 @@ + SUBROUTINE TG01HD( JOBCON, COMPQ, COMPZ, N, M, P, A, LDA, E, LDE, + $ B, LDB, C, LDC, Q, LDQ, Z, LDZ, NCONT, NIUCON, + $ NRBLCK, RTAU, TOL, IWORK, DWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To compute orthogonal transformation matrices Q and Z which +C reduce the N-th order descriptor system (A-lambda*E,B,C) +C to the form +C +C ( Ac * ) ( Ec * ) ( Bc ) +C Q'*A*Z = ( ) , Q'*E*Z = ( ) , Q'*B = ( ) , +C ( 0 Anc ) ( 0 Enc ) ( 0 ) +C +C C*Z = ( Cc Cnc ) , +C +C where the NCONT-th order descriptor system (Ac-lambda*Ec,Bc,Cc) +C is a finite and/or infinite controllable. The pencil +C Anc - lambda*Enc is regular of order N-NCONT and contains the +C uncontrollable finite and/or infinite eigenvalues of the pencil +C A-lambda*E. +C +C For JOBCON = 'C' or 'I', the pencil ( Bc Ec-lambda*Ac ) has full +C row rank NCONT for all finite lambda and is in a staircase form +C with +C _ _ _ _ +C ( E1,0 E1,1 ... E1,k-1 E1,k ) +C ( _ _ _ ) +C ( Bc Ec ) = ( 0 E2,1 ... E2,k-1 E2,k ) , (1) +C ( ... _ _ ) +C ( 0 0 ... Ek,k-1 Ek,k ) +C +C _ _ _ +C ( A1,1 ... A1,k-1 A1,k ) +C ( _ _ ) +C Ac = ( 0 ... A2,k-1 A2,k ) , (2) +C ( ... _ ) +C ( 0 ... 0 Ak,k ) +C _ +C where Ei,i-1 is an rtau(i)-by-rtau(i-1) full row rank matrix +C _ +C (with rtau(0) = M) and Ai,i is an rtau(i)-by-rtau(i) +C upper triangular matrix. +C +C For JOBCON = 'F', the pencil ( Bc Ac-lambda*Ec ) has full +C row rank NCONT for all finite lambda and is in a staircase form +C with +C _ _ _ _ +C ( A1,0 A1,1 ... A1,k-1 A1,k ) +C ( _ _ _ ) +C ( Bc Ac ) = ( 0 A2,1 ... A2,k-1 A2,k ) , (3) +C ( ... _ _ ) +C ( 0 0 ... Ak,k-1 Ak,k ) +C +C _ _ _ +C ( E1,1 ... E1,k-1 E1,k ) +C ( _ _ ) +C Ec = ( 0 ... E2,k-1 E2,k ) , (4) +C ( ... _ ) +C ( 0 ... 0 Ek,k ) +C _ +C where Ai,i-1 is an rtau(i)-by-rtau(i-1) full row rank matrix +C _ +C (with rtau(0) = M) and Ei,i is an rtau(i)-by-rtau(i) +C upper triangular matrix. +C +C For JOBCON = 'C', the (N-NCONT)-by-(N-NCONT) regular pencil +C Anc - lambda*Enc has the form +C +C ( Ainc - lambda*Einc * ) +C Anc - lambda*Enc = ( ) , +C ( 0 Afnc - lambda*Efnc ) +C +C where: +C 1) the NIUCON-by-NIUCON regular pencil Ainc - lambda*Einc, +C with Ainc upper triangular and nonsingular, contains the +C uncontrollable infinite eigenvalues of A - lambda*E; +C 2) the (N-NCONT-NIUCON)-by-(N-NCONT-NIUCON) regular pencil +C Afnc - lambda*Efnc, with Efnc upper triangular and +C nonsingular, contains the uncontrollable finite +C eigenvalues of A - lambda*E. +C +C Note: The significance of the two diagonal blocks can be +C interchanged by calling the routine with the +C arguments A and E interchanged. In this case, +C Ainc - lambda*Einc contains the uncontrollable zero +C eigenvalues of A - lambda*E, while Afnc - lambda*Efnc +C contains the uncontrollable nonzero finite and infinite +C eigenvalues of A - lambda*E. +C +C For JOBCON = 'F', the pencil Anc - lambda*Enc has the form +C +C Anc - lambda*Enc = Afnc - lambda*Efnc , +C +C where the regular pencil Afnc - lambda*Efnc, with Efnc +C upper triangular and nonsingular, contains the uncontrollable +C finite eigenvalues of A - lambda*E. +C +C For JOBCON = 'I', the pencil Anc - lambda*Enc has the form +C +C Anc - lambda*Enc = Ainc - lambda*Einc , +C +C where the regular pencil Ainc - lambda*Einc, with Ainc +C upper triangular and nonsingular, contains the uncontrollable +C nonzero finite and infinite eigenvalues of A - lambda*E. +C +C The left and/or right orthogonal transformations Q and Z +C performed to reduce the system matrices can be optionally +C accumulated. +C +C The reduced order descriptor system (Ac-lambda*Ec,Bc,Cc) has +C the same transfer-function matrix as the original system +C (A-lambda*E,B,C). +C +C ARGUMENTS +C +C Mode Parameters +C +C JOBCON CHARACTER*1 +C = 'C': separate both finite and infinite uncontrollable +C eigenvalues; +C = 'F': separate only finite uncontrollable eigenvalues: +C = 'I': separate only nonzero finite and infinite +C uncontrollable eigenvalues. +C +C COMPQ CHARACTER*1 +C = 'N': do not compute Q; +C = 'I': Q is initialized to the unit matrix, and the +C orthogonal matrix Q is returned; +C = 'U': Q must contain an orthogonal matrix Q1 on entry, +C and the product Q1*Q is returned. +C +C COMPZ CHARACTER*1 +C = 'N': do not compute Z; +C = 'I': Z is initialized to the unit matrix, and the +C orthogonal matrix Z is returned; +C = 'U': Z must contain an orthogonal matrix Z1 on entry, +C and the product Z1*Z is returned. +C +C Input/Output Parameters +C +C N (input) INTEGER +C The dimension of the descriptor state vector; also the +C order of square matrices A and E, the number of rows of +C matrix B, and the number of columns of matrix C. N >= 0. +C +C M (input) INTEGER +C The dimension of descriptor system input vector; also the +C number of columns of matrix B. M >= 0. +C +C P (input) INTEGER +C The dimension of descriptor system output vector; also the +C number of rows of matrix C. P >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading N-by-N part of this array must +C contain the N-by-N state matrix A. +C On exit, the leading N-by-N part of this array contains +C the transformed state matrix Q'*A*Z, +C +C ( Ac * ) +C Q'*A*Z = ( ) , +C ( 0 Anc ) +C +C where Ac is NCONT-by-NCONT and Anc is +C (N-NCONT)-by-(N-NCONT). +C If JOBCON = 'F', the matrix ( Bc Ac ) is in the +C controllability staircase form (3). +C If JOBCON = 'C' or 'I', the submatrix Ac is upper +C triangular. +C If JOBCON = 'C', the Anc matrix has the form +C +C ( Ainc * ) +C Anc = ( ) , +C ( 0 Afnc ) +C +C where the NIUCON-by-NIUCON matrix Ainc is nonsingular and +C upper triangular. +C If JOBCON = 'I', Anc is nonsingular and upper triangular. +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,N). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading N-by-N part of this array must +C contain the N-by-N descriptor matrix E. +C On exit, the leading N-by-N part of this array contains +C the transformed descriptor matrix Q'*E*Z, +C +C ( Ec * ) +C Q'*E*Z = ( ) , +C ( 0 Enc ) +C +C where Ec is NCONT-by-NCONT and Enc is +C (N-NCONT)-by-(N-NCONT). +C If JOBCON = 'C' or 'I', the matrix ( Bc Ec ) is in the +C controllability staircase form (1). +C If JOBCON = 'F', the submatrix Ec is upper triangular. +C If JOBCON = 'C', the Enc matrix has the form +C +C ( Einc * ) +C Enc = ( ) , +C ( 0 Efnc ) +C +C where the NIUCON-by-NIUCON matrix Einc is nilpotent +C and the (N-NCONT-NIUCON)-by-(N-NCONT-NIUCON) matrix Efnc +C is nonsingular and upper triangular. +C If JOBCON = 'F', Enc is nonsingular and upper triangular. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,N). +C +C B (input/output) DOUBLE PRECISION array, dimension (LDB,M) +C On entry, the leading N-by-M part of this array must +C contain the N-by-M input matrix B. +C On exit, the leading N-by-M part of this array contains +C the transformed input matrix +C +C ( Bc ) +C Q'*B = ( ) , +C ( 0 ) +C +C where Bc is NCONT-by-M. +C For JOBCON = 'C' or 'I', the matrix ( Bc Ec ) is in the +C controllability staircase form (1). +C For JOBCON = 'F', the matrix ( Bc Ac ) is in the +C controllability staircase form (3). +C +C LDB INTEGER +C The leading dimension of array B. LDB >= MAX(1,N). +C +C C (input/output) DOUBLE PRECISION array, dimension (LDC,N) +C On entry, the leading P-by-N part of this array must +C contain the state/output matrix C. +C On exit, the leading P-by-N part of this array contains +C the transformed matrix C*Z. +C +C LDC INTEGER +C The leading dimension of array C. LDC >= MAX(1,P). +C +C Q (input/output) DOUBLE PRECISION array, dimension (LDQ,N) +C If COMPQ = 'N': Q is not referenced. +C If COMPQ = 'I': on entry, Q need not be set; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix Q, +C where Q' is the product of transformations +C which are applied to A, E, and B on +C the left. +C If COMPQ = 'U': on entry, the leading N-by-N part of this +C array must contain an orthogonal matrix +C Qc; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix +C Qc*Q. +C +C LDQ INTEGER +C The leading dimension of array Q. +C LDQ >= 1, if COMPQ = 'N'; +C LDQ >= MAX(1,N), if COMPQ = 'U' or 'I'. +C +C Z (input/output) DOUBLE PRECISION array, dimension (LDZ,N) +C If COMPZ = 'N': Z is not referenced. +C If COMPZ = 'I': on entry, Z need not be set; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix Z, +C which is the product of transformations +C applied to A, E, and C on the right. +C If COMPZ = 'U': on entry, the leading N-by-N part of this +C array must contain an orthogonal matrix +C Zc; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix +C Zc*Z. +C +C LDZ INTEGER +C The leading dimension of array Z. +C LDZ >= 1, if COMPZ = 'N'; +C LDZ >= MAX(1,N), if COMPZ = 'U' or 'I'. +C +C NCONT (output) INTEGER +C The order of the reduced matrices Ac and Ec, and the +C number of rows of reduced matrix Bc; also the order of +C the controllable part of the pair (A-lambda*E,B). +C +C NIUCON (output) INTEGER +C For JOBCON = 'C', the order of the reduced matrices +C Ainc and Einc; also the number of uncontrollable +C infinite eigenvalues of the pencil A - lambda*E. +C For JOBCON = 'F' or 'I', NIUCON has no significance +C and is set to zero. +C +C NRBLCK (output) INTEGER +C For JOBCON = 'C' or 'I', the number k, of full row rank +C _ +C blocks Ei,i in the staircase form of the pencil +C (Bc Ec-lambda*Ac) (see (1) and (2)). +C For JOBCON = 'F', the number k, of full row rank blocks +C _ +C Ai,i in the staircase form of the pencil (Bc Ac-lambda*Ec) +C (see (3) and (4)). +C +C RTAU (output) INTEGER array, dimension (N) +C RTAU(i), for i = 1, ..., NRBLCK, is the row dimension of +C _ _ +C the full row rank block Ei,i-1 or Ai,i-1 in the staircase +C form (1) or (3) for JOBCON = 'C' or 'I', or +C for JOBCON = 'F', respectively. +C +C Tolerances +C +C TOL DOUBLE PRECISION +C The tolerance to be used in rank determinations when +C transforming (A-lambda*E, B). If the user sets TOL > 0, +C then the given value of TOL is used as a lower bound for +C reciprocal condition numbers in rank determinations; a +C (sub)matrix whose estimated condition number is less than +C 1/TOL is considered to be of full rank. If the user sets +C TOL <= 0, then an implicitly computed, default tolerance, +C defined by TOLDEF = N*N*EPS, is used instead, where EPS +C is the machine precision (see LAPACK Library routine +C DLAMCH). TOL < 1. +C +C Workspace +C +C IWORK INTEGER array, dimension (M) +C +C DWORK DOUBLE PRECISION array, dimension MAX(N,2*M) +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The subroutine is based on the reduction algorithms of [1]. +C +C REFERENCES +C +C [1] A. Varga +C Computation of Irreducible Generalized State-Space +C Realizations. +C Kybernetika, vol. 26, pp. 89-106, 1990. +C +C NUMERICAL ASPECTS +C +C The algorithm is numerically backward stable and requires +C 0( N**3 ) floating point operations. +C +C FURTHER COMMENTS +C +C If the system matrices A, E and B are badly scaled, it is +C generally recommendable to scale them with the SLICOT routine +C TG01AD, before calling TG01HD. +C +C CONTRIBUTOR +C +C C. Oara, University "Politehnica" Bucharest. +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C March 1999. Based on the RASP routine RPDSCF. +C +C REVISIONS +C +C July 1999, V. Sima, Research Institute for Informatics, Bucharest. +C +C KEYWORDS +C +C Controllability, minimal realization, orthogonal canonical form, +C orthogonal transformation. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ONE + PARAMETER ( ONE = 1.0D0 ) +C .. Scalar Arguments .. + CHARACTER COMPQ, COMPZ, JOBCON + INTEGER INFO, LDA, LDB, LDC, LDE, LDQ, LDZ, + $ M, N, NCONT, NIUCON, NRBLCK, P + DOUBLE PRECISION TOL +C .. Array Arguments .. + INTEGER IWORK( * ), RTAU( * ) + DOUBLE PRECISION A( LDA, * ), B( LDB, * ), C( LDC, * ), + $ DWORK( * ), E( LDE, * ), Q( LDQ, * ), + $ Z( LDZ, * ) +C .. Local Scalars .. + CHARACTER JOBQ, JOBZ + LOGICAL FINCON, ILQ, ILZ, INFCON + INTEGER ICOMPQ, ICOMPZ, LBA, NR +C .. External Functions .. + LOGICAL LSAME + EXTERNAL LSAME +C .. External Subroutines .. + EXTERNAL TG01HX, XERBLA +C .. Intrinsic Functions .. + INTRINSIC MAX +C +C .. Executable Statements .. +C +C Decode JOBCON. +C + IF( LSAME( JOBCON, 'C' ) ) THEN + FINCON = .TRUE. + INFCON = .TRUE. + ELSE IF( LSAME( JOBCON, 'F' ) ) THEN + FINCON = .TRUE. + INFCON = .FALSE. + ELSE IF( LSAME( JOBCON, 'I' ) ) THEN + FINCON = .FALSE. + INFCON = .TRUE. + ELSE + FINCON = .FALSE. + INFCON = .FALSE. + END IF +C +C Decode COMPQ. +C + IF( LSAME( COMPQ, 'N' ) ) THEN + ILQ = .FALSE. + ICOMPQ = 1 + ELSE IF( LSAME( COMPQ, 'U' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 2 + ELSE IF( LSAME( COMPQ, 'I' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 3 + ELSE + ICOMPQ = 0 + END IF +C +C Decode COMPZ. +C + IF( LSAME( COMPZ, 'N' ) ) THEN + ILZ = .FALSE. + ICOMPZ = 1 + ELSE IF( LSAME( COMPZ, 'U' ) ) THEN + ILZ = .TRUE. + ICOMPZ = 2 + ELSE IF( LSAME( COMPZ, 'I' ) ) THEN + ILZ = .TRUE. + ICOMPZ = 3 + ELSE + ICOMPZ = 0 + END IF +C +C Test the input scalar parameters. +C + INFO = 0 + IF( .NOT.FINCON .AND. .NOT.INFCON ) THEN + INFO = -1 + ELSE IF( ICOMPQ.LE.0 ) THEN + INFO = -2 + ELSE IF( ICOMPZ.LE.0 ) THEN + INFO = -3 + ELSE IF( N.LT.0 ) THEN + INFO = -4 + ELSE IF( M.LT.0 ) THEN + INFO = -5 + ELSE IF( P.LT.0 ) THEN + INFO = -6 + ELSE IF( LDA.LT.MAX( 1, N ) ) THEN + INFO = -8 + ELSE IF( LDE.LT.MAX( 1, N ) ) THEN + INFO = -10 + ELSE IF( LDB.LT.MAX( 1, N ) ) THEN + INFO = -12 + ELSE IF( LDC.LT.MAX( 1, P ) ) THEN + INFO = -14 + ELSE IF( ( ILQ .AND. LDQ.LT.N ) .OR. LDQ.LT.1 ) THEN + INFO = -16 + ELSE IF( ( ILZ .AND. LDZ.LT.N ) .OR. LDZ.LT.1 ) THEN + INFO = -18 + ELSE IF( TOL.GE.ONE ) THEN + INFO = -23 + END IF + IF( INFO.NE.0 ) THEN + CALL XERBLA( 'TG01HD', -INFO ) + RETURN + END IF +C + JOBQ = COMPQ + JOBZ = COMPZ +C + IF( FINCON ) THEN +C +C Perform finite controllability form reduction. +C + CALL TG01HX( JOBQ, JOBZ, N, N, M, P, N, MAX( 0, N-1 ), A, LDA, + $ E, LDE, B, LDB, C, LDC, Q, LDQ, Z, LDZ, NR, + $ NRBLCK, RTAU, TOL, IWORK, DWORK, INFO ) + IF( NRBLCK.GT.1 ) THEN + LBA = RTAU(1) + RTAU(2) - 1 + ELSE IF( NRBLCK.EQ.1 ) THEN + LBA = RTAU(1) - 1 + ELSE + LBA = 0 + END IF + IF( ILQ ) JOBQ = 'U' + IF( ILZ ) JOBZ = 'U' + ELSE + NR = N + LBA = MAX( 0, N-1 ) + END IF +C + IF( INFCON ) THEN +C +C Perform infinite controllability form reduction. +C + CALL TG01HX( JOBQ, JOBZ, N, N, M, P, NR, LBA, E, LDE, + $ A, LDA, B, LDB, C, LDC, Q, LDQ, Z, LDZ, NCONT, + $ NRBLCK, RTAU, TOL, IWORK, DWORK, INFO ) + IF( FINCON ) THEN + NIUCON = NR - NCONT + ELSE + NIUCON = 0 + END IF + ELSE + NCONT = NR + NIUCON = 0 + END IF +C + RETURN +C +C *** Last line of TG01HD *** + END Added: trunk/octave-forge/main/control/src/TG01ID.f =================================================================== --- trunk/octave-forge/main/control/src/TG01ID.f (rev 0) +++ trunk/octave-forge/main/control/src/TG01ID.f 2010-09-25 14:35:25 UTC (rev 7766) @@ -0,0 +1,587 @@ + SUBROUTINE TG01ID( JOBOBS, COMPQ, COMPZ, N, M, P, A, LDA, E, LDE, + $ B, LDB, C, LDC, Q, LDQ, Z, LDZ, NOBSV, NIUOBS, + $ NLBLCK, CTAU, TOL, IWORK, DWORK, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To compute orthogonal transformation matrices Q and Z which +C reduce the N-th order descriptor system (A-lambda*E,B,C) +C to the form +C +C ( Ano * ) ( Eno * ) ( Bno ) +C Q'*A*Z = ( ) , Q'*E*Z = ( ) , Q'*B = ( ) , +C ( 0 Ao ) ( 0 Eo ) ( Bo ) +C +C C*Z = ( 0 Co ) , +C +C where the NOBSV-th order descriptor system (Ao-lambda*Eo,Bo,Co) +C is a finite and/or infinite observable. The pencil +C Ano - lambda*Eno is regular of order N-NOBSV and contains the +C unobservable finite and/or infinite eigenvalues of the pencil +C A-lambda*E. +C +C For JOBOBS = 'O' or 'I', the pencil ( Eo-lambda*Ao ) has full +C ( Co ) +C column rank NOBSV for all finite lambda and is in a staircase form +C with +C _ _ _ _ +C ( Ek,k Ek,k-1 ... Ek,2 Ek,1 ) +C ( _ _ _ _ ) +C ( Eo ) = ( Ek-1,k Ek-1,k-1 ... Ek-1,2 Ek-1,1 ) , (1) +C ( Co ) ( ... ... _ _ ) +C ( 0 0 ... E1,2 E1,1 ) +C ( _ ) +C ( 0 0 ... 0 E0,1 ) +C _ _ _ +C ( Ak,k ... Ak,2 Ak,1 ) +C ( ... _ _ ) +C Ao = ( 0 ... A2,2 A2,1 ) , (2) +C ( _ ) +C ( 0 ... 0 A1,1 ) +C _ +C where Ei-1,i is a CTAU(i-1)-by-CTAU(i) full column rank matrix +C _ +C (with CTAU(0) = P) and Ai,i is a CTAU(i)-by-CTAU(i) +C upper triangular matrix. +C +C For JOBOBS = 'F', the pencil ( Ao-lambda*Eo ) has full +C ( Co ) +C column rank NOBSV for all finite lambda and is in a staircase form +C with +C _ _ _ _ +C ( Ak,k Ak,k-1 ... Ak,2 Ak,1 ) +C ( _ _ _ _ ) +C ( Ao ) = ( Ak-1,k Ak-1,k-1 ... Ak-1,2 Ak-1,1 ) , (3) +C ( Co ) ( ... ... _ _ ) +C ( 0 0 ... A1,2 A1,1 ) +C ( _ ) +C ( 0 0 ... 0 A0,1 ) +C _ _ _ +C ( Ek,k ... Ek,2 Ek,1 ) +C ( ... _ _ ) +C Eo = ( 0 ... E2,2 E2,1 ) , (4) +C ( _ ) +C ( 0 ... 0 E1,1 ) +C _ +C where Ai-1,i is a CTAU(i-1)-by-CTAU(i) full column rank matrix +C _ +C (with CTAU(0) = P) and Ei,i is a CTAU(i)-by-CTAU(i) +C upper triangular matrix. +C +C For JOBOBS = 'O', the (N-NOBSV)-by-(N-NOBSV) regular pencil +C Ano - lambda*Eno has the form +C +C ( Afno - lambda*Efno * ) +C Ano - lambda*Eno = ( ) , +C ( 0 Aino - lambda*Eino ) +C +C where: +C 1) the NIUOBS-by-NIUOBS regular pencil Aino - lambda*Eino, +C with Aino upper triangular and nonsingular, contains the +C unobservable infinite eigenvalues of A - lambda*E; +C 2) the (N-NOBSV-NIUOBS)-by-(N-NOBSV-NIUOBS) regular pencil +C Afno - lambda*Efno, with Efno upper triangular and +C nonsingular, contains the unobservable finite +C eigenvalues of A - lambda*E. +C +C Note: The significance of the two diagonal blocks can be +C interchanged by calling the routine with the +C arguments A and E interchanged. In this case, +C Aino - lambda*Eino contains the unobservable zero +C eigenvalues of A - lambda*E, while Afno - lambda*Efno +C contains the unobservable nonzero finite and infinite +C eigenvalues of A - lambda*E. +C +C For JOBOBS = 'F', the pencil Ano - lambda*Eno has the form +C +C Ano - lambda*Eno = Afno - lambda*Efno , +C +C where the regular pencil Afno - lambda*Efno, with Efno +C upper triangular and nonsingular, contains the unobservable +C finite eigenvalues of A - lambda*E. +C +C For JOBOBS = 'I', the pencil Ano - lambda*Eno has the form +C +C Ano - lambda*Eno = Aino - lambda*Eino , +C +C where the regular pencil Aino - lambda*Eino, with Aino +C upper triangular and nonsingular, contains the unobservable +C nonzero finite and infinite eigenvalues of A - lambda*E. +C +C The left and/or right orthogonal transformations Q and Z +C performed to reduce the system matrices can be optionally +C accumulated. +C +C The reduced order descriptor system (Ao-lambda*Eo,Bo,Co) has +C the same transfer-function matrix as the original system +C (A-lambda*E,B,C). +C +C ARGUMENTS +C +C Mode Parameters +C +C JOBOBS CHARACTER*1 +C = 'O': separate both finite and infinite unobservable +C eigenvalues; +C = 'F': separate only finite unobservable eigenvalues; +C = 'I': separate only nonzero finite and infinite +C unobservable eigenvalues. +C +C COMPQ CHARACTER*1 +C = 'N': do not compute Q; +C = 'I': Q is initialized to the unit matrix, and the +C orthogonal matrix Q is returned; +C = 'U': Q must contain an orthogonal matrix Q1 on entry, +C and the product Q1*Q is returned. +C +C COMPZ CHARACTER*1 +C = 'N': do not compute Z; +C = 'I': Z is initialized to the unit matrix, and the +C orthogonal matrix Z is returned; +C = 'U': Z must contain an orthogonal matrix Z1 on entry, +C and the product Z1*Z is returned. +C +C Input/Output Parameters +C +C N (input) INTEGER +C The dimension of the descriptor state vector; also the +C order of square matrices A and E, the number of rows of +C matrix B, and the number of columns of matrix C. N >= 0. +C +C M (input) INTEGER +C The dimension of descriptor system input vector; also the +C number of columns of matrix B. M >= 0. +C +C P (input) INTEGER +C The dimension of descriptor system output vector; also the +C number of rows of matrix C. P >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading N-by-N part of this array must +C contain the N-by-N state matrix A. +C On exit, the leading N-by-N part of this array contains +C the transformed state matrix Q'*A*Z, +C +C ( Ano * ) +C Q'*A*Z = ( ) , +C ( 0 Ao ) +C +C where Ao is NOBSV-by-NOBSV and Ano is +C (N-NOBSV)-by-(N-NOBSV). +C If JOBOBS = 'F', the matrix ( Ao ) is in the observability +C ( Co ) +C staircase form (3). +C If JOBOBS = 'O' or 'I', the submatrix Ao is upper +C triangular. +C If JOBOBS = 'O', the submatrix Ano has the form +C +C ( Afno * ) +C Ano = ( ) , +C ( 0 Aino ) +C +C where the NIUOBS-by-NIUOBS matrix Aino is nonsingular and +C upper triangular. +C If JOBOBS = 'I', Ano is nonsingular and upper triangular. +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,N). +C +C E (input/output) DOUBLE PRECISION array, dimension (LDE,N) +C On entry, the leading N-by-N part of this array must +C contain the N-by-N descriptor matrix E. +C On exit, the leading N-by-N part of this array contains +C the transformed state matrix Q'*E*Z, +C +C ( Eno * ) +C Q'*E*Z = ( ) , +C ( 0 Eo ) +C +C where Eo is NOBSV-by-NOBSV and Eno is +C (N-NOBSV)-by-(N-NOBSV). +C If JOBOBS = 'O' or 'I', the matrix ( Eo ) is in the +C ( Co ) +C observability staircase form (1). +C If JOBOBS = 'F', the submatrix Eo is upper triangular. +C If JOBOBS = 'O', the Eno matrix has the form +C +C ( Efno * ) +C Eno = ( ) , +C ( 0 Eino ) +C +C where the NIUOBS-by-NIUOBS matrix Eino is nilpotent +C and the (N-NOBSV-NIUOBS)-by-(N-NOBSV-NIUOBS) matrix Efno +C is nonsingular and upper triangular. +C If JOBOBS = 'F', Eno is nonsingular and upper triangular. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,N). +C +C B (input/output) DOUBLE PRECISION array, dimension +C (LDB,MAX(M,P)) +C On entry, the leading N-by-M part of this array must +C contain the N-by-M input matrix B. +C On exit, the leading N-by-M part of this array contains +C the transformed input matrix Q'*B. +C +C LDB INTEGER +C The leading dimension of array B. +C LDB >= MAX(1,N) if M > 0 or LDB >= 1 if M = 0. +C +C C (input/output) DOUBLE PRECISION array, dimension (LDC,N) +C On entry, the leading P-by-N part of this array must +C contain the state/output matrix C. +C On exit, the leading P-by-N part of this array contains +C the transformed matrix +C +C C*Z = ( 0 Co ) , +C +C where Co is P-by-NOBSV. +C If JOBOBS = 'O' or 'I', the matrix ( Eo ) is in the +C ( Co ) +C observability staircase form (1). +C If JOBOBS = 'F', the matrix ( Ao ) is in the observability +C ( Co ) +C staircase form (3). +C +C LDC INTEGER +C The leading dimension of array C. LDC >= MAX(1,M,P). +C +C Q (input/output) DOUBLE PRECISION array, dimension (LDQ,N) +C If COMPQ = 'N': Q is not referenced. +C If COMPQ = 'I': on entry, Q need not be set; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix Q, +C where Q' is the product of transformations +C which are applied to A, E, and B on +C the left. +C If COMPQ = 'U': on entry, the leading N-by-N part of this +C array must contain an orthogonal matrix +C Qc; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix +C Qc*Q. +C +C LDQ INTEGER +C The leading dimension of array Q. +C LDQ >= 1, if COMPQ = 'N'; +C LDQ >= MAX(1,N), if COMPQ = 'U' or 'I'. +C +C Z (input/output) DOUBLE PRECISION array, dimension (LDZ,N) +C If COMPZ = 'N': Z is not referenced. +C If COMPZ = 'I': on entry, Z need not be set; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix Z, +C which is the product of transformations +C applied to A, E, and C on the right. +C If COMPZ = 'U': on entry, the leading N-by-N part of this +C array must contain an orthogonal matrix +C Zc; +C on exit, the leading N-by-N part of this +C array contains the orthogonal matrix +C Zc*Z. +C +C LDZ INTEGER +C The leading dimension of array Z. +C LDZ >= 1, if COMPZ = 'N'; +C LDZ >= MAX(1,N), if COMPZ = 'U' or 'I'. +C +C NOBSV (output) INTEGER +C The order of the reduced matrices Ao and Eo, and the +C number of columns of reduced matrix Co; also the order of +C observable part of the pair (C, A-lambda*E). +C +C NIUOBS (output) INTEGER +C For JOBOBS = 'O', the order of the reduced matrices +C Aino and Eino; also the number of unobservable +C infinite eigenvalues of the pencil A - lambda*E. +C For JOBOBS = 'F' or 'I', NIUOBS has no significance +C and is set to zero. +C +C NLBLCK (output) INTEGER +C For JOBOBS = 'O' or 'I', the number k, of full column rank +C _ +C blocks Ei-1,i in the staircase form of the pencil +C (Eo-lambda*Ao) (see (1) and (2)). +C ( Co ) +C For JOBOBS = 'F', the number k, of full column rank blocks +C _ +C Ai-1,i in the staircase form of the pencil (Ao-lambda*Eo) +C ( Co ) +C (see (3) and (4)). +C +C CTAU (output) INTEGER array, dimension (N) +C CTAU(i), for i = 1, ..., NLBLCK, is the column dimension +C _ _ +C of the full column rank block Ei-1,i or Ai-1,i in the +C staircase form (1) or (3) for JOBOBS = 'O' or 'I', or +C for JOBOBS = 'F', respectively. +C +C Tolerances +C +C TOL DOUBLE PRECISION +C The tolerance to be used in rank determinations when +C transforming (A'-lambda*E',C')'. If the user sets TOL > 0, +C then the given value of TOL is used as a lower bound for +C reciprocal condition numbers in rank determinations; a +C (sub)matrix whose estimated condition number is less than +C 1/TOL is considered to be of full rank. If the user sets +C TOL <= 0, then an implicitly computed, default tolerance, +C defined by TOLDEF = N*N*EPS, is used instead, where EPS +C is the machine precision (see LAPACK Library routine +C DLAMCH). TOL < 1. +C +C Workspace +C +C IWORK INTEGER array, dimension (P) +C +C DWORK DOUBLE PRECISION array, dimension MAX(N,2*P) +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value. +C +C METHOD +C +C The subroutine is based on the dual of the reduction +C algorithms of [1]. +C +C REFERENCES +C +C [1] A. Varga +C Computation of Irreducible Generalized State-Space +C Realizations. +C Kybernetika, vol. 26, pp. 89-106, 1990. +C +C NUMERICAL ASPECTS +C +C The algorithm is numerically backward stable and requires +C 0( N**3 ) floating point operations. +C +C FURTHER COMMENTS +C +C If the system matrices A, E and C are badly scaled, it is +C generally recommendable to scale them with the SLICOT routine +C TG01AD, before calling TG01ID. +C +C CONTRIBUTOR +C +C C. Oara, University "Politehnica" Bucharest. +C A. Varga, German Aerospace Center, DLR Oberpfaffenhofen. +C March 1999. Based on the RASP routine RPDSCF. +C +C REVISIONS +C +C July 1999, V. Sima, Research Institute for Informatics, Bucharest. +C May 2003, March 2004, V. Sima. +C +C KEYWORDS +C +C Observability, minimal realization, orthogonal canonical form, +C orthogonal transformation. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ONE + PARAMETER ( ONE = 1.0D0 ) +C .. Scalar Arguments .. + CHARACTER COMPQ, COMPZ, JOBOBS + INTEGER INFO, LDA, LDB, LDC, LDE, LDQ, LDZ, + $ M, N, NIUOBS, NLBLCK, NOBSV, P + DOUBLE PRECISION TOL +C .. Array Arguments .. + INTEGER CTAU( * ), IWORK( * ) + DOUBLE PRECISION A( LDA, * ), B( LDB, * ), C( LDC, * ), + $ DWORK( * ), E( LDE, * ), Q( LDQ, * ), + $ Z( LDZ, * ) +C .. Local Scalars .. + CHARACTER JOBQ, JOBZ + LOGICAL FINOBS, ILQ, ILZ, INFOBS + INTEGER I, ICOMPQ, ICOMPZ, LBA, LBE, NR +C .. Local Arrays .. + DOUBLE PRECISION DUM(1) +C .. External Functions .. + LOGICAL LSAME + EXTERNAL LSAME +C .. External Subroutines .. + EXTERNAL AB07MD, DSWAP, MA02BD, MA02CD, TB01XD, + $ TG01HX, XERBLA +C .. Intrinsic Functions .. + INTRINSIC MAX +C +C .. Executable Statements .. +C +C Decode JOBOBS. +C + IF( LSAME( JOBOBS, 'O') ) THEN + FINOBS = .TRUE. + INFOBS = .TRUE. + ELSE IF( LSAME( JOBOBS, 'F') ) THEN + FINOBS = .TRUE. + INFOBS = .FALSE. + ELSE IF( LSAME( JOBOBS, 'I') ) THEN + FINOBS = .FALSE. + INFOBS = .TRUE. + ELSE + FINOBS = .FALSE. + INFOBS = .FALSE. + END IF +C +C Decode COMPQ. +C + IF( LSAME( COMPQ, 'N' ) ) THEN + ILQ = .FALSE. + ICOMPQ = 1 + ELSE IF( LSAME( COMPQ, 'U' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 2 + ELSE IF( LSAME( COMPQ, 'I' ) ) THEN + ILQ = .TRUE. + ICOMPQ = 3 + ELSE + ICOMPQ = 0 + END IF +C +C Decode COMPZ. +C + IF( LSAME( COMPZ, 'N' ) ) THEN + ILZ = .FALSE. + ICOMPZ = 1 + ELSE IF( LSAME( COMPZ, 'U' ) ) THEN + ILZ = .TRUE. + ICOMPZ = 2 + ELSE IF( LSAME( COMPZ, 'I' ) ) THEN + ILZ = .TRUE. + ... [truncated message content] |
From: <par...@us...> - 2010-10-01 22:17:00
|
Revision: 7790 http://octave.svn.sourceforge.net/octave/?rev=7790&view=rev Author: paramaniac Date: 2010-10-01 22:16:52 +0000 (Fri, 01 Oct 2010) Log Message: ----------- control: add descriptor model support for ARE solvers (incomplete) Modified Paths: -------------- trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/src/Makefile trunk/octave-forge/main/control/src/makefile_lqr.m Added Paths: ----------- trunk/octave-forge/main/control/src/MA02GD.f trunk/octave-forge/main/control/src/MB02VD.f trunk/octave-forge/main/control/src/SG02AD.f trunk/octave-forge/main/control/src/slsg02ad.cc Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-10-01 13:27:35 UTC (rev 7789) +++ trunk/octave-forge/main/control/inst/care.m 2010-10-01 22:16:52 UTC (rev 7790) @@ -68,16 +68,13 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: November 2009 -## Version: 0.4 +## Version: 0.5 -function [x, l, g] = care (a, b, q, r, s = []) +function [x, l, g] = care (a, b, q, r, s = [], e = []) - ## TODO: Add SLICOT SG02AD (Solution of continuous- or discrete-time - ## algebraic Riccati equations for descriptor systems) - ## TODO: extract feedback matrix g from SB02OD (and SG02AD) - if (nargin < 4 || nargin > 5) + if (nargin < 4 || nargin > 6) print_usage (); endif @@ -86,11 +83,11 @@ endif if (! is_real_matrix (b) || rows (a) != rows (b)) - error ("care: b must be real and conformal to a"); + error ("care: a and b must have the same number of rows"); endif if (columns (r) != columns (b)) - error ("care: (b, r) not conformable"); + error ("care: b and r must have the same number of columns"); endif if (! is_real_matrix (s) && ! size_equal (s, b)) @@ -98,8 +95,12 @@ rows (s), columns (s), rows (b), columns (b)); endif + if (! isempty (e) && (! is_real_square_matrix (e) || ! size_equal (e, a))) + error ("care: a and e must have the same number of rows"); + endif + ## check stabilizability - if (! isstabilizable (a, b, [], [], 0)) + if (! isstabilizable (a, b, e, [], 0)) error ("care: (a, b) not stabilizable"); endif @@ -117,14 +118,22 @@ endif ## solve the riccati equation - if (isempty (s)) - [x, l] = slsb02od (a, b, q, r, b, false, false); - - g = r \ (b.'*x); # gain matrix + if (isempty (e)) + if (isempty (s)) + [x, l] = slsb02od (a, b, q, r, b, false, false); + g = r \ (b.'*x); # gain matrix + else + [x, l] = slsb02od (a, b, q, r, s, false, true); + g = r \ (b.'*x + s.'); # gain matrix + endif else - [x, l] = slsb02od (a, b, q, r, s, false, true); - - g = r \ (b.'*x + s.'); # gain matrix + if (isempty (s)) + [x, l] = slsg02ad (a, e, b, q, r, b, false, false); + g = r \ (e.'*x*b).'; + else + [x, l] = slsg02ad (a, e, b, q, r, s, false, true); + g = r \ (e.'*x*b + s).'; + endif endif endfunction @@ -182,4 +191,29 @@ %! %!assert (x, xe, 1e-4); %!assert (l, le, 1e-4); -%!assert (g, ge, 1e-4); \ No newline at end of file +%!assert (g, ge, 1e-4); + +%!shared x, xe +%! a = [ 0.0 1.0 +%! 0.0 0.0 ]; +%! +%! e = [ 1.0 0.0 +%! 0.0 1.0 ]; +%! +%! b = [ 0.0 +%! 1.0 ]; +%! +%! c = [ 1.0 0.0 +%! 0.0 1.0 +%! 0.0 0.0 ]; +%! +%! d = [ 0.0 +%! 0.0 +%! 1.0 ]; +%! +%! x = care (a, b, c.'*c, d.'*d, [], e); +%! +%! xe = [ 1.7321 1.0000 +%! 1.0000 1.7321 ]; +%! +%!assert (x, xe, 1e-4); \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-10-01 13:27:35 UTC (rev 7789) +++ trunk/octave-forge/main/control/inst/dare.m 2010-10-01 22:16:52 UTC (rev 7790) @@ -68,16 +68,13 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 -## Version: 0.4 +## Version: 0.5 -function [x, l, g] = dare (a, b, q, r, s = []) +function [x, l, g] = dare (a, b, q, r, s = [], e = []) - ## TODO: Add SLICOT SG02AD (Solution of continuous- or discrete-time - ## algebraic Riccati equations for descriptor systems) - ## TODO: extract feedback matrix g from SB02OD (and SG02AD) - if (nargin < 4 || nargin > 5) + if (nargin < 4 || nargin > 6) print_usage (); endif @@ -97,9 +94,13 @@ error ("dare: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", rows (s), columns (s), rows (b), columns (b)); endif - + + if (! isempty (e) && (! is_real_square_matrix (e) || ! size_equal (e, a))) + error ("dare: a and e must have the same number of rows"); + endif + ## check stabilizability - if (! isstabilizable (a, b, [], [], 1)) + if (! isstabilizable (a, b, e, [], 1)) error ("dare: (a, b) not stabilizable"); endif @@ -117,14 +118,22 @@ endif ## solve the riccati equation - if (isempty (s)) - [x, l] = slsb02od (a, b, q, r, b, true, false); - - g = (r + b.'*x*b) \ (b.'*x*a); # gain matrix + if (isempty (e)) + if (isempty (s)) + [x, l] = slsb02od (a, b, q, r, b, true, false); + g = (r + b.'*x*b) \ (b.'*x*a); # gain matrix + else + [x, l] = slsb02od (a, b, q, r, s, true, true); + g = (r + b.'*x*b) \ (b.'*x*a + s.'); # gain matrix + endif else - [x, l] = slsb02od (a, b, q, r, s, true, true); - - g = (r + b.'*x*b) \ (b.'*x*a + s.'); # gain matrix + if (isempty (s)) + [x, l] = slsg02ad (a, e, b, q, r, b, true, false); + g = (r + b.'*x*b) \ (a.'*x*b).'; + else + [x, l] = slsg02ad (a, e, b, q, r, s, true, true); + g = (r + b.'*x*b) \ (a.'*x*b + s).'; + endif endif endfunction @@ -153,4 +162,6 @@ %! %!assert (x, xe, 1e-4); %!assert (sort (l), sort (le), 1e-4); -%!assert (g, ge, 1e-4); \ No newline at end of file +%!assert (g, ge, 1e-4); + +## TODO: add more tests (nonempty s and/or e) \ No newline at end of file Added: trunk/octave-forge/main/control/src/MA02GD.f =================================================================== --- trunk/octave-forge/main/control/src/MA02GD.f (rev 0) +++ trunk/octave-forge/main/control/src/MA02GD.f 2010-10-01 22:16:52 UTC (rev 7790) @@ -0,0 +1,158 @@ + SUBROUTINE MA02GD( N, A, LDA, K1, K2, IPIV, INCX ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To perform a series of column interchanges on the matrix A. +C One column interchange is initiated for each of columns K1 through +C K2 of A. This is useful for solving linear systems X*A = B, when +C the matrix A has already been factored by LAPACK Library routine +C DGETRF. +C +C ARGUMENTS +C +C Input/Output Parameters +C +C N (input) INTEGER +C The number of rows of the matrix A. N >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,*) +C On entry, the leading N-by-M part of this array must +C contain the matrix A to which the column interchanges will +C be applied, where M is the largest element of IPIV(K), for +C K = K1, ..., K2. +C On exit, the leading N-by-M part of this array contains +C the permuted matrix. +C +C LDA INTEGER +C The leading dimension of the array A. LDA >= MAX(1,N). +C +C K1 (input) INTEGER +C The first element of IPIV for which a column interchange +C will be done. +C +C K2 (input) INTEGER +C The last element of IPIV for which a column interchange +C will be done. +C +C IPIV (input) INTEGER array, dimension (K1+(K2-K1)*abs(INCX)) +C The vector of interchanging (pivot) indices. Only the +C elements in positions K1 through K2 of IPIV are accessed. +C IPIV(K) = L implies columns K and L are to be +C interchanged. +C +C INCX (input) INTEGER +C The increment between successive values of IPIV. +C If INCX is negative, the interchanges are applied in +C reverse order. +C +C METHOD +C +C The columns IPIV(K) and K are swapped for K = K1, ..., K2, for +C INCX = 1 (and similarly, for INCX <> 1). +C +C FURTHER COMMENTS +C +C This routine is the column-oriented counterpart of the LAPACK +C Library routine DLASWP. The LAPACK Library routine DLAPMT cannot +C be used in this context. To solve the system X*A = B, where A and +C B are N-by-N and M-by-N, respectively, the following statements +C can be used: +C +C CALL DGETRF( N, N, A, LDA, IPIV, INFO ) +C CALL DTRSM( 'R', 'U', 'N', 'N', M, N, ONE, A, LDA, B, LDB ) +C CALL DTRSM( 'R', 'L', 'N', 'U', M, N, ONE, A, LDA, B, LDB ) +C CALL MA02GD( M, B, LDB, 1, N, IPIV, -1 ) +C +C CONTRIBUTOR +C +C V. Sima, Research Institute for Informatics, Bucharest, Mar. 2000. +C +C REVISIONS +C +C V. Sima, Research Institute for Informatics, Bucharest, Apr. 2008. +C +C KEYWORDS +C +C Elementary matrix operations, linear algebra. +C +C ****************************************************************** +C +C .. Scalar Arguments .. + INTEGER INCX, K1, K2, LDA, N +C .. +C .. Array Arguments .. + INTEGER IPIV( * ) + DOUBLE PRECISION A( LDA, * ) +C .. +C .. Local Scalars .. + INTEGER J, JP, JX +C .. +C .. External Subroutines .. + EXTERNAL DSWAP +C .. +C .. Executable Statements .. +C +C Quick return if possible. +C + IF( INCX.EQ.0 .OR. N.EQ.0 ) + $ RETURN +C +C Interchange column J with column IPIV(J) for each of columns K1 +C through K2. +C + IF( INCX.GT.0 ) THEN + JX = K1 + ELSE + JX = 1 + ( 1-K2 )*INCX + END IF +C + IF( INCX.EQ.1 ) THEN +C + DO 10 J = K1, K2 + JP = IPIV( J ) + IF( JP.NE.J ) + $ CALL DSWAP( N, A( 1, J ), 1, A( 1, JP ), 1 ) + 10 CONTINUE +C + ELSE IF( INCX.GT.1 ) THEN +C + DO 20 J = K1, K2 + JP = IPIV( JX ) + IF( JP.NE.J ) + $ CALL DSWAP( N, A( 1, J ), 1, A( 1, JP ), 1 ) + JX = JX + INCX + 20 CONTINUE +C + ELSE IF( INCX.LT.0 ) THEN +C + DO 30 J = K2, K1, -1 + JP = IPIV( JX ) + IF( JP.NE.J ) + $ CALL DSWAP( N, A( 1, J ), 1, A( 1, JP ), 1 ) + JX = JX + INCX + 30 CONTINUE +C + END IF +C + RETURN +C +C *** Last line of MA02GD *** + END Added: trunk/octave-forge/main/control/src/MB02VD.f =================================================================== --- trunk/octave-forge/main/control/src/MB02VD.f (rev 0) +++ trunk/octave-forge/main/control/src/MB02VD.f 2010-10-01 22:16:52 UTC (rev 7790) @@ -0,0 +1,187 @@ + SUBROUTINE MB02VD( TRANS, M, N, A, LDA, IPIV, B, LDB, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To compute the solution to a real system of linear equations +C X * op(A) = B, +C where op(A) is either A or its transpose, A is an N-by-N matrix, +C and X and B are M-by-N matrices. +C The LU decomposition with partial pivoting and row interchanges, +C A = P * L * U, is used, where P is a permutation matrix, L is unit +C lower triangular, and U is upper triangular. +C +C ARGUMENTS +C +C Mode Parameters +C +C TRANS CHARACTER*1 +C Specifies the form of op(A) to be used as follows: +C = 'N': op(A) = A; +C = 'T': op(A) = A'; +C = 'C': op(A) = A'. +C +C Input/Output Parameters +C +C M (input) INTEGER +C The number of rows of the matrix B. M >= 0. +C +C N (input) INTEGER +C The number of columns of the matrix B, and the order of +C the matrix A. N >= 0. +C +C A (input/output) DOUBLE PRECISION array, dimension (LDA,N) +C On entry, the leading N-by-N part of this array must +C contain the coefficient matrix A. +C On exit, the leading N-by-N part of this array contains +C the factors L and U from the factorization A = P*L*U; +C the unit diagonal elements of L are not stored. +C +C LDA INTEGER +C The leading dimension of the array A. LDA >= MAX(1,N). +C +C IPIV (output) INTEGER array, dimension (N) +C The pivot indices that define the permutation matrix P; +C row i of the matrix was interchanged with row IPIV(i). +C +C B (input/output) DOUBLE PRECISION array, dimension (LDB,N) +C On entry, the leading M-by-N part of this array must +C contain the right hand side matrix B. +C On exit, if INFO = 0, the leading M-by-N part of this +C array contains the solution matrix X. +C +C LDB (input) INTEGER +C The leading dimension of the array B. LDB >= max(1,M). +C +C INFO (output) INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value; +C > 0: if INFO = i, U(i,i) is exactly zero. The +C factorization has been completed, but the factor U +C is exactly singular, so the solution could not be +C computed. +C +C METHOD +C +C The LU decomposition with partial pivoting and row interchanges is +C used to factor A as +C A = P * L * U, +C where P is a permutation matrix, L is unit lower triangular, and +C U is upper triangular. The factored form of A is then used to +C solve the system of equations X * A = B or X * A' = B. +C +C FURTHER COMMENTS +C +C This routine enables to solve the system X * A = B or X * A' = B +C as easily and efficiently as possible; it is similar to the LAPACK +C Library routine DGESV, which solves A * X = B. +C +C CONTRIBUTOR +C +C V. Sima, Research Institute for Informatics, Bucharest, Mar. 2000. +C +C REVISIONS +C +C - +C +C KEYWORDS +C +C Elementary matrix operations, linear algebra. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ONE + PARAMETER ( ONE = 1.0D0 ) +C .. Scalar Arguments .. + CHARACTER TRANS + INTEGER INFO, LDA, LDB, M, N +C .. +C .. Array Arguments .. + INTEGER IPIV( * ) + DOUBLE PRECISION A( LDA, * ), B( LDB, * ) +C .. +C .. Local Scalars .. + LOGICAL TRAN +C .. +C .. External Functions .. + LOGICAL LSAME + EXTERNAL LSAME +C .. +C .. External Subroutines .. + EXTERNAL DGETRF, DTRSM, MA02GD, XERBLA +C .. +C .. Intrinsic Functions .. + INTRINSIC MAX +C .. +C .. Executable Statements .. +C +C Test the scalar input parameters. +C + INFO = 0 + TRAN = LSAME( TRANS, 'T' ) .OR. LSAME( TRANS, 'C' ) +C + IF( .NOT.TRAN .AND. .NOT.LSAME( TRANS, 'N' ) ) THEN + INFO = -1 + ELSE IF( M.LT.0 ) THEN + INFO = -2 + ELSE IF( N.LT.0 ) THEN + INFO = -3 + ELSE IF( LDA.LT.MAX( 1, N ) ) THEN + INFO = -5 + ELSE IF( LDB.LT.MAX( 1, M ) ) THEN + INFO = -8 + END IF +C + IF( INFO.NE.0 ) THEN + CALL XERBLA( 'MB02VD', -INFO ) + RETURN + END IF +C +C Compute the LU factorization of A. +C + CALL DGETRF( N, N, A, LDA, IPIV, INFO ) +C + IF( INFO.EQ.0 ) THEN + IF( TRAN ) THEN +C +C Compute X = B * A**(-T). +C + CALL MA02GD( M, B, LDB, 1, N, IPIV, 1 ) + CALL DTRSM( 'Right', 'Lower', 'Transpose', 'Unit', M, N, + $ ONE, A, LDA, B, LDB ) + CALL DTRSM( 'Right', 'Upper', 'Transpose', 'NonUnit', M, + $ N, ONE, A, LDA, B, LDB ) + ELSE +C +C Compute X = B * A**(-1). +C + CALL DTRSM( 'Right', 'Upper', 'NoTranspose', 'NonUnit', M, + $ N, ONE, A, LDA, B, LDB ) + CALL DTRSM( 'Right', 'Lower', 'NoTranspose', 'Unit', M, N, + $ ONE, A, LDA, B, LDB ) + CALL MA02GD( M, B, LDB, 1, N, IPIV, -1 ) + END IF + END IF + RETURN +C +C *** Last line of MB02VD *** + END Modified: trunk/octave-forge/main/control/src/Makefile =================================================================== --- trunk/octave-forge/main/control/src/Makefile 2010-10-01 13:27:35 UTC (rev 7789) +++ trunk/octave-forge/main/control/src/Makefile 2010-10-01 22:16:52 UTC (rev 7790) @@ -2,7 +2,7 @@ slsb01bd.oct slsb10fd.oct slsb10dd.oct slsb03md.oct slsb04md.oct \ slsb04qd.oct slsg03ad.oct slsb02od.oct slab13ad.oct slab01od.oct \ sltb01pd.oct slsb03od.oct slsg03bd.oct slag08bd.oct sltg01jd.oct \ - sltg01hd.oct sltg01id.oct \ + sltg01hd.oct sltg01id.oct slsg02ad.oct \ is_real_scalar.oct is_real_vector.oct is_real_matrix.oct \ is_real_square_matrix.oct @@ -161,6 +161,12 @@ TG01ID.f TB01XD.f MA02CD.f AB07MD.f TG01HX.f \ MA02BD.f +# solution of algebraic Riccati equations for descriptor systems +slsg02ad.oct: slsg02ad.cc + mkoctfile slsg02ad.cc \ + SG02AD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ + MB01SD.f MB02VD.f MB02PD.f MA02GD.f + # helpers is_real_scalar.oct: is_real_scalar.cc mkoctfile is_real_scalar.cc Added: trunk/octave-forge/main/control/src/SG02AD.f =================================================================== --- trunk/octave-forge/main/control/src/SG02AD.f (rev 0) +++ trunk/octave-forge/main/control/src/SG02AD.f 2010-10-01 22:16:52 UTC (rev 7790) @@ -0,0 +1,939 @@ + SUBROUTINE SG02AD( DICO, JOBB, FACT, UPLO, JOBL, SCAL, SORT, ACC, + $ N, M, P, A, LDA, E, LDE, B, LDB, Q, LDQ, R, + $ LDR, L, LDL, RCONDU, X, LDX, ALFAR, ALFAI, + $ BETA, S, LDS, T, LDT, U, LDU, TOL, IWORK, + $ DWORK, LDWORK, BWORK, IWARN, INFO ) +C +C SLICOT RELEASE 5.0. +C +C Copyright (c) 2002-2009 NICONET e.V. +C +C This program is free software: you can redistribute it and/or +C modify it under the terms of the GNU General Public License as +C published by the Free Software Foundation, either version 2 of +C the License, or (at your option) any later version. +C +C This program is distributed in the hope that it will be useful, +C but WITHOUT ANY WARRANTY; without even the implied warranty of +C MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +C GNU General Public License for more details. +C +C You should have received a copy of the GNU General Public License +C along with this program. If not, see +C <http://www.gnu.org/licenses/>. +C +C PURPOSE +C +C To solve for X either the continuous-time algebraic Riccati +C equation +C -1 +C Q + A'XE + E'XA - (L+E'XB)R (L+E'XB)' = 0 , (1) +C +C or the discrete-time algebraic Riccati equation +C -1 +C E'XE = A'XA - (L+A'XB)(R + B'XB) (L+A'XB)' + Q , (2) +C +C where A, E, B, Q, R, and L are N-by-N, N-by-N, N-by-M, N-by-N, +C M-by-M and N-by-M matrices, respectively, such that Q = C'C, +C R = D'D and L = C'D; X is an N-by-N symmetric matrix. +C The routine also returns the computed values of the closed-loop +C spectrum of the system, i.e., the stable eigenvalues +C lambda(1),...,lambda(N) of the pencil (A - BF,E), where F is +C the optimal gain matrix, +C -1 +C F = R (L+E'XB)' , for (1), +C +C and +C -1 +C F = (R+B'XB) (L+A'XB)' , for (2). +C -1 +C Optionally, matrix G = BR B' may be given instead of B and R. +C Other options include the case with Q and/or R given in a +C factored form, Q = C'C, R = D'D, and with L a zero matrix. +C +C The routine uses the method of deflating subspaces, based on +C reordering the eigenvalues in a generalized Schur matrix pair. +C +C It is assumed that E is nonsingular, but this condition is not +C checked. Note that the definition (1) of the continuous-time +C algebraic Riccati equation, and the formula for the corresponding +C optimal gain matrix, require R to be nonsingular, but the +C associated linear quadratic optimal problem could have a unique +C solution even when matrix R is singular, under mild assumptions +C (see METHOD). The routine SG02AD works accordingly in this case. +C +C ARGUMENTS +C +C Mode Parameters +C +C DICO CHARACTER*1 +C Specifies the type of Riccati equation to be solved as +C follows: +C = 'C': Equation (1), continuous-time case; +C = 'D': Equation (2), discrete-time case. +C +C JOBB CHARACTER*1 +C Specifies whether or not the matrix G is given, instead +C of the matrices B and R, as follows: +C = 'B': B and R are given; +C = 'G': G is given. +C +C FACT CHARACTER*1 +C Specifies whether or not the matrices Q and/or R (if +C JOBB = 'B') are factored, as follows: +C = 'N': Not factored, Q and R are given; +C = 'C': C is given, and Q = C'C; +C = 'D': D is given, and R = D'D; +C = 'B': Both factors C and D are given, Q = C'C, R = D'D. +C +C UPLO CHARACTER*1 +C If JOBB = 'G', or FACT = 'N', specifies which triangle of +C the matrices G, or Q and R, is stored, as follows: +C = 'U': Upper triangle is stored; +C = 'L': Lower triangle is stored. +C +C JOBL CHARACTER*1 +C Specifies whether or not the matrix L is zero, as follows: +C = 'Z': L is zero; +C = 'N': L is nonzero. +C JOBL is not used if JOBB = 'G' and JOBL = 'Z' is assumed. +C SLICOT Library routine SB02MT should be called just before +C SG02AD, for obtaining the results when JOBB = 'G' and +C JOBL = 'N'. +C +C SCAL CHARACTER*1 +C If JOBB = 'B', specifies whether or not a scaling strategy +C should be used to scale Q, R, and L, as follows: +C = 'G': General scaling should be used; +C = 'N': No scaling should be used. +C SCAL is not used if JOBB = 'G'. +C +C SORT CHARACTER*1 +C Specifies which eigenvalues should be obtained in the top +C of the generalized Schur form, as follows: +C = 'S': Stable eigenvalues come first; +C = 'U': Unstable eigenvalues come first. +C +C ACC CHARACTER*1 +C Specifies whether or not iterative refinement should be +C used to solve the system of algebraic equations giving +C the solution matrix X, as follows: +C = 'R': Use iterative refinement; +C = 'N': Do not use iterative refinement. +C +C Input/Output Parameters +C +C N (input) INTEGER +C The actual state dimension, i.e., the order of the +C matrices A, E, Q, and X, and the number of rows of the +C matrices B and L. N >= 0. +C +C M (input) INTEGER +C The number of system inputs. If JOBB = 'B', M is the +C order of the matrix R, and the number of columns of the +C matrix B. M >= 0. +C M is not used if JOBB = 'G'. +C +C P (input) INTEGER +C The number of system outputs. If FACT = 'C' or 'D' or 'B', +C P is the number of rows of the matrices C and/or D. +C P >= 0. +C Otherwise, P is not used. +C +C A (input) DOUBLE PRECISION array, dimension (LDA,N) +C The leading N-by-N part of this array must contain the +C state matrix A of the descriptor system. +C +C LDA INTEGER +C The leading dimension of array A. LDA >= MAX(1,N). +C +C E (input) DOUBLE PRECISION array, dimension (LDE,N) +C The leading N-by-N part of this array must contain the +C matrix E of the descriptor system. +C +C LDE INTEGER +C The leading dimension of array E. LDE >= MAX(1,N). +C +C B (input) DOUBLE PRECISION array, dimension (LDB,*) +C If JOBB = 'B', the leading N-by-M part of this array must +C contain the input matrix B of the system. +C If JOBB = 'G', the leading N-by-N upper triangular part +C (if UPLO = 'U') or lower triangular part (if UPLO = 'L') +C of this array must contain the upper triangular part or +C lower triangular part, respectively, of the matrix +C -1 +C G = BR B'. The stricly lower triangular part (if +C UPLO = 'U') or stricly upper triangular part (if +C UPLO = 'L') is not referenced. +C +C LDB INTEGER +C The leading dimension of array B. LDB >= MAX(1,N). +C +C Q (input) DOUBLE PRECISION array, dimension (LDQ,N) +C If FACT = 'N' or 'D', the leading N-by-N upper triangular +C part (if UPLO = 'U') or lower triangular part (if UPLO = +C 'L') of this array must contain the upper triangular part +C or lower triangular part, respectively, of the symmetric +C state weighting matrix Q. The stricly lower triangular +C part (if UPLO = 'U') or stricly upper triangular part (if +C UPLO = 'L') is not referenced. +C If FACT = 'C' or 'B', the leading P-by-N part of this +C array must contain the output matrix C of the system. +C If JOBB = 'B' and SCAL = 'G', then Q is modified +C internally, but is restored on exit. +C +C LDQ INTEGER +C The leading dimension of array Q. +C LDQ >= MAX(1,N) if FACT = 'N' or 'D'; +C LDQ >= MAX(1,P) if FACT = 'C' or 'B'. +C +C R (input) DOUBLE PRECISION array, dimension (LDR,*) +C If FACT = 'N' or 'C', the leading M-by-M upper triangular +C part (if UPLO = 'U') or lower triangular part (if UPLO = +C 'L') of this array must contain the upper triangular part +C or lower triangular part, respectively, of the symmetric +C input weighting matrix R. The stricly lower triangular +C part (if UPLO = 'U') or stricly upper triangular part (if +C UPLO = 'L') is not referenced. +C If FACT = 'D' or 'B', the leading P-by-M part of this +C array must contain the direct transmission matrix D of the +C system. +C If JOBB = 'B' and SCAL = 'G', then R is modified +C internally, but is restored on exit. +C If JOBB = 'G', this array is not referenced. +C +C LDR INTEGER +C The leading dimension of array R. +C LDR >= MAX(1,M) if JOBB = 'B' and FACT = 'N' or 'C'; +C LDR >= MAX(1,P) if JOBB = 'B' and FACT = 'D' or 'B'; +C LDR >= 1 if JOBB = 'G'. +C +C L (input) DOUBLE PRECISION array, dimension (LDL,*) +C If JOBL = 'N' and JOBB = 'B', the leading N-by-M part of +C this array must contain the cross weighting matrix L. +C If JOBB = 'B' and SCAL = 'G', then L is modified +C internally, but is restored on exit. +C If JOBL = 'Z' or JOBB = 'G', this array is not referenced. +C +C LDL INTEGER +C The leading dimension of array L. +C LDL >= MAX(1,N) if JOBL = 'N' and JOBB = 'B'; +C LDL >= 1 if JOBL = 'Z' or JOBB = 'G'. +C +C RCONDU (output) DOUBLE PRECISION +C If N > 0 and INFO = 0 or INFO = 7, an estimate of the +C reciprocal of the condition number (in the 1-norm) of +C the N-th order system of algebraic equations from which +C the solution matrix X is obtained. +C +C X (output) DOUBLE PRECISION array, dimension (LDX,N) +C If INFO = 0, the leading N-by-N part of this array +C contains the solution matrix X of the problem. +C +C LDX INTEGER +C The leading dimension of array X. LDX >= MAX(1,N). +C +C ALFAR (output) DOUBLE PRECISION array, dimension (2*N) +C ALFAI (output) DOUBLE PRECISION array, dimension (2*N) +C BETA (output) DOUBLE PRECISION array, dimension (2*N) +C The generalized eigenvalues of the 2N-by-2N matrix pair, +C ordered as specified by SORT (if INFO = 0, or INFO >= 5). +C For instance, if SORT = 'S', the leading N elements of +C these arrays contain the closed-loop spectrum of the +C system. Specifically, +C lambda(k) = [ALFAR(k)+j*ALFAI(k)]/BETA(k) for +C k = 1,2,...,N. +C +C S (output) DOUBLE PRECISION array, dimension (LDS,*) +C The leading 2N-by-2N part of this array contains the +C ordered real Schur form S of the first matrix in the +C reduced matrix pencil associated to the optimal problem, +C corresponding to the scaled Q, R, and L, if JOBB = 'B' +C and SCAL = 'G'. That is, +C +C (S S ) +C ( 11 12) +C S = ( ), +C (0 S ) +C ( 22) +C +C where S , S and S are N-by-N matrices. +C 11 12 22 +C Array S must have 2*N+M columns if JOBB = 'B', and 2*N +C columns, otherwise. +C +C LDS INTEGER +C The leading dimension of array S. +C LDS >= MAX(1,2*N+M) if JOBB = 'B'; +C LDS >= MAX(1,2*N) if JOBB = 'G'. +C +C T (output) DOUBLE PRECISION array, dimension (LDT,2*N) +C The leading 2N-by-2N part of this array contains the +C ordered upper triangular form T of the second matrix in +C the reduced matrix pencil associated to the optimal +C problem, corresponding to the scaled Q, R, and L, if +C JOBB = 'B' and SCAL = 'G'. That is, +C +C (T T ) +C ( 11 12) +C T = ( ), +C (0 T ) +C ( 22) +C +C where T , T and T are N-by-N matrices. +C 11 12 22 +C +C LDT INTEGER +C The leading dimension of array T. +C LDT >= MAX(1,2*N+M) if JOBB = 'B'; +C LDT >= MAX(1,2*N) if JOBB = 'G'. +C +C U (output) DOUBLE PRECISION array, dimension (LDU,2*N) +C The leading 2N-by-2N part of this array contains the right +C transformation matrix U which reduces the 2N-by-2N matrix +C pencil to the ordered generalized real Schur form (S,T). +C That is, +C +C (U U ) +C ( 11 12) +C U = ( ), +C (U U ) +C ( 21 22) +C +C where U , U , U and U are N-by-N matrices. +C 11 12 21 22 +C If JOBB = 'B' and SCAL = 'G', then U corresponds to the +C scaled pencil. If a basis for the stable deflating +C subspace of the original problem is needed, then the +C submatrix U must be multiplied by the scaling factor +C 21 +C contained in DWORK(4). +C +C LDU INTEGER +C The leading dimension of array U. LDU >= MAX(1,2*N). +C +C Tolerances +C +C TOL DOUBLE PRECISION +C The tolerance to be used to test for near singularity of +C the original matrix pencil, specifically of the triangular +C M-by-M factor obtained during the reduction process. If +C the user sets TOL > 0, then the given value of TOL is used +C as a lower bound for the reciprocal condition number of +C that matrix; a matrix whose estimated condition number is +C less than 1/TOL is considered to be nonsingular. If the +C user sets TOL <= 0, then a default tolerance, defined by +C TOLDEF = EPS, is used instead, where EPS is the machine +C precision (see LAPACK Library routine DLAMCH). +C This parameter is not referenced if JOBB = 'G'. +C +C Workspace +C +C IWORK INTEGER array, dimension (LIWORK) +C LIWORK >= MAX(1,M,2*N) if JOBB = 'B'; +C LIWORK >= MAX(1,2*N) if JOBB = 'G'. +C +C DWORK DOUBLE PRECISION array, dimension (LDWORK) +C On exit, if INFO = 0, DWORK(1) returns the optimal value +C of LDWORK. If JOBB = 'B' and N > 0, DWORK(2) returns the +C reciprocal of the condition number of the M-by-M bottom +C right lower triangular matrix obtained while compressing +C the matrix pencil of order 2N+M to obtain a pencil of +C order 2N. If ACC = 'R', and INFO = 0 or INFO = 7, DWORK(3) +C returns the reciprocal pivot growth factor (see SLICOT +C Library routine MB02PD) for the LU factorization of the +C coefficient matrix of the system of algebraic equations +C giving the solution matrix X; if DWORK(3) is much +C less than 1, then the computed X and RCONDU could be +C unreliable. If INFO = 0 or INFO = 7, DWORK(4) returns the +C scaling factor used to scale Q, R, and L. DWORK(4) is set +C to 1 if JOBB = 'G' or SCAL = 'N'. +C +C LDWORK INTEGER +C The length of the array DWORK. +C LDWORK >= MAX(7*(2*N+1)+16,16*N), if JOBB = 'G'; +C LDWORK >= MAX(7*(2*N+1)+16,16*N,2*N+M,3*M), if JOBB = 'B'. +C For optimum performance LDWORK should be larger. +C +C BWORK LOGICAL array, dimension (2*N) +C +C Warning Indicator +C +C IWARN INTEGER +C = 0: no warning; +C = 1: the computed solution may be inaccurate due to poor +C scaling or eigenvalues too close to the boundary of +C the stability domain (the imaginary axis, if +C DICO = 'C', or the unit circle, if DICO = 'D'). +C +C Error Indicator +C +C INFO INTEGER +C = 0: successful exit; +C < 0: if INFO = -i, the i-th argument had an illegal +C value; +C = 1: if the computed extended matrix pencil is singular, +C possibly due to rounding errors; +C = 2: if the QZ algorithm failed; +C = 3: if reordering of the generalized eigenvalues failed; +C = 4: if after reordering, roundoff changed values of +C some complex eigenvalues so that leading eigenvalues +C in the generalized Schur form no longer satisfy the +C stability condition; this could also be caused due +C to scaling; +C = 5: if the computed dimension of the solution does not +C equal N; +C = 6: if the spectrum is too close to the boundary of +C the stability domain; +C = 7: if a singular matrix was encountered during the +C computation of the solution matrix X. +C +C METHOD +C +C The routine uses a variant of the method of deflating subspaces +C proposed by van Dooren [1]. See also [2], [3], [4]. +C It is assumed that E is nonsingular, the triple (E,A,B) is +C strongly stabilizable and detectable (see [3]); if, in addition, +C +C - [ Q L ] +C R := [ ] >= 0 , +C [ L' R ] +C +C then the pencils +C +C discrete-time continuous-time +C +C |A 0 B| |E 0 0| |A 0 B| |E 0 0| +C |Q -E' L| - z |0 -A' 0| , |Q A' L| - s |0 -E' 0| , (3) +C |L' 0 R| |0 -B' 0| |L' B' R| |0 0 0| +C +C are dichotomic, i.e., they have no eigenvalues on the boundary of +C the stability domain. The above conditions are sufficient for +C regularity of these pencils. A necessary condition is that +C rank([ B' L' R']') = m. +C +C Under these assumptions the algebraic Riccati equation is known to +C have a unique non-negative definite solution. +C The first step in the method of deflating subspaces is to form the +C extended matrices in (3), of order 2N + M. Next, these pencils are +C compressed to a form of order 2N (see [1]) +C +C lambda x A - B . +C f f +C +C This generalized eigenvalue problem is then solved using the QZ +C algorithm and the stable deflating subspace Ys is determined. +C If [Y1'|Y2']' is a basis for Ys, then the required solution is +C -1 +C X = Y2 x Y1 . +C +C REFERENCES +C +C [1] Van Dooren, P. +C A Generalized Eigenvalue Approach for Solving Riccati +C Equations. +C SIAM J. Sci. Stat. Comp., 2, pp. 121-135, 1981. +C +C [2] Arnold, III, W.F. and Laub, A.J. +C Generalized Eigenproblem Algorithms and Software for +C Algebraic Riccati Equations. +C Proc. IEEE, 72, 1746-1754, 1984. +C +C [3] Mehrmann, V. +C The Autonomous Linear Quadratic Control Problem. Theory and +C Numerical Solution. +C Lect. Notes in Control and Information Sciences, vol. 163, +C Springer-Verlag, Berlin, 1991. +C +C [4] Sima, V. +C Algorithms for Linear-Quadratic Optimization. +C Pure and Applied Mathematics: A Series of Monographs and +C Textbooks, vol. 200, Marcel Dekker, Inc., New York, 1996. +C +C NUMERICAL ASPECTS +C +C This routine is particularly suited for systems where the matrix R +C is ill-conditioned, or even singular. +C +C FURTHER COMMENTS +C +C To obtain a stabilizing solution of the algebraic Riccati +C equations set SORT = 'S'. +C +C The routine can also compute the anti-stabilizing solutions of +C the algebraic Riccati equations, by specifying SORT = 'U'. +C +C CONTRIBUTOR +C +C V. Sima, Katholieke Univ. Leuven, Belgium, June 2002. +C +C REVISIONS +C +C V. Sima, Katholieke Univ. Leuven, Belgium, September 2002, +C December 2002. +C +C KEYWORDS +C +C Algebraic Riccati equation, closed loop system, continuous-time +C system, discrete-time system, optimal regulator, Schur form. +C +C ****************************************************************** +C +C .. Parameters .. + DOUBLE PRECISION ZERO, HALF, ONE, P1, FOUR + PARAMETER ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0, + $ P1 = 0.1D0, FOUR = 4.0D0 ) +C .. Scalar Arguments .. + CHARACTER ACC, DICO, FACT, JOBB, JOBL, SCAL, SORT, UPLO + INTEGER INFO, IWARN, LDA, LDB, LDE, LDL, LDQ, LDR, LDS, + $ LDT, LDU, LDWORK, LDX, M, N, P + DOUBLE PRECISION RCONDU, TOL +C .. Array Arguments .. + LOGICAL BWORK(*) + INTEGER IWORK(*) + DOUBLE PRECISION A(LDA,*), ALFAI(*), ALFAR(*), B(LDB,*), BETA(*), + $ DWORK(*), E(LDE,*), L(LDL,*), Q(LDQ,*), + $ R(LDR,*), S(LDS,*), T(LDT,*), U(LDU,*), X(LDX,*) +C .. Local Scalars .. + CHARACTER EQUED, QTYPE, RTYPE + LOGICAL COLEQU, DISCR, LFACB, LFACN, LFACQ, LFACR, + $ LJOBB, LJOBL, LJOBLN, LSCAL, LSORT, LUPLO, + $ REFINE, ROWEQU + INTEGER I, INFO1, IW, IWB, IWC, IWF, IWR, J, LDW, MP, + $ NDIM, NN, NNM, NP, NP1, WRKOPT + DOUBLE PRECISION ASYM, EPS, PIVOTU, RCONDL, RNORM, SCALE, SEPS, + $ U12M, UNORM +C .. External Functions .. + LOGICAL LSAME, SB02OU, SB02OV, SB02OW + DOUBLE PRECISION DLAMCH, DLANGE, DLANSY + EXTERNAL DLAMCH, DLANGE, DLANSY, LSAME, SB02OU, SB02OV, + $ SB02OW +C .. External Subroutines .. + EXTERNAL DAXPY, DCOPY, DGECON, DGEMM, DGEQRF, DGGES, + $ DLACPY, DLASCL, DLASET, DORGQR, DSCAL, DSWAP, + $ MB01SD, MB02PD, MB02VD, SB02OY, XERBLA +C .. Intrinsic Functions .. + INTRINSIC ABS, INT, MAX, SQRT +C .. Executable Statements .. +C + IWARN = 0 + INFO = 0 + DISCR = LSAME( DICO, 'D' ) + LJOBB = LSAME( JOBB, 'B' ) + LFACN = LSAME( FACT, 'N' ) + LFACQ = LSAME( FACT, 'C' ) + LFACR = LSAME( FACT, 'D' ) + LFACB = LSAME( FACT, 'B' ) + LUPLO = LSAME( UPLO, 'U' ) + LSORT = LSAME( SORT, 'S' ) + REFINE = LSAME( ACC, 'R' ) + NN = 2*N + IF ( LJOBB ) THEN + LJOBL = LSAME( JOBL, 'Z' ) + LJOBLN = LSAME( JOBL, 'N' ) + LSCAL = LSAME( SCAL, 'G' ) + NNM = NN + M + LDW = MAX( NNM, 3*M ) + ELSE + LSCAL = .FALSE. + NNM = NN + LDW = 1 + END IF + NP1 = N + 1 +C +C Test the input scalar arguments. +C + IF( .NOT.DISCR .AND. .NOT.LSAME( DICO, 'C' ) ) THEN + INFO = -1 + ELSE IF( .NOT.LJOBB .AND. .NOT.LSAME( JOBB, 'G' ) ) THEN + INFO = -2 + ELSE IF( .NOT.LFACQ .AND. .NOT.LFACR .AND. .NOT.LFACB + $ .AND. .NOT.LFACN ) THEN + INFO = -3 + ELSE IF( .NOT.LJOBB .OR. LFACN ) THEN + IF( .NOT.LUPLO .AND. .NOT.LSAME( UPLO, 'L' ) ) + $ INFO = -4 + END IF + IF( INFO.EQ.0 .AND. LJOBB ) THEN + IF( .NOT.LJOBL .AND. .NOT.LJOBLN ) THEN + INFO = -5 + ELSE IF( .NOT.LSCAL .AND. .NOT. LSAME( SCAL, 'N' ) ) THEN + INFO = -6 + END IF + END IF + IF( INFO.EQ.0 ) THEN + IF( .NOT.LSORT .AND. .NOT.LSAME( SORT, 'U' ) ) THEN + INFO = -7 + ELSE IF( .NOT.REFINE .AND. .NOT.LSAME( ACC, 'N' ) ) THEN + INFO = -8 + ELSE IF( N.LT.0 ) THEN + INFO = -9 + ELSE IF( LJOBB ) THEN + IF( M.LT.0 ) + $ INFO = -10 + END IF + END IF + IF( INFO.EQ.0 .AND. .NOT.LFACN ) THEN + IF( P.LT.0 ) + $ INFO = -11 + END IF + IF( INFO.EQ.0 ) THEN + IF( LDA.LT.MAX( 1, N ) ) THEN + INFO = -13 + ELSE IF( LDE.LT.MAX( 1, N ) ) THEN + INFO = -15 + ELSE IF( LDB.LT.MAX( 1, N ) ) THEN + INFO = -17 + ELSE IF( ( ( LFACN.OR.LFACR ) .AND. LDQ.LT.MAX( 1, N ) ) .OR. + $ ( ( LFACQ.OR.LFACB ) .AND. LDQ.LT.MAX( 1, P ) ) ) THEN + INFO = -19 + ELSE IF( LJOBB ) THEN + IF ( ( LFACN.OR.LFACQ ) .AND. LDR.LT.MAX( 1, M ) .OR. + $ ( LFACR.OR.LFACB ) .AND. LDR.LT.MAX( 1, P ) ) THEN + INFO = -21 + ELSE IF( ( LJOBLN .AND. LDL.LT.MAX( 1, N ) ) .OR. + $ ( LJOBL .AND. LDL.LT.1 ) ) THEN + INFO = -23 + END IF + ELSE + IF( LDR.LT.1 ) THEN + INFO = -21 + ELSE IF( LDL.LT.1 ) THEN + INFO = -23 + END IF + END IF + END IF + IF( INFO.EQ.0 ) THEN + IF( LDX.LT.MAX( 1, N ) ) THEN + INFO = -26 + ELSE IF( LDS.LT.MAX( 1, NNM ) ) THEN + INFO = -31 + ELSE IF( LDT.LT.MAX( 1, NNM ) ) THEN + INFO = -33 + ELSE IF( LDU.LT.MAX( 1, NN ) ) THEN + INFO = -35 + ELSE IF( LDWORK.LT.MAX( 14*N + 23, 16*N, LDW ) ) THEN + INFO = -39 + END IF + END IF +C + IF ( INFO.NE.0 ) THEN +C +C Error return. +C + CALL XERBLA( 'SG02AD', -INFO ) + RETURN + END IF +C +C Quick return if possible. +C + IF ( N.EQ.0 ) THEN + DWORK(1) = FOUR + DWORK(4) = ONE + RETURN + END IF +C +C Start computations. +C +C (Note: Comments in the code beginning "Workspace:" describe the +C minimal amount of real workspace needed at that point in the +C code, as well as the preferred amount for good performance. +C NB refers to the optimal block size for the immediately +C following subroutine, as returned by ILAENV.) +C + LSCAL = LSCAL .AND. LJOBB + IF ( LSCAL ) THEN +C +C Scale the matrices Q, R (or G), and L so that +C norm(Q) + norm(R) + norm(L) = 1, +C using the 1-norm. If Q and/or R are factored, the norms of +C the factors are used. +C Workspace: need max(N,M), if FACT = 'N'; +C N, if FACT = 'D'; +C M, if FACT = 'C'. +C + IF ( LFACN .OR. LFACR ) THEN + SCALE = DLANSY( '1-norm', UPLO, N, Q, LDQ, DWORK ) + QTYPE = UPLO + NP = N + ELSE + SCALE = DLANGE( '1-norm', P, N, Q, LDQ, DWORK ) + QTYPE = 'G' + NP = P + END IF +C + IF ( LFACN .OR. LFACQ ) THEN + RNORM = DLANSY( '1-norm', UPLO, M, R, LDR, DWORK ) + RTYPE = UPLO + MP = M + ELSE + RNORM = DLANGE( '1-norm', P, M, R, LDR, DWORK ) + RTYPE = 'G' + MP = P + END IF + SCALE = SCALE + RNORM +C + IF ( LJOBLN ) + $ SCALE = SCALE + DLANGE( '1-norm', N, M, L, LDL, DWORK ) + IF ( SCALE.EQ.ZERO ) + $ SCALE = ONE +C + CALL DLASCL( QTYPE, 0, 0, SCALE, ONE, NP, N, Q, LDQ, INFO1 ) + CALL DLASCL( RTYPE, 0, 0, SCALE, ONE, MP, M, R, LDR, INFO1 ) + IF ( LJOBLN ) + $ CALL DLASCL( 'G', 0, 0, SCALE, ONE, N, M, L, LDL, INFO1 ) + ELSE + SCALE = ONE + END IF +C +C Construct the extended matrix pair. +C Workspace: need 1, if JOBB = 'G', +C max(1,2*N+M,3*M), if JOBB = 'B'; +C prefer larger. +C + CALL SB02OY( 'Optimal control', DICO, JOBB, FACT, UPLO, JOBL, + $ 'Not identity E', N, M, P, A, LDA, B, LDB, Q, LDQ, R, + $ LDR, L, LDL, E, LDE, S, LDS, T, LDT, TOL, IWORK, + $ DWORK, LDWORK, INFO ) +C + IF ( LSCAL ) THEN +C +C Undo scaling of the data arrays. +C + CALL DLASCL( QTYPE, 0, 0, ONE, SCALE, NP, N, Q, LDQ, INFO1 ) + CALL DLASCL( RTYPE, 0, 0, ONE, SCALE, MP, M, R, LDR, INFO1 ) + IF ( LJOBLN ) + $ CALL DLASCL( 'G', 0, 0, ONE, SCALE, N, M, L, LDL, INFO1 ) + END IF +C + IF ( INFO.NE.0 ) + $ RETURN + WRKOPT = DWORK(1) + IF ( LJOBB ) + $ RCONDL = DWORK(2) +C +C Workspace: need max(7*(2*N+1)+16,16*N); +C prefer larger. +C + IF ( DISCR ) THEN + IF ( LSORT ) THEN +C +C The natural tendency of the QZ algorithm to get the largest +C eigenvalues in the leading part of the matrix pair is +C exploited, by computing the unstable eigenvalues of the +C permuted matrix pair. +C + CALL DGGES( 'No vectors', 'Vectors', 'Sort', SB02OV, NN, T, + $ LDT, S, LDS, NDIM, ALFAR, ALFAI, BETA, U, LDU, + $ U, LDU, DWORK, LDWORK, BWORK, INFO1 ) + CALL DSWAP( N, ALFAR(NP1), 1, ALFAR, 1 ) + CALL DSWAP( N, ALFAI(NP1), 1, ALFAI, 1 ) + CALL DSWAP( N, BETA (NP1), 1, BETA , 1 ) + ELSE + CALL DGGES( 'No vectors', 'Vectors', 'Sort', SB02OV, NN, S, + $ LDS, T, LDT, NDIM, ALFAR, ALFAI, BETA, U, LDU, + $ U, LDU, DWORK, LDWORK, BWORK, INFO1 ) + END IF + ELSE + IF ( LSORT ) THEN + CALL DGGES( 'No vectors', 'Vectors', 'Sort', SB02OW, NN, S, + $ LDS, T, LDT, NDIM, ALFAR, ALFAI, BETA, U, LDU, + $ U, LDU, DWORK, LDWORK, BWORK, INFO1 ) + ELSE + CALL DGGES( 'No vectors', 'Vectors', 'Sort', SB02OU, NN, S, + $ LDS, T, LDT, NDIM, ALFAR, ALFAI, BETA, U, LDU, + $ U, LDU, DWORK, LDWORK, BWORK, INFO1 ) + END IF + END IF + IF ( INFO1.GT.0 .AND. INFO1.LE.NN+1 ) THEN + INFO = 2 + ELSE IF ( INFO1.EQ.NN+2 ) THEN + INFO = 4 + ELSE IF ( INFO1.EQ.NN+3 ) THEN + INFO = 3 + ELSE IF ( NDIM.NE.N ) THEN + INFO = 5 + END IF + IF ( INFO.NE.0 ) + $ RETURN + WRKOPT = MAX( WRKOPT, INT( DWORK(1) ) ) +C +C Take the non-identity matrix E into account and orthogonalize the +C basis. Use the array X as workspace. +C Workspace: need N; +C prefer N*NB. +C + CALL DGEMM( 'No transpose', 'No transpose', N, N, N, ONE, E, LDE, + $ U, LDU, ZERO, X, LDX ) + CALL DLACPY( 'Full', N, N, X, LDX, U, LDU ) + CALL DGEQRF( NN, N, U, LDU, X, DWORK, LDWORK, INFO1 ) + WRKOPT = MAX( WRKOPT, INT( DWORK(1) ) ) + CALL DORGQR( NN, N, N, U, LDU, X, DWORK, LDWORK, INFO1 ) + WRKOPT = MAX( WRKOPT, INT( DWORK(1) ) ) +C +C Check for the symmetry of the solution. The array X is again used +C as workspace. +C + CALL DGEMM( 'Transpose', 'No transpose', N, N, N, ONE, U, LDU, + $ U(NP1,1), LDU, ZERO, X, LDX ) + U12M = ZERO + ASYM = ZERO +C + DO 20 J = 1, N +C + DO 10 I = 1, N + U12M = MAX( U12M, ABS( X(I,J) ) ) + ASYM = MAX( ASYM, ABS( X(I,J) - X(J,I) ) ) + 10 CONTINUE +C + 20 CONTINUE +C + EPS = DLAMCH( 'Epsilon' ) + SEPS = SQRT( EPS ) + ASYM = ASYM - SEPS + IF ( ASYM.GT.P1*U12M ) THEN + INFO = 6 + RETURN + ELSE IF ( ASYM.GT.SEPS ) THEN + IWARN = 1 + END IF +C +C Compute the solution of X*U(1,1) = U(2,1). Use the (2,1) block +C of S as a workspace for factoring U(1,1). +C + IF ( REFINE ) THEN +C +C Use LU factorization and iterative refinement for finding X. +C Workspace: need 8*N. +C +C First transpose U(2,1) in-situ. +C + DO 30 I = 1, N - 1 + CALL DSWAP( N-I, U(N+I,I+1), LDU, U(N+I+1,I), 1 ) + 30 CONTINUE +C + IWR = 1 + IWC = IWR + N + IWF = IWC + N + IWB = IWF + N + IW = IWB + N +C + CALL MB02PD( 'Equilibrate', 'Transpose', N, N, U, LDU, + $ S(NP1,1), LDS, IWORK, EQUED, DWORK(IWR), + $ DWORK(IWC), U(NP1,1), LDU, X, LDX, RCONDU, + $ DWORK(IWF), DWORK(IWB), IWORK(NP1), DWORK(IW), + $ INFO1 ) +C +C Transpose U(2,1) back in-situ. +C + DO 40 I = 1, N - 1 + CALL DSWAP( N-I, U(N+I,I+1), LDU, U(N+I+1,I), 1 ) + 40 CONTINUE +C + IF( .NOT.LSAME( EQUED, 'N' ) ) THEN +C +C Undo the equilibration of U(1,1) and U(2,1). +C + ROWEQU = LSAME( EQUED, 'R' ) .OR. LSAME( EQUED, 'B' ) + COLEQU = LSAME( EQUED, 'C' ) .OR. LSAME( EQUED, 'B' ) +C + IF( ROWEQU ) THEN +C + DO 50 I = 0, N - 1 + DWORK(IWR+I) = ONE / DWORK(IWR+I) + 50 CONTINUE +C + CALL MB01SD( 'Row scaling', N, N, U, LDU, DWORK(IWR), + $ DWORK(IWC) ) + END IF +C + IF( COLEQU ) THEN +C + DO 60 I = 0, N - 1 + DWORK(IWC+I) = ONE / DWORK(IWC+I) + 60 CONTINUE +C + CALL MB01SD( 'Column scaling', NN, N, U, LDU, DWORK(IWR), + $ DWORK(IWC) ) + END IF + END IF +C + PIVOTU = DWORK(IW) +C + IF ( INFO1.GT.0 ) THEN +C +C Singular matrix. Set INFO and DWORK for error return. +C + INFO = 7 + GO TO 80 + END IF +C + ELSE +C +C Use LU factorization and a standard solution algorithm. +C + CALL DLACPY( 'Full', N, N, U, LDU, S(NP1,1), LDS ) + CALL DLACPY( 'Full', N, N, U(NP1,1), LDU, X, LDX ) +C +C Solve the system X*U(1,1) = U(2,1). +C + CALL MB02VD( 'No Transpose', N, N, S(NP1,1), LDS, IWORK, X, + $ LDX, INFO1 ) +C + IF ( INFO1.NE.0 ) THEN + INFO = 7 + RCONDU = ZERO + GO TO 80 + ELSE +C +C Compute the norm of U(1,1). +C + UNORM = DLANGE( '1-norm', N, N, U, LDU, DWORK ) +C +C Estimate the reciprocal condition of U(1,1). +C Workspace: need 4*N. +C + CALL DGECON( '1-norm', N, S(NP1,1), LDS, UNORM, RCONDU, + $ DWORK, IWORK(NP1), INFO ) +C + IF ( RCONDU.LT.EPS ) THEN +C +C Nearly singular matrix. Set IWARN for warning indication. +C + IWARN = 1 + END IF + WRKOPT = MAX( WRKOPT, 4*N ) + END IF + END IF +C +C Set S(2,1) to zero. +C + CALL DLASET( 'Full', N, N, ZERO, ZERO, S(NP1,1), LDS ) +C +C Make sure the solution matrix X is symmetric. +C + DO 70 I = 1, N - 1 + CALL DAXPY( N-I, ONE, X(I,I+1), LDX, X(I+1,I), 1 ) + CALL DSCAL( N-I, HALF, X(I+1,I), 1 ) + CALL DCOPY( N-I, X(I+1,I), 1, X(I,I+1), LDX ) + 70 CONTINUE +C + IF ( LSCAL ) THEN +C +C Undo scaling for the solution X. +C + CALL DLASCL( 'G', 0, 0, ONE, SCALE, N, N, X, LDX, INFO1 ) + END IF +C + DWORK(1) = WRKOPT +C + 80 CONTINUE + IF ( LJOBB ) + $ DWORK(2) = RCONDL + IF ( REFINE ) + $ DWORK(3) = PIVOTU + DWORK(4) = SCALE +C + RETURN +C *** Last line of SG02AD *** + END Modified: trunk/octave-forge/main/control/src/makefile_lqr.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_lqr.m 2010-10-01 13:27:35 UTC (rev 7789) +++ trunk/octave-forge/main/control/src/makefile_lqr.m 2010-10-01 22:16:52 UTC (rev 7790) @@ -15,4 +15,9 @@ SB02OD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ SB02MR.f SB02MV.f +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsg02ad.cc \ + SG02AD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ + MB01SD.f MB02VD.f MB02PD.f MA02GD.f + cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/src/slsg02ad.cc =================================================================== --- trunk/octave-forge/main/control/src/slsg02ad.cc (rev 0) +++ trunk/octave-forge/main/control/src/slsg02ad.cc 2010-10-01 22:16:52 UTC (rev 7790) @@ -0,0 +1,213 @@ +/* + +Copyright (C) 2010 Lukas F. Reichlin + +This file is part of LTI Syncope. + +LTI Syncope is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +LTI Syncope is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program. If not, see <http://www.gnu.org/licenses/>. + +Solution of algebraic Riccati equations for descriptor systems. +Uses SLICOT SG02AD by courtesy of NICONET e.V. +<http://www.slicot.org> + +Author: Lukas Reichlin <luk...@gm...> +Created: October 2010 +Version: 0.1 + +*/ + +#include <octave/oct.h> +#include <f77-fcn.h> +#include "common.cc" +#include <complex> + +extern "C" +{ + int F77_FUNC (sg02ad, SG02AD) + (char& DICO, char& JOBB, + char& FACT, char& UPLO, + char& JOBL, char& SCAL, + char& SORT, char& ACC, + int& N, int& M, int& P, + double* A, int& LDA, + double* E, int& LDE, + double* B, int& LDB, + double* Q, int& LDQ, + double* R, int& LDR, + double* L, int& LDL, + double& RCONDU, + double* X, int& LDX, + double* ALFAR, double* ALFAI, + double* BETA, + double* S, int& LDS, + double* T, int& LDT, + double* U, int& LDU, + double& TOL, + int* IWORK, + double* DWORK, int& LDWORK, + bool* BWORK, + int& IWARN, int& INFO); +} + +DEFUN_DLD (slsg02ad, args, nargout, + "-*- texinfo -*-\n\ +Slicot SG02AD Release 5.0\n\ +No argument checking.\n\ +For internal use only.") +{ + int nargin = args.length (); + octave_value_list retval; + + if (nargin != 8) + { + print_usage (); + } + else + { + // arguments in + char dico; + char jobb = 'B'; + char fact = 'N'; + char uplo = 'U'; + char jobl; + char scal = 'N'; + char sort = 'S'; + char acc = 'N'; + + Matrix a = args(0).matrix_value (); + Matrix e = args(1).matrix_value (); + Matrix b = args(2).matrix_value (); + Matrix q = args(3).matrix_value (); + Matrix r = args(4).matrix_value (); + Matrix l = args(5).matrix_value (); + int discrete = args(6).int_value (); + int ijobl = args(7).int_value (); + + if (discrete == 0) + dico = 'C'; + else + dico = 'D'; + + if (ijobl == 0) + jobl = 'Z'; + else + jobl = 'N'; + + int n = a.rows (); // n: number of states + int m = b.columns (); // m: number of inputs + int p = 0; // p: number of outputs, not used because FACT = 'N' + + int lda = max (1, n); + int lde = max (1, n); + int ldb = max (1, n); + int ldq = max (1, n); + int ldr = max (1, m); + int ldl = max (1, n); + + // arguments out + double rcondu; + + int ldx = max (1, n); + Matrix x (ldx, n); + + int nu = 2*n; + ColumnVector alfar (nu); + ColumnVector alfai (nu); + ColumnVector be... [truncated message content] |
From: <par...@us...> - 2010-10-03 07:58:19
|
Revision: 7796 http://octave.svn.sourceforge.net/octave/?rev=7796&view=rev Author: paramaniac Date: 2010-10-03 07:58:11 +0000 (Sun, 03 Oct 2010) Log Message: ----------- control: style fixes Modified Paths: -------------- trunk/octave-forge/main/control/INDEX trunk/octave-forge/main/control/inst/@lti/feedback.m trunk/octave-forge/main/control/inst/@lti/freqresp.m trunk/octave-forge/main/control/inst/@lti/lft.m trunk/octave-forge/main/control/inst/@lti/mpower.m trunk/octave-forge/main/control/inst/@lti/set.m trunk/octave-forge/main/control/inst/@ss/__freqresp__.m trunk/octave-forge/main/control/inst/@ss/__set__.m trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m trunk/octave-forge/main/control/inst/@ss/__sys_inverse__.m trunk/octave-forge/main/control/inst/@ss/display.m trunk/octave-forge/main/control/inst/@ss/ss.m trunk/octave-forge/main/control/inst/@tf/__freqresp__.m trunk/octave-forge/main/control/inst/@tf/__minreal__.m trunk/octave-forge/main/control/inst/@tf/tf.m trunk/octave-forge/main/control/inst/__axis_limits__.m trunk/octave-forge/main/control/inst/__frequency_range__.m trunk/octave-forge/main/control/inst/__time_response__.m trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/dlyap.m trunk/octave-forge/main/control/inst/dss.m trunk/octave-forge/main/control/inst/gram.m trunk/octave-forge/main/control/inst/h2syn.m trunk/octave-forge/main/control/inst/hinfsyn.m trunk/octave-forge/main/control/inst/isctrb.m trunk/octave-forge/main/control/inst/isdetectable.m trunk/octave-forge/main/control/inst/issample.m trunk/octave-forge/main/control/inst/isstabilizable.m trunk/octave-forge/main/control/inst/lsim.m trunk/octave-forge/main/control/inst/lyap.m trunk/octave-forge/main/control/inst/margin.m trunk/octave-forge/main/control/inst/place.m trunk/octave-forge/main/control/inst/rlocus.m trunk/octave-forge/main/control/inst/sigma.m Modified: trunk/octave-forge/main/control/INDEX =================================================================== --- trunk/octave-forge/main/control/INDEX 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/INDEX 2010-10-03 07:58:11 UTC (rev 7796) @@ -97,7 +97,7 @@ dlyapchol lyap lyapchol -Octave-only +Octave-Specific isctrb isdetectable isobsv Modified: trunk/octave-forge/main/control/inst/@lti/feedback.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/feedback.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@lti/feedback.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -45,7 +45,7 @@ [p1, m1] = size (sys1); switch (nargin) - case 1 # sys = feedback (sys) + case 1 # sys = feedback (sys) if (p1 != m1) error ("feedback: argument must be a square system"); endif @@ -65,25 +65,25 @@ sys2 = eye (p1); feedin = 1 : m1; feedout = 1 : p1; - else # sys = feedback (sys1, sys2) + else # sys = feedback (sys1, sys2) fbsign = -1; sys2 = sys2_or_fbsign; feedin = 1 : m1; feedout = 1 : p1; endif - case 3 # sys = feedback (sys1, sys2, "+") + case 3 # sys = feedback (sys1, sys2, "+") fbsign = checkfbsign (feedin_or_fbsign); sys2 = sys2_or_fbsign; feedin = 1 : m1; feedout = 1 : p1; - case 4 # sys = feedback (sys1, sys2, feedin, feedout) + case 4 # sys = feedback (sys1, sys2, feedin, feedout) fbsign = -1; sys2 = sys2_or_fbsign; feedin = feedin_or_fbsign; - case 5 # sys = feedback (sys1, sys2, feedin, feedout, "+") + case 5 # sys = feedback (sys1, sys2, feedin, feedout, "+") fbsign = checkfbsign (fbsign); sys2 = sys2_or_fbsign; feedin = feedin_or_fbsign; Modified: trunk/octave-forge/main/control/inst/@lti/freqresp.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -44,7 +44,7 @@ function H = freqresp (sys, w) - if (nargin != 2) # case freqresp () not possible + if (nargin != 2) # case freqresp () not possible print_usage (); endif Modified: trunk/octave-forge/main/control/inst/@lti/lft.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lft.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@lti/lft.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -106,7 +106,7 @@ if (nargin == 2) # sys = lft (sys1, sys2) nu = nu_max; ny = ny_max; - else # sys = lft (sys1, sys2, nu, ny) + else # sys = lft (sys1, sys2, nu, ny) if (! is_real_scalar (nu) || nu < 0) error ("lft: argument nu must be a positive integer"); endif Modified: trunk/octave-forge/main/control/inst/@lti/mpower.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -38,13 +38,13 @@ ex = round (abs (e)); # make sure ex is a positive integer switch (sign (e)) - case -1 # lti^-ex + case -1 # lti^-ex sys = inv (sys); retsys = sys; - case 0 # lti^0 + case 0 # lti^0 retsys = eye (p); return; - case 1 # lti^ex + case 1 # lti^ex retsys = sys; endswitch Modified: trunk/octave-forge/main/control/inst/@lti/set.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/set.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@lti/set.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -27,7 +27,7 @@ function retsys = set (sys, varargin) - if (nargin == 1) # set (sys), sys = set (sys) + if (nargin == 1) # set (sys), sys = set (sys) [props, vals] = __property_names__ (sys); nrows = numel (props); @@ -46,7 +46,7 @@ warning ("lti: set: use sys = get (sys, ""property1"", ...) to save changes"); warning (" octave does not support pass by reference"); - else # sys = set (sys, "prop1", val1, ...) + else # sys = set (sys, "prop1", val1, ...) if (rem (nargin-1, 2)) error ("lti: set: properties and values must come in pairs"); Modified: trunk/octave-forge/main/control/inst/@ss/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -34,21 +34,21 @@ if (tsam > 0) # discrete system s = num2cell (exp (i * w * tsam)); - else # continuous system + else # continuous system s = num2cell (i * w); endif switch (resptype) - case 0 # default system + case 0 # default system H = cellfun (@(x) c/(x*e - a)*b + d, s, "uniformoutput", false); - case 1 # inversed system + case 1 # inversed system H = cellfun (@(x) inv (c/(x*e - a)*b + d), s, "uniformoutput", false); - case 2 # inversed sensitivity + case 2 # inversed sensitivity H = cellfun (@(x) j + c/(x*e - a)*b + d, s, "uniformoutput", false); - case 3 # inversed complementary sensitivity + case 3 # inversed complementary sensitivity H = cellfun (@(x) j + inv (c/(x*e - a)*b + d), s, "uniformoutput", false); otherwise Modified: trunk/octave-forge/main/control/inst/@ss/__set__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__set__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/__set__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -24,7 +24,7 @@ function sys = __set__ (sys, prop, val) - switch (prop) # {<internal name>, <user name>} + switch (prop) # {<internal name>, <user name>} case "a" __ss_dim__ (val, sys.b, sys.c, sys.d); sys.a = val; Modified: trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -28,10 +28,10 @@ error ("ss: ss2tf: MIMO case not implemented yet"); endif - if (isempty (sys.a)) # static gain + if (isempty (sys.a)) # static gain num = sys.d; den = 1; - else # default case + else # default case [zer, gain] = zero (sys); num = gain * real (poly (zer)); @@ -39,6 +39,6 @@ endif retsys = tf (num, den, get (sys, "tsam")); # tsam needed to set appropriate tfvar - retlti = sys.lti; # preserve lti properties + retlti = sys.lti; # preserve lti properties endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@ss/__sys_inverse__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys_inverse__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/__sys_inverse__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -33,9 +33,9 @@ if (! isempty (e) || rcond (d) < eps) # dss or strictly proper ss n = rows (a); - m = columns (b); # p = m (square system) + m = columns (b); # p = m (square system) - if (isempty (e)) # avoid testing twice? + if (isempty (e)) # avoid testing twice? e = eye (n); endif @@ -47,7 +47,7 @@ sys.stname = repmat ({""}, n+m, 1); - else # proper ss + else # proper ss di = inv (d); Modified: trunk/octave-forge/main/control/inst/@ss/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/display.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/display.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -78,7 +78,7 @@ function __disp_mat__ (m, mname, rname, cname) - MAX_LEN = 12; # max length of row name and column name + MAX_LEN = 12; # max length of row name and column name [mrows, mcols] = size (m); row_name = strjust (strvcat (" ", rname), "left"); Modified: trunk/octave-forge/main/control/inst/@ss/ss.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -64,18 +64,18 @@ e = []; switch (nargin) - case 0 # ss () - ## tsam = -1; # noting is done here, but "case 0" needed to prevent "otherwise" + case 0 # ss () + ## tsam = -1; # nothing is done here, but "case 0" needed to prevent "otherwise" case 1 - if (isa (a, "ss")) # already in ss form + if (isa (a, "ss")) # already in ss form sys = a; return; - elseif (isa (a, "lti")) # another lti object + elseif (isa (a, "lti")) # another lti object [sys, alti] = __sys2ss__ (a); - sys.lti = alti; # preserve lti properties + sys.lti = alti; # preserve lti properties return; - elseif (is_real_matrix (a)) # static gain + elseif (is_real_matrix (a)) # static gain d = a; a = []; b = zeros (0, columns (d)); @@ -92,7 +92,7 @@ d = zeros (rows (c), columns (b)); tsam = 0; - case 4 # continuous system ss (a, b, c, d), ss ([], [], [], d) + case 4 # continuous system ss (a, b, c, d), ss ([], [], [], d) [b, c] = __gain_check__ (b, c, d); tsam = 0; @@ -106,16 +106,16 @@ if (argc > 0) varargin = varargin(2:end); endif - else # sys = ss (a, b, c, d, "prop1, "val1", ...) + else # sys = ss (a, b, c, d, "prop1, "val1", ...) tsam = 0; endif endswitch - if (isempty (a)) # static system + if (isempty (a)) # static system tsam = -1; - a = []; # avoid [](nx0) or [](0xn) + a = []; # avoid [](nx0) or [](0xn) endif [p, m, n] = __ss_dim__ (a, b, c, d); Modified: trunk/octave-forge/main/control/inst/@tf/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__freqresp__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@tf/__freqresp__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -28,7 +28,7 @@ if (tsam > 0) # discrete system s = num2cell (exp (i * w * tsam)); - else # continuous system + else # continuous system s = num2cell (i * w); endif @@ -46,13 +46,13 @@ j = eye (p); switch (resptype) - case 1 # inversed system + case 1 # inversed system H = cellfun (@inv, H, "uniformoutput", false); - case 2 # inversed sensitivity + case 2 # inversed sensitivity H = cellfun (@(x) j + x, H, "uniformoutput", false); - case 3 # inversed complementary sensitivity + case 3 # inversed complementary sensitivity H = cellfun (@(x) j + inv (x), H, "uniformoutput", false); otherwise Modified: trunk/octave-forge/main/control/inst/@tf/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__minreal__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@tf/__minreal__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -27,7 +27,7 @@ ## TODO: Once ZPK models are implemented, convert TF to ZPK, ## do cancellations over there and convert back to TF - sqrt_eps = sqrt (eps); # treshold for zero + sqrt_eps = sqrt (eps); # treshold for zero [p, m] = size (sys); @@ -38,11 +38,11 @@ [zer, gain] = zero (sisosys); pol = pole (sisosys); - for k = length (zer) : -1 : 1 # reversed because of deleted zeros + for k = length (zer) : -1 : 1 # reversed because of deleted zeros [jnk, idx] = min (abs (zer(k) - pol)); # find best match if (tol == "def") - if (abs (zer(k)) < sqrt_eps) # catch case zer(k) = 0 + if (abs (zer(k)) < sqrt_eps) # catch case zer(k) = 0 t = 1000 * eps; else t = 1000 * abs (zer(k)) * sqrt_eps; @@ -60,8 +60,8 @@ num = real (gain * poly (zer)); den = real (poly (pol)); - num_idx = find (abs (num) < sqrt_eps); # suppress numerical noise - den_idx = find (abs (den) < sqrt_eps); # in polynomial coefficients + num_idx = find (abs (num) < sqrt_eps); # suppress numerical noise + den_idx = find (abs (den) < sqrt_eps); # in polynomial coefficients num(num_idx) = 0; den(den_idx) = 0; Modified: trunk/octave-forge/main/control/inst/@tf/tf.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -62,7 +62,7 @@ function sys = tf (num = {}, den = {}, varargin) ## model precedence: frd > ss > zpk > tf > double - ## inferiorto ("frd", "ss", "zpk"); # error if de-commented. bug in octave? + ## inferiorto ("frd", "ss", "zpk"); # error if de-commented. bug in octave? superiorto ("double"); argc = 0; @@ -70,24 +70,24 @@ switch (nargin) case 0 tsam = -1; - tfvar = "x"; # undefined + tfvar = "x"; # undefined case 1 - if (isa (num, "tf")) # already in tf form + if (isa (num, "tf")) # already in tf form sys = num; return; - elseif (isa (num, "lti")) # another lti object + elseif (isa (num, "lti")) # another lti object [sys, numlti] = __sys2tf__ (num); - sys.lti = numlti; # preserve lti properties + sys.lti = numlti; # preserve lti properties return; - elseif (is_real_vector (num)) # static gain + elseif (is_real_vector (num)) # static gain num = num2cell (num); num = __vec2tfpoly__ (num); [p, m] = size (num); den = tfpolyones (p, m); tsam = -1; - tfvar = "x"; # undefined - elseif (ischar (num)) # s = tf ("s") + tfvar = "x"; # undefined + elseif (ischar (num)) # s = tf ("s") tfvar = num; num = __vec2tfpoly__ ([1, 0]); den = __vec2tfpoly__ ([1]); @@ -102,19 +102,19 @@ tsam = den; num = __vec2tfpoly__ ([1, 0]); den = __vec2tfpoly__ ([1]); - else # sys = tf (num, den) + else # sys = tf (num, den) num = __vec2tfpoly__ (num); den = __vec2tfpoly__ (den); tfvar = "s"; tsam = 0; endif - otherwise # default case + otherwise # default case num = __vec2tfpoly__ (num); den = __vec2tfpoly__ (den); argc = numel (varargin); - if (issample (varargin{1}, 1)) # sys = tf (num, den, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, 1)) # sys = tf (num, den, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; @@ -129,7 +129,7 @@ if (argc > 0) varargin = varargin(2:end); endif - else # sys = tf (num, den, "prop1, "val1", ...) + else # sys = tf (num, den, "prop1, "val1", ...) tsam = 0; tfvar = "s"; endif Modified: trunk/octave-forge/main/control/inst/__axis_limits__.m =================================================================== --- trunk/octave-forge/main/control/inst/__axis_limits__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/__axis_limits__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -45,8 +45,8 @@ ## compute axis limits minv = min (axdata); maxv = max (axdata); - delv = (maxv-minv)/2; # breadth of the plot - midv = (minv + maxv)/2; # midpoint of the plot + delv = (maxv-minv)/2; # breadth of the plot + midv = (minv + maxv)/2; # midpoint of the plot axmid = [midv(1), midv(1), midv(2), midv(2)]; axdel = [-0.1, 0.1, -0.1, 0.1]; # default plot width (if less than 2-d data) if (max (delv) == 0) Modified: trunk/octave-forge/main/control/inst/__frequency_range__.m =================================================================== --- trunk/octave-forge/main/control/inst/__frequency_range__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/__frequency_range__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -42,7 +42,7 @@ zer = zero (sys); pol = pole (sys); tsam = get (sys, "tsam"); - discrete = (tsam > 0); # static gains (tsam = -1) are continuous + discrete = (tsam > 0); # static gains (tsam = -1) are continuous ## make sure zer, pol are row vectors pol = reshape (pol, 1, []); @@ -85,8 +85,8 @@ if (isempty (iip) && isempty (iiz)) ## no poles/zeros away from omega = 0; pick defaults - dec_min = 0; # -1 - dec_max = 2; # 3 + dec_min = 0; # -1 + dec_max = 2; # 3 else dec_min = floor (log10 (min (abs ([cpol, czer])))); dec_max = ceil (log10 (max (abs ([cpol, czer])))); @@ -94,7 +94,7 @@ ## expand to show the entirety of the "interesting" portion of the plot switch (wbounds) - case "std" # standard + case "std" # standard if (dec_min == dec_max) dec_min -= 2; dec_max += 2; @@ -102,7 +102,7 @@ dec_min--; dec_max++; endif - case "ext" # extended (for nyquist) + case "ext" # extended (for nyquist) if (any (abs (pol) < sqrt (eps))) # look for integrators ## dec_min -= 0.5; dec_max += 2; Modified: trunk/octave-forge/main/control/inst/__time_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__time_response__.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/__time_response__.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -25,17 +25,17 @@ function [y, t, x_arr] = __time_response__ (sys, resptype, plotflag, tfinal, dt, x0) if (! isa (sys, "ss")) - sys = ss (sys); # sys must be proper + sys = ss (sys); # sys must be proper endif if (is_real_vector (tfinal) && length (tfinal) > 1) # time vector t passed - dt = tfinal(2) - tfinal(1); # assume that t is regularly spaced + dt = tfinal(2) - tfinal(1); # assume that t is regularly spaced tfinal = tfinal(end); endif [A, B, C, D, tsam] = ssdata (sys); - discrete = ! isct (sys); # static gains are treated as analog systems + discrete = ! isct (sys); # static gains are treated as analog systems if (discrete) if (! isempty (dt)) @@ -51,11 +51,11 @@ sys = c2d (sys, dt, "zoh"); endif - [F, G] = ssdata (sys); # matrices C and D don't change + [F, G] = ssdata (sys); # matrices C and D don't change - n = rows (F); # number of states - m = columns (G); # number of inputs - p = rows (C); # number of outputs + n = rows (F); # number of states + m = columns (G); # number of inputs + p = rows (C); # number of outputs ## time vector t = reshape (0 : dt : tfinal, [], 1); @@ -71,7 +71,7 @@ x_arr = zeros (l_t, n); ## initial conditions - x = reshape (x0, [], 1); # make sure that x is a column vector + x = reshape (x0, [], 1); # make sure that x is a column vector if (n != length (x0)) error ("initial: x0 must be a vector with %d elements", n); @@ -92,7 +92,7 @@ y = zeros (l_t, p, m); x_arr = zeros (l_t, n, m); - for j = 1 : m # for every input channel + for j = 1 : m # for every input channel ## initial conditions x = zeros (n, 1); u = zeros (m, 1); @@ -114,18 +114,18 @@ y = zeros (l_t, p, m); x_arr = zeros (l_t, n, m); - for j = 1 : m # for every input channel + for j = 1 : m # for every input channel ## initial conditions u = zeros (m, 1); u(j) = 1; if (discrete) - x = zeros (n, 1); # zero by definition + x = zeros (n, 1); # zero by definition y(1, :, j) = D * u / dt; x_arr(1, :, j) = x; x = G * u / dt; else - x = B * u; # B, not G! + x = B * u; # B, not G! y(1, :, j) = C * x; x_arr(1, :, j) = x; x = F * x; @@ -150,7 +150,7 @@ endswitch - if (plotflag) # display plot + if (plotflag) # display plot ## TODO: Set correct titles, especially for multi-input systems ## Limitations probably due to the Gnuplot backend @@ -170,7 +170,7 @@ cols = m; endif - if (discrete) # discrete system + if (discrete) # discrete system for k = 1 : p for j = 1 : cols @@ -197,7 +197,7 @@ xlabel ("Time [s]"); - else # continuous system + else # continuous system for k = 1 : p for j = 1 : cols @@ -234,11 +234,11 @@ ## code based on __stepimp__.m of Kai P. Mueller and A. Scottedward Hodel - TOL = 1.0e-10; # values below TOL are assumed to be zero - N_MIN = 50; # min number of points - N_MAX = 2000; # max number of points - N_DEF = 1000; # default number of points - T_DEF = 10; # default simulation time + TOL = 1.0e-10; # values below TOL are assumed to be zero + N_MIN = 50; # min number of points + N_MAX = 2000; # max number of points + N_DEF = 1000; # default number of points + T_DEF = 10; # default simulation time n = rows (A); eigw = eig (A); @@ -302,7 +302,7 @@ endif endif - if (! isempty (Ts)) # catch case analog system with dt specified + if (! isempty (Ts)) # catch case analog system with dt specified dt = Ts; endif Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/care.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -121,7 +121,7 @@ if (isempty (e)) if (isempty (s)) [x, l] = slsb02od (a, b, q, r, b, false, false); - g = r \ (b.'*x); # gain matrix + g = r \ (b.'*x); # gain matrix else [x, l] = slsb02od (a, b, q, r, s, false, true); g = r \ (b.'*x + s.'); # gain matrix Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/dare.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -121,7 +121,7 @@ if (isempty (e)) if (isempty (s)) [x, l] = slsb02od (a, b, q, r, b, true, false); - g = (r + b.'*x*b) \ (b.'*x*a); # gain matrix + g = (r + b.'*x*b) \ (b.'*x*a); # gain matrix else [x, l] = slsb02od (a, b, q, r, s, true, true); g = (r + b.'*x*b) \ (b.'*x*a + s.'); # gain matrix Modified: trunk/octave-forge/main/control/inst/dlyap.m =================================================================== --- trunk/octave-forge/main/control/inst/dlyap.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/dlyap.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -45,7 +45,7 @@ scale = 1; switch (nargin) - case 2 # Lyapunov equation + case 2 # Lyapunov equation if (! is_real_square_matrix (a, b)) error ("dlyap: a, b must be real and square"); @@ -55,11 +55,11 @@ error ("dlyap: a, b must have the same number of rows"); endif - [x, scale] = slsb03md (a, -b, true); # AXA' - X = -B + [x, scale] = slsb03md (a, -b, true); # AXA' - X = -B - ## x /= scale; # 0 < scale <= 1 + ## x /= scale; # 0 < scale <= 1 - case 3 # Sylvester equation + case 3 # Sylvester equation if (! is_real_square_matrix (a, b)) error ("dlyap: a, b must be real and square"); @@ -69,9 +69,9 @@ error ("dlyap: c must be a real (%dx%d) matrix", rows (a), columns (b)); endif - x = slsb04qd (-a, b, c); # AXB' - X = -C + x = slsb04qd (-a, b, c); # AXB' - X = -C - case 4 # generalized Lyapunov equation + case 4 # generalized Lyapunov equation if (! isempty (c)) print_usage (); @@ -91,7 +91,7 @@ [x, scale] = slsg03ad (a, e, -b, true); # AXA' - EXE' = -B - ## x /= scale; # 0 < scale <= 1 + ## x /= scale; # 0 < scale <= 1 otherwise print_usage (); Modified: trunk/octave-forge/main/control/inst/dss.m =================================================================== --- trunk/octave-forge/main/control/inst/dss.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/dss.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -58,10 +58,10 @@ function sys = dss (varargin) switch (nargin) - case 0 # useful for "set (dss)" + case 0 # useful for "set (dss)" sys = ss (); - case 1 # static gain + case 1 # static gain sys = ss (varargin{1}); case {2, 3, 4} Modified: trunk/octave-forge/main/control/inst/gram.m =================================================================== --- trunk/octave-forge/main/control/inst/gram.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/gram.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -41,7 +41,7 @@ print_usage (); endif - if (ischar (argin2)) # the function was called as "gram (sys, mode)" + if (ischar (argin2)) # the function was called as "gram (sys, mode)" sys = argin1; argin2 = lower (argin2); @@ -57,7 +57,7 @@ elseif (! strcmp (argin2, "c")) print_usage (); endif - else # the function was called as "gram (a, b)" + else # the function was called as "gram (a, b)" a = argin1; b = argin2; @@ -71,7 +71,7 @@ endif if (isct (sys)) - W = lyap (a, b*b.'); # let lyap do the error checking about dimensions + W = lyap (a, b*b.'); # let lyap do the error checking about dimensions else # discrete-time system W = dlyap (a, b*b.'); # let dlyap do the error checking about dimensions endif Modified: trunk/octave-forge/main/control/inst/h2syn.m =================================================================== --- trunk/octave-forge/main/control/inst/h2syn.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/h2syn.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -117,9 +117,9 @@ endif ## H-2 synthesis - if (isct (P)) # continuous plant + if (isct (P)) # continuous plant [ak, bk, ck, dk] = slsb10hd (a, b, c, d, ncon, nmeas); - else # discrete plant + else # discrete plant [ak, bk, ck, dk] = slsb10ed (a, b, c, d, ncon, nmeas); endif Modified: trunk/octave-forge/main/control/inst/hinfsyn.m =================================================================== --- trunk/octave-forge/main/control/inst/hinfsyn.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/hinfsyn.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -120,9 +120,9 @@ endif ## H-infinity synthesis - if (isct (P)) # continuous plant + if (isct (P)) # continuous plant [ak, bk, ck, dk] = slsb10fd (a, b, c, d, ncon, nmeas, gmax); - else # discrete plant + else # discrete plant [ak, bk, ck, dk] = slsb10dd (a, b, c, d, ncon, nmeas, gmax); endif Modified: trunk/octave-forge/main/control/inst/isctrb.m =================================================================== --- trunk/octave-forge/main/control/inst/isctrb.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/isctrb.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -65,7 +65,7 @@ endif tol = b; [a, b, c, d, e] = dssdata (a, []); - elseif (nargin < 2) # isctrb (a, b), isctrb (a, b, tol) + elseif (nargin < 2) # isctrb (a, b), isctrb (a, b, tol) print_usage (); elseif (! is_real_square_matrix (a) || ! is_real_matrix (b) || rows (a) != rows (b)) error ("isctrb: a(%dx%d), b(%dx%d) not conformal", @@ -76,7 +76,7 @@ endif if (isempty (tol)) - tol = 0; # default tolerance + tol = 0; # default tolerance elseif (! is_real_scalar (tol)) error ("isctrb: tol must be a real scalar"); endif Modified: trunk/octave-forge/main/control/inst/isdetectable.m =================================================================== --- trunk/octave-forge/main/control/inst/isdetectable.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/isdetectable.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -68,14 +68,14 @@ if (nargin == 0) print_usage (); - elseif (isa (a, "lti")) # isdetectable (sys), isdetectable (sys, tol) + elseif (isa (a, "lti")) # isdetectable (sys), isdetectable (sys, tol) if (nargin > 2) print_usage (); endif - bool = isstabilizable (a.', c); # transpose is overloaded + bool = isstabilizable (a.', c); # transpose is overloaded elseif (nargin < 2 || nargin > 5) print_usage (); - else # isdetectable (a, c, ...) + else # isdetectable (a, c, ...) bool = isstabilizable (a.', c.', e.', tol, dflg); # arguments checked inside endif Modified: trunk/octave-forge/main/control/inst/issample.m =================================================================== --- trunk/octave-forge/main/control/inst/issample.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/issample.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -37,7 +37,7 @@ if (flg == 0) # refuse -1 and 0 bool = is_real_scalar (tsam) && (tsam > 0); - else # allow -1 and 0 + else # allow -1 and 0 bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1); endif Modified: trunk/octave-forge/main/control/inst/isstabilizable.m =================================================================== --- trunk/octave-forge/main/control/inst/isstabilizable.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/isstabilizable.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -85,7 +85,7 @@ tol = b; dflg = ! isct (a); [a, b, c, d, e] = dssdata (a, []); - elseif (nargin == 1) # isstabilizable (a, b, ...) + elseif (nargin == 1) # isstabilizable (a, b, ...) print_usage (); elseif (! is_real_square_matrix (a) || rows (a) != rows (b)) error ("isstabilizable: a must be square and conformal to b"); @@ -94,7 +94,7 @@ endif if (isempty (tol)) - tol = 0; # default tolerance + tol = 0; # default tolerance elseif (! is_real_scalar (tol)) error ("isstabilizable: tol must be a real scalar"); endif Modified: trunk/octave-forge/main/control/inst/lsim.m =================================================================== --- trunk/octave-forge/main/control/inst/lsim.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/lsim.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -62,17 +62,17 @@ endif if (! isa (sys, "ss")) - sys = ss (sys); # sys must be proper + sys = ss (sys); # sys must be proper endif [A, B, C, D, tsam] = ssdata (sys); - discrete = ! isct (sys); # static gains are treated as analog systems + discrete = ! isct (sys); # static gains are treated as analog systems urows = rows (u); ucols = columns (u); - if (discrete) # discrete system + if (discrete) # discrete system if (isempty (t)) dt = tsam; tfinal = tsam * (urows - 1); @@ -84,24 +84,24 @@ dt = tsam; tfinal = t(end); endif - else # continuous system + else # continuous system if (isempty (t)) error ("lsim: invalid time vector"); elseif (length (t) == 1) dt = t / (urows - 1); tfinal = t; else - dt = t(2) - t(1); # assume that t is regularly spaced + dt = t(2) - t(1); # assume that t is regularly spaced tfinal = t(end); endif - sys = c2d (sys, dt, method); # convert to discrete model + sys = c2d (sys, dt, method); # convert to discrete model endif - [F, G] = ssdata (sys); # matrices C and D don't change + [F, G] = ssdata (sys); # matrices C and D don't change - n = rows (F); # number of states - m = columns (G); # number of inputs - p = rows (C); # number of outputs + n = rows (F); # number of states + m = columns (G); # number of inputs + p = rows (C); # number of outputs t = reshape (0 : dt : tfinal, [], 1); # time vector trows = length (t); @@ -125,7 +125,7 @@ error ("initial: x0 must be a vector with %d elements", n); endif - x = reshape (x0, [], 1); # make sure that x is a column vector + x = reshape (x0, [], 1); # make sure that x is a column vector ## simulation for k = 1 : trows @@ -134,7 +134,7 @@ x = F * x + G * u(k, :).'; endfor - if (! nargout) # plot information + if (! nargout) # plot information str = "Linear Simulation Results"; outname = get (sys, "outname"); @@ -144,7 +144,7 @@ outname = __mark_empty_names__ (outname); endif - if (discrete) # discrete system + if (discrete) # discrete system for k = 1 : p subplot (p, 1, k); stairs (t, y(:, k)); @@ -155,7 +155,7 @@ ylabel (sprintf ("Amplitude %s", outname{k})); endfor xlabel ("Time [s]"); - else # continuous system + else # continuous system for k = 1 : p subplot (p, 1, k); plot (t, y(:, k)); @@ -167,7 +167,7 @@ endfor xlabel ("Time [s]"); endif - else # return values + else # return values y_r = y; t_r = t; x_r = x_arr; Modified: trunk/octave-forge/main/control/inst/lyap.m =================================================================== --- trunk/octave-forge/main/control/inst/lyap.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/lyap.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -45,7 +45,7 @@ scale = 1; switch (nargin) - case 2 # Lyapunov equation + case 2 # Lyapunov equation if (! is_real_square_matrix (a, b)) error ("lyap: a, b must be real and square"); @@ -55,11 +55,11 @@ error ("lyap: a, b must have the same number of rows"); endif - [x, scale] = slsb03md (a, -b, false); # AX + XA' = -B + [x, scale] = slsb03md (a, -b, false); # AX + XA' = -B - ## x /= scale; # 0 < scale <= 1 + ## x /= scale; # 0 < scale <= 1 - case 3 # Sylvester equation + case 3 # Sylvester equation if (! is_real_square_matrix (a, b)) error ("lyap: a, b must be real and square"); @@ -71,7 +71,7 @@ x = slsb04md (a, b, -c); # AX + XB = -C - case 4 # generalized Lyapunov equation + case 4 # generalized Lyapunov equation if (! isempty (c)) print_usage (); @@ -91,7 +91,7 @@ [x, scale] = slsg03ad (a, e, -b, false); # AXE' + EXA' = -B - ## x /= scale; # 0 < scale <= 1 + ## x /= scale; # 0 < scale <= 1 otherwise print_usage (); Modified: trunk/octave-forge/main/control/inst/margin.m =================================================================== --- trunk/octave-forge/main/control/inst/margin.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/margin.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -144,7 +144,7 @@ den = den{1, 1}; - if (Ts == 0) # CONTINUOUS SYSTEM + if (Ts == 0) # CONTINUOUS SYSTEM ## create polynomials s -> jw l_num = length (num); @@ -181,7 +181,7 @@ [phi, w_phi] = pm_filter (w, num, den, Ts, tol); - else # DISCRETE SYSTEM + else # DISCRETE SYSTEM ## create polynomials z -> 1/z l_num = length (num); @@ -213,13 +213,13 @@ z = roots (gm_poly); ## filter results - idx = find (abs (abs (z) - 1) < tol); # find z with magnitude 1 + idx = find (abs (abs (z) - 1) < tol); # find z with magnitude 1 - if (length (idx) > 0) # if z with magnitude 1 exist + if (length (idx) > 0) # if z with magnitude 1 exist z_gm = z(idx); - w = log (z_gm) / (i*Ts); # get frequencies w from z + w = log (z_gm) / (i*Ts); # get frequencies w from z [gamma, w_gamma] = gm_filter (w, num, den, Ts, tol); - else # there are no z with magnitude 1 + else # there are no z with magnitude 1 gamma = Inf; w_gamma = NaN; endif @@ -239,13 +239,13 @@ z = roots (pm_poly); ## filter results - idx = find (abs (abs (z) - 1) < tol); # find z with magnitude 1 + idx = find (abs (abs (z) - 1) < tol); # find z with magnitude 1 - if (length (idx) > 0) # if z with magnitude 1 exist + if (length (idx) > 0) # if z with magnitude 1 exist z_gm = z(idx); - w = log (z_gm) / (i*Ts); # get frequencies w from z + w = log (z_gm) / (i*Ts); # get frequencies w from z [phi, w_phi] = pm_filter (w, num, den, Ts, tol); - else # there are no z with magnitude 1 + else # there are no z with magnitude 1 phi = 180; w_phi = NaN; endif @@ -253,7 +253,7 @@ endif - if (nargout == 0) # show bode diagram + if (nargout == 0) # show bode diagram [H, w] = __frequency_response__ (sys, [], false, 0, "std"); @@ -300,7 +300,7 @@ xlabel (xl_str) ylabel ("Phase [deg]") - else # return values + else # return values gamma_r = gamma; phi_r = phi; w_gamma_r = w_gamma; @@ -329,7 +329,7 @@ idx = find ((abs (imag (w)) < tol) & (real (w) > 0)); # find frequencies in R+ - if (length (idx) > 0) # if frequencies in R+ exist + if (length (idx) > 0) # if frequencies in R+ exist w_gm = real (w(idx)); if (Ts == 0) @@ -345,15 +345,15 @@ ## find crossings between 0 and -1 idx = find ((real (f_resp) < 0) & (real (f_resp) >= -1)); - if (length (idx) > 0) # if crossings between 0 and -1 exist + if (length (idx) > 0) # if crossings between 0 and -1 exist gm = gm(idx); w_gm = w_gm(idx); [gamma, idx] = min (gm); w_gamma = w_gm(idx); - else # there are no crossings between 0 and -1 - idx = find (real (f_resp) < -1); # find crossings between -1 and -Inf + else # there are no crossings between 0 and -1 + idx = find (real (f_resp) < -1); # find crossings between -1 and -Inf - if (length (idx) > 0) # if crossings between -1 and -Inf exist + if (length (idx) > 0) # if crossings between -1 and -Inf exist gm = gm(idx); w_gm = w_gm(idx); [gamma, idx] = max (gm); @@ -363,7 +363,7 @@ w_gamma = NaN; endif endif - else # there are no frequencies in R+ + else # there are no frequencies in R+ gamma = Inf; w_gamma = NaN; endif @@ -375,7 +375,7 @@ idx = find ((abs (imag (w)) < tol) & (real (w) > 0)); # find frequencies in R+ - if (length (idx) > 0) # if frequencies in R+ exist + if (length (idx) > 0) # if frequencies in R+ exist w_pm = real (w(idx)); if (Ts == 0) @@ -390,7 +390,7 @@ [phi, idx] = min (pm); w_phi = w_pm(idx); - else # there are no frequencies in R+ + else # there are no frequencies in R+ phi = 180; w_phi = NaN; endif @@ -401,7 +401,7 @@ %!shared margin_c, margin_c_exp, margin_d, margin_d_exp %! sysc = tf ([24], [1, 6, 11, 6]); %! [gamma_c, phi_c, w_gamma_c, w_phi_c] = margin (sysc); -%! sysd = tf (c2d (ss (sysc), 0.3)); # c2d for tf not implemented yet +%! sysd = tf (c2d (ss (sysc), 0.3)); # c2d for tf not implemented yet %! [gamma_d, phi_d, w_gamma_d, w_phi_d] = margin (sysd); %! %! margin_c = [gamma_c, phi_c, w_gamma_c, w_phi_c]; Modified: trunk/octave-forge/main/control/inst/place.m =================================================================== --- trunk/octave-forge/main/control/inst/place.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/place.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -87,7 +87,7 @@ discrete = ! isct (sys); # treat tsam = -1 as continuous system endif else # place (a, b, p), place (a, b, p, alpha), place (a, b, p, alpha, tol) - if (nargin < 3) # nargin > 5 already tested + if (nargin < 3) # nargin > 5 already tested print_usage (); else if (! is_real_square_matrix (a) || ! is_real_matrix (b) || rows (a) != rows (b)) Modified: trunk/octave-forge/main/control/inst/rlocus.m =================================================================== --- trunk/octave-forge/main/control/inst/rlocus.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/rlocus.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -81,24 +81,24 @@ if (lden < 2) error ("system has no poles"); elseif (lnum < lden) - num = [zeros(1,lden-lnum), num]; # so that derivative is shortened by one + num = [zeros(1,lden-lnum), num]; # so that derivative is shortened by one endif olpol = roots (den); olzer = roots (num); - nas = lden - lnum; # number of asymptotes + nas = lden - lnum; # number of asymptotes maxk = 0; if (nas > 0) cas = (sum (olpol) - sum (olzer)) / nas; angles = (2*[1:nas]-1)*pi/nas; - # printf("rlocus: there are %d asymptotes centered at %f\n", nas, cas); + ## printf("rlocus: there are %d asymptotes centered at %f\n", nas, cas); else cas = angles = []; maxk = 100*den(1)/num(1); endif - # compute real axis break points and corresponding gains + ## compute real axis break points and corresponding gains dnum = polyderiv (num); dden = polyderiv (den); brkp = conv (den, dnum) - conv (num, dden); @@ -113,7 +113,7 @@ endif if (nas == 0) - maxk = max (1, 2*maxk); # get at least some root locus + maxk = max (1, 2*maxk); # get at least some root locus else ## get distance from breakpoints, poles, and zeros to center of asymptotes dmax = 3*max (abs ([vec(olzer); vec(olpol); vec(real_ax_pts)] - cas)); @@ -121,7 +121,7 @@ dmax = 1; endif - # get gain for dmax along each asymptote, adjust maxk if necessary + ## get gain for dmax along each asymptote, adjust maxk if necessary svals = cas + dmax * exp (j*angles); kvals = -polyval (den, svals) ./ polyval (num, svals); maxk = max (maxk, max (real (kvals))); @@ -176,9 +176,9 @@ ## sort according to nearest-neighbor rlpol = sort_roots (rlpol, smtolx, smtoly); - done = (nargin == 4); # perform a smoothness check + done = (nargin == 4); # perform a smoothness check while (! done && ngain < 1000) - done = 1 ; # assume done + done = 1 ; # assume done dp = abs (diff (rlpol.')).'; maxdp = max (dp); @@ -203,7 +203,7 @@ newg = linspace (g1, g2, 5); newg = newg(2:4); gvec = [gvec,newg]; - done = 0; # need to process new gains + done = 0; # need to process new gains endif endfor @@ -239,14 +239,14 @@ if (! isempty (rlzer)) nelts++; endif - # add asymptotes + ## add asymptotes n_A = length (olpol) - length (olzer); if (n_A > 0) nelts += n_A; endif args = cell (3, nelts); kk = 0; - # asymptotes first + ## asymptotes first if (n_A > 0) len_A = 2*max (abs (axlim)); sigma_A = (sum(olpol) - sum(olzer))/n_A; @@ -261,7 +261,7 @@ endif endfor endif - # locus next + ## locus next for ii = 1:rows(rlpol) args{1,++kk} = real (rlpol (ii,:)); args{2,kk} = imag (rlpol (ii,:)); @@ -271,7 +271,7 @@ args{3,kk} = "b-"; endif endfor - # poles and zeros last + ## poles and zeros last args{1,++kk} = real (olpol); args{2,kk} = imag (olpol); args{3,kk} = "rx;open loop poles;"; @@ -304,12 +304,12 @@ function rlpol = sort_roots (rlpol, tolx, toly) - # no point sorting of you've only got one pole! + ## no point sorting of you've only got one pole! if (rows (rlpol) == 1) return; endif - # reorder entries in each column of rlpol to be by their nearest-neighbors + ## reorder entries in each column of rlpol to be by their nearest-neighbors rlpol dp = diff (rlpol.').'; drp = max (real (dp)); @@ -319,7 +319,7 @@ return; endif - [np, ng] = size (rlpol); # num poles, num gains + [np, ng] = size (rlpol); # num poles, num gains for jj = idx vals = rlpol(:,[jj,jj+1]); jdx = (jj+1):ng; Modified: trunk/octave-forge/main/control/inst/sigma.m =================================================================== --- trunk/octave-forge/main/control/inst/sigma.m 2010-10-01 23:57:50 UTC (rev 7795) +++ trunk/octave-forge/main/control/inst/sigma.m 2010-10-03 07:58:11 UTC (rev 7796) @@ -96,7 +96,7 @@ xlabel (xl_str) ylabel ("Singular Values [dB]") grid ("on") - else # return values + else # return values sv_r = sv; w_r = reshape (w, [], 1); endif This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-05 06:29:12
|
Revision: 7802 http://octave.svn.sourceforge.net/octave/?rev=7802&view=rev Author: paramaniac Date: 2010-10-05 06:29:05 +0000 (Tue, 05 Oct 2010) Log Message: ----------- control: create "devel" folder for developer makefiles in order to prevent their installation by "pkg install" Added Paths: ----------- trunk/octave-forge/main/control/devel/ trunk/octave-forge/main/control/devel/makefile_all.m trunk/octave-forge/main/control/devel/makefile_chol.m trunk/octave-forge/main/control/devel/makefile_h2syn.m trunk/octave-forge/main/control/devel/makefile_hankel.m trunk/octave-forge/main/control/devel/makefile_helpers.m trunk/octave-forge/main/control/devel/makefile_hinfsyn.m trunk/octave-forge/main/control/devel/makefile_lqr.m trunk/octave-forge/main/control/devel/makefile_lyap.m trunk/octave-forge/main/control/devel/makefile_minreal.m trunk/octave-forge/main/control/devel/makefile_norm.m trunk/octave-forge/main/control/devel/makefile_place.m trunk/octave-forge/main/control/devel/makefile_staircase.m trunk/octave-forge/main/control/devel/makefile_zero.m Removed Paths: ------------- trunk/octave-forge/main/control/src/makefile_all.m trunk/octave-forge/main/control/src/makefile_chol.m trunk/octave-forge/main/control/src/makefile_h2syn.m trunk/octave-forge/main/control/src/makefile_hankel.m trunk/octave-forge/main/control/src/makefile_helpers.m trunk/octave-forge/main/control/src/makefile_hinfsyn.m trunk/octave-forge/main/control/src/makefile_lqr.m trunk/octave-forge/main/control/src/makefile_lyap.m trunk/octave-forge/main/control/src/makefile_minreal.m trunk/octave-forge/main/control/src/makefile_norm.m trunk/octave-forge/main/control/src/makefile_place.m trunk/octave-forge/main/control/src/makefile_staircase.m trunk/octave-forge/main/control/src/makefile_zero.m Added: trunk/octave-forge/main/control/devel/makefile_all.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_all.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_all.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,27 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_all")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +makefile_chol +makefile_h2syn +makefile_hankel +makefile_helpers +makefile_hinfsyn +makefile_lqr +makefile_lyap +makefile_minreal +makefile_norm +makefile_place +makefile_staircase +makefile_zero + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_chol.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_chol.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_chol.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,26 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_chol")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb03od.cc \ + SB03OD.f select.f SB03OU.f SB03OT.f MB04ND.f \ + MB04OD.f SB03OR.f SB03OY.f SB04PX.f MB04NY.f \ + MB04OY.f SB03OV.f + + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsg03bd.cc \ + SG03BD.f SG03BV.f SG03BU.f SG03BW.f SG03BX.f \ + SG03BY.f MB02UU.f MB02UV.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_h2syn.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_h2syn.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_h2syn.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,31 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_h2syn")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb10hd.cc \ + SB10HD.f SB10UD.f SB10VD.f SB10WD.f SB02RD.f \ + MB01RU.f SB02SD.f MA02ED.f SB02RU.f SB02MR.f \ + MB01SD.f SB02MS.f SB02MV.f SB02MW.f MA02AD.f \ + SB02QD.f MB02PD.f SB03QX.f SB03QY.f MB01RX.f \ + MB01RY.f SB03SX.f SB03SY.f select.f SB03MX.f \ + SB03MY.f MB01UD.f SB03MV.f SB03MW.f SB04PX.f + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb10ed.cc \ + SB10ED.f SB10SD.f SB10TD.f SB10PD.f MB01RX.f \ + SB02SD.f SB02OD.f MB01RU.f SB02OU.f SB02OV.f \ + SB02OW.f MB01RY.f SB02OY.f SB03SX.f SB03SY.f \ + MA02ED.f select.f SB03MX.f SB02MR.f SB02MV.f \ + MB01UD.f SB03MV.f SB04PX.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_hankel.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_hankel.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_hankel.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,22 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_hankel")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slab13ad.cc \ + AB13AD.f TB01ID.f TB01KD.f AB13AX.f MA02DD.f \ + MB03UD.f TB01LD.f SB03OU.f MB03QX.f select.f \ + SB03OT.f MB03QD.f MB04ND.f MB04OD.f MB03QY.f \ + SB03OR.f SB03OY.f SB04PX.f MB04NY.f MB04OY.f \ + SB03OV.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_helpers.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_helpers.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_helpers.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,22 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_helpers")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile is_real_scalar.cc + +mkoctfile is_real_vector.cc + +mkoctfile is_real_matrix.cc + +mkoctfile is_real_square_matrix.cc + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_hinfsyn.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_hinfsyn.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_hinfsyn.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,31 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_hinfsyn")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb10fd.cc \ + SB10FD.f SB10PD.f SB10QD.f SB10RD.f SB02RD.f \ + MB01RU.f MB01RX.f MA02AD.f SB02SD.f MA02ED.f \ + SB02RU.f SB02MR.f MB01SD.f SB02MS.f SB02MV.f \ + SB02MW.f SB02QD.f MB02PD.f SB03QX.f SB03QY.f \ + MB01RY.f SB03SX.f SB03SY.f select.f SB03MX.f \ + SB03MY.f MB01UD.f SB03MV.f SB03MW.f SB04PX.f + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb10dd.cc \ + SB10DD.f MB01RU.f MB01RX.f SB02SD.f SB02OD.f \ + MA02AD.f SB02OU.f SB02OV.f SB02OW.f MB01RY.f \ + SB02OY.f SB03SX.f SB03SY.f MA02ED.f select.f \ + SB03MX.f SB02MR.f SB02MV.f MB01UD.f SB03MV.f \ + SB04PX.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_lqr.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_lqr.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_lqr.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,24 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_lqr")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb02od.cc \ + SB02OD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ + SB02MR.f SB02MV.f + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsg02ad.cc \ + SG02AD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ + MB01SD.f MB02VD.f MB02PD.f MA02GD.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_lyap.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_lyap.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_lyap.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,37 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_lyap")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +## Lypunov +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb03md.cc \ + SB03MD.f select.f SB03MX.f SB03MY.f MB01RD.f \ + SB03MV.f SB03MW.f SB04PX.f + + +## Sylvester +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb04md.cc \ + SB04MD.f SB04MU.f SB04MY.f SB04MR.f SB04MW.f + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb04qd.cc \ + SB04QD.f SB04QU.f SB04QY.f SB04MW.f SB04QR.f + + +## Generalized Lyapunov +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsg03ad.cc \ + SG03AD.f MB01RW.f MB01RD.f SG03AX.f SG03AY.f \ + MB02UU.f MB02UV.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_minreal.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_minreal.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_minreal.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,23 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_minreal")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + sltb01pd.cc \ + TB01PD.f TB01XD.f TB01ID.f AB07MD.f TB01UD.f \ + MB03OY.f MB01PD.f MB01QD.f + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + sltg01jd.cc \ + TG01JD.f TG01AD.f TB01XD.f MA02CD.f TG01HX.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_norm.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_norm.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_norm.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,32 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_norm")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +## H-2 norm +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slab13bd.cc \ + AB13BD.f SB08DD.f SB03OU.f SB01FY.f TB01LD.f \ + SB03OT.f MB04ND.f MB04OD.f MB03QX.f select.f \ + SB03OR.f MB04OX.f MB03QD.f SB03OY.f MA02AD.f \ + MB03QY.f SB04PX.f MB04NY.f MB04OY.f SB03OV.f + +## L-inf norm +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slab13dd.cc \ + AB13DD.f MA02AD.f MB01SD.f MB03XD.f TB01ID.f \ + TG01AD.f TG01BD.f AB13DX.f MA01AD.f MA02ID.f \ + MB03XP.f MB04DD.f MB04QB.f MB04TB.f MB03XU.f \ + MB04TS.f UE01MD.f MB02RD.f MB02SD.f MB04QC.f \ + MB04QF.f MB03YA.f MB03YD.f MB02RZ.f MB04QU.f \ + MB02SZ.f MB03YT.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_place.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_place.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_place.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,19 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_place")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slsb01bd.cc \ + SB01BD.f MB03QD.f MB03QY.f SB01BX.f SB01BY.f \ + select.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_staircase.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_staircase.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_staircase.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,30 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_staircase")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +## staircase form using orthogonal transformations +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slab01od.cc \ + AB01OD.f AB01ND.f MB03OY.f MB01PD.f MB01QD.f + +## controllability staircase form of descriptor state-space models +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + sltg01hd.cc \ + TG01HD.f TG01HX.f + +## observability staircase form of descriptor state-space models +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + sltg01id.cc \ + TG01ID.f TB01XD.f MA02CD.f AB07MD.f TG01HX.f \ + MA02BD.f + +cd (homedir); \ No newline at end of file Added: trunk/octave-forge/main/control/devel/makefile_zero.m =================================================================== --- trunk/octave-forge/main/control/devel/makefile_zero.m (rev 0) +++ trunk/octave-forge/main/control/devel/makefile_zero.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -0,0 +1,25 @@ +## ============================================================================== +## Developer Makefile for OCT-files +## ============================================================================== +## USAGE: * fetch control from Octave-Forge by svn +## * add control/inst, control/src and control/devel to your Octave path +## * run makefile_* +## ============================================================================== + +homedir = pwd (); +develdir = fileparts (which ("makefile_zero")); +srcdir = [develdir, "/../src"]; +cd (srcdir); + +## transmission zeros of state-space models +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slab08nd.cc \ + AB08ND.f AB08NX.f TB01ID.f MB03OY.f MB03PY.f + +## transmission zeros of descriptor state-space models +mkoctfile "-Wl,-framework" "-Wl,vecLib" \ + slag08bd.cc \ + AG08BD.f AG08BY.f TG01AD.f TB01XD.f MA02CD.f \ + TG01FD.f MA02BD.f MB03OY.f + +cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_all.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_all.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_all.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,26 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_all")); -cd (srcdir); - -makefile_chol -makefile_h2syn -makefile_hankel -makefile_helpers -makefile_hinfsyn -makefile_lqr -makefile_lyap -makefile_minreal -makefile_norm -makefile_place -makefile_staircase -makefile_zero - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_chol.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_chol.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_chol.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,25 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_chol")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb03od.cc \ - SB03OD.f select.f SB03OU.f SB03OT.f MB04ND.f \ - MB04OD.f SB03OR.f SB03OY.f SB04PX.f MB04NY.f \ - MB04OY.f SB03OV.f - - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsg03bd.cc \ - SG03BD.f SG03BV.f SG03BU.f SG03BW.f SG03BX.f \ - SG03BY.f MB02UU.f MB02UV.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_h2syn.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_h2syn.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_h2syn.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,30 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_h2syn")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb10hd.cc \ - SB10HD.f SB10UD.f SB10VD.f SB10WD.f SB02RD.f \ - MB01RU.f SB02SD.f MA02ED.f SB02RU.f SB02MR.f \ - MB01SD.f SB02MS.f SB02MV.f SB02MW.f MA02AD.f \ - SB02QD.f MB02PD.f SB03QX.f SB03QY.f MB01RX.f \ - MB01RY.f SB03SX.f SB03SY.f select.f SB03MX.f \ - SB03MY.f MB01UD.f SB03MV.f SB03MW.f SB04PX.f - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb10ed.cc \ - SB10ED.f SB10SD.f SB10TD.f SB10PD.f MB01RX.f \ - SB02SD.f SB02OD.f MB01RU.f SB02OU.f SB02OV.f \ - SB02OW.f MB01RY.f SB02OY.f SB03SX.f SB03SY.f \ - MA02ED.f select.f SB03MX.f SB02MR.f SB02MV.f \ - MB01UD.f SB03MV.f SB04PX.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_hankel.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_hankel.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_hankel.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,21 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_hankel")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slab13ad.cc \ - AB13AD.f TB01ID.f TB01KD.f AB13AX.f MA02DD.f \ - MB03UD.f TB01LD.f SB03OU.f MB03QX.f select.f \ - SB03OT.f MB03QD.f MB04ND.f MB04OD.f MB03QY.f \ - SB03OR.f SB03OY.f SB04PX.f MB04NY.f MB04OY.f \ - SB03OV.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_helpers.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_helpers.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_helpers.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,21 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_helpers")); -cd (srcdir); - -mkoctfile is_real_scalar.cc - -mkoctfile is_real_vector.cc - -mkoctfile is_real_matrix.cc - -mkoctfile is_real_square_matrix.cc - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_hinfsyn.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_hinfsyn.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_hinfsyn.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,30 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_hinfsyn")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb10fd.cc \ - SB10FD.f SB10PD.f SB10QD.f SB10RD.f SB02RD.f \ - MB01RU.f MB01RX.f MA02AD.f SB02SD.f MA02ED.f \ - SB02RU.f SB02MR.f MB01SD.f SB02MS.f SB02MV.f \ - SB02MW.f SB02QD.f MB02PD.f SB03QX.f SB03QY.f \ - MB01RY.f SB03SX.f SB03SY.f select.f SB03MX.f \ - SB03MY.f MB01UD.f SB03MV.f SB03MW.f SB04PX.f - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb10dd.cc \ - SB10DD.f MB01RU.f MB01RX.f SB02SD.f SB02OD.f \ - MA02AD.f SB02OU.f SB02OV.f SB02OW.f MB01RY.f \ - SB02OY.f SB03SX.f SB03SY.f MA02ED.f select.f \ - SB03MX.f SB02MR.f SB02MV.f MB01UD.f SB03MV.f \ - SB04PX.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_lqr.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_lqr.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_lqr.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,23 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_lqr")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb02od.cc \ - SB02OD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ - SB02MR.f SB02MV.f - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsg02ad.cc \ - SG02AD.f SB02OU.f SB02OV.f SB02OW.f SB02OY.f \ - MB01SD.f MB02VD.f MB02PD.f MA02GD.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_lyap.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_lyap.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_lyap.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,36 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_lyap")); -cd (srcdir); - -## Lypunov -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb03md.cc \ - SB03MD.f select.f SB03MX.f SB03MY.f MB01RD.f \ - SB03MV.f SB03MW.f SB04PX.f - - -## Sylvester -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb04md.cc \ - SB04MD.f SB04MU.f SB04MY.f SB04MR.f SB04MW.f - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb04qd.cc \ - SB04QD.f SB04QU.f SB04QY.f SB04MW.f SB04QR.f - - -## Generalized Lyapunov -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsg03ad.cc \ - SG03AD.f MB01RW.f MB01RD.f SG03AX.f SG03AY.f \ - MB02UU.f MB02UV.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_minreal.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_minreal.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_minreal.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,22 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_minreal")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - sltb01pd.cc \ - TB01PD.f TB01XD.f TB01ID.f AB07MD.f TB01UD.f \ - MB03OY.f MB01PD.f MB01QD.f - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - sltg01jd.cc \ - TG01JD.f TG01AD.f TB01XD.f MA02CD.f TG01HX.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_norm.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_norm.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_norm.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,31 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_norm")); -cd (srcdir); - -## H-2 norm -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slab13bd.cc \ - AB13BD.f SB08DD.f SB03OU.f SB01FY.f TB01LD.f \ - SB03OT.f MB04ND.f MB04OD.f MB03QX.f select.f \ - SB03OR.f MB04OX.f MB03QD.f SB03OY.f MA02AD.f \ - MB03QY.f SB04PX.f MB04NY.f MB04OY.f SB03OV.f - -## L-inf norm -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slab13dd.cc \ - AB13DD.f MA02AD.f MB01SD.f MB03XD.f TB01ID.f \ - TG01AD.f TG01BD.f AB13DX.f MA01AD.f MA02ID.f \ - MB03XP.f MB04DD.f MB04QB.f MB04TB.f MB03XU.f \ - MB04TS.f UE01MD.f MB02RD.f MB02SD.f MB04QC.f \ - MB04QF.f MB03YA.f MB03YD.f MB02RZ.f MB04QU.f \ - MB02SZ.f MB03YT.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_place.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_place.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_place.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,18 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_place")); -cd (srcdir); - -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slsb01bd.cc \ - SB01BD.f MB03QD.f MB03QY.f SB01BX.f SB01BY.f \ - select.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_staircase.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_staircase.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_staircase.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,29 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_staircase")); -cd (srcdir); - -## staircase form using orthogonal transformations -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slab01od.cc \ - AB01OD.f AB01ND.f MB03OY.f MB01PD.f MB01QD.f - -## controllability staircase form of descriptor state-space models -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - sltg01hd.cc \ - TG01HD.f TG01HX.f - -## observability staircase form of descriptor state-space models -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - sltg01id.cc \ - TG01ID.f TB01XD.f MA02CD.f AB07MD.f TG01HX.f \ - MA02BD.f - -cd (homedir); \ No newline at end of file Deleted: trunk/octave-forge/main/control/src/makefile_zero.m =================================================================== --- trunk/octave-forge/main/control/src/makefile_zero.m 2010-10-04 21:21:03 UTC (rev 7801) +++ trunk/octave-forge/main/control/src/makefile_zero.m 2010-10-05 06:29:05 UTC (rev 7802) @@ -1,24 +0,0 @@ -## ============================================================================== -## Developer Makefile for OCT-files -## ============================================================================== -## USAGE: * fetch control from Octave-Forge by svn -## * add control/inst and control/src to your Octave path -## * run makefile_* -## ============================================================================== - -homedir = pwd (); -srcdir = fileparts (which ("makefile_zero")); -cd (srcdir); - -## transmission zeros of state-space models -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slab08nd.cc \ - AB08ND.f AB08NX.f TB01ID.f MB03OY.f MB03PY.f - -## transmission zeros of descriptor state-space models -mkoctfile "-Wl,-framework" "-Wl,vecLib" \ - slag08bd.cc \ - AG08BD.f AG08BY.f TG01AD.f TB01XD.f MA02CD.f \ - TG01FD.f MA02BD.f MB03OY.f - -cd (homedir); \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-06 21:59:35
|
Revision: 7810 http://octave.svn.sourceforge.net/octave/?rev=7810&view=rev Author: paramaniac Date: 2010-10-06 21:59:28 +0000 (Wed, 06 Oct 2010) Log Message: ----------- control: revert accidental changes Modified Paths: -------------- trunk/octave-forge/main/control/devel/RELEASE_PACKAGE trunk/octave-forge/main/control/inst/ltimodels.m Modified: trunk/octave-forge/main/control/devel/RELEASE_PACKAGE =================================================================== --- trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2010-10-06 21:22:55 UTC (rev 7809) +++ trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2010-10-06 21:59:28 UTC (rev 7810) @@ -1,9 +1,10 @@ ===================================================================================== Prepare control-2.0 Package for Release ===================================================================================== -USAGE: * update version number in the commands below +USAGE: * adapt all paths to your machine + * update version number in the commands below * copy-paste entire block at once to the terminal - * <http://octave.sourceforge.net/developers.html> + * follow instructions on <http://octave.sourceforge.net/developers.html> TODO: * create a nice shell script for this task ===================================================================================== Modified: trunk/octave-forge/main/control/inst/ltimodels.m =================================================================== --- trunk/octave-forge/main/control/inst/ltimodels.m 2010-10-06 21:22:55 UTC (rev 7809) +++ trunk/octave-forge/main/control/inst/ltimodels.m 2010-10-06 21:59:28 UTC (rev 7810) @@ -295,9 +295,83 @@ %!assert (M, Me, 1e-4); +## dss: minreal (SLICOT TG01JD) +%!shared Ar, Br, Cr, Dr, Er, Ae, Be, Ce, De, Ee +%! A = [ -2 -3 0 0 0 0 0 0 0 +%! 1 0 0 0 0 0 0 0 0 +%! 0 0 -2 -3 0 0 0 0 0 +%! 0 0 1 0 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 1 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 +%! 0 0 0 0 0 0 0 0 1 ]; +%! +%! E = [ 1 0 0 0 0 0 0 0 0 +%! 0 1 0 0 0 0 0 0 0 +%! 0 0 1 0 0 0 0 0 0 +%! 0 0 0 1 0 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 0 1 0 0 0 0 +%! 0 0 0 0 0 0 0 0 0 +%! 0 0 0 0 0 0 1 0 0 +%! 0 0 0 0 0 0 0 1 0 ]; +%! +%! B = [ 1 0 +%! 0 0 +%! 0 1 +%! 0 0 +%! -1 0 +%! 0 0 +%! 0 -1 +%! 0 0 +%! 0 0 ]; +%! +%! C = [ 1 0 1 -3 0 1 0 2 0 +%! 0 1 1 3 0 1 0 0 1 ]; +%! +%! D = zeros (2, 2); +%! +%! sys = dss (A, B, C, D, E); +%! sysmin = minreal (sys, 0.0); +%! [Ar, Br, Cr, Dr, Er] = dssdata (sysmin); +%! +%! Ae = [ 1.0000 -0.0393 -0.0980 -0.1066 0.0781 -0.2330 0.0777 +%! 0.0000 1.0312 0.2717 0.2609 -0.1533 0.6758 -0.3553 +%! 0.0000 0.0000 1.3887 0.6699 -0.4281 1.6389 -0.7615 +%! 0.0000 0.0000 0.0000 -1.2147 0.2423 -0.9792 0.4788 +%! 0.0000 0.0000 0.0000 0.0000 -1.0545 0.5035 -0.2788 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.6355 -0.4323 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%! Ee = [ 0.4100 0.2590 0.5080 -0.3109 0.0705 0.1429 -0.1477 +%! -0.7629 -0.3464 0.0992 -0.3007 0.0619 0.2483 -0.0152 +%! 0.1120 -0.2124 -0.4184 -0.1288 0.0569 -0.4213 -0.6182 +%! 0.0000 0.1122 -0.0039 0.2771 -0.0758 0.0975 0.3923 +%! 0.0000 0.0000 0.3708 -0.4290 0.1006 0.1402 -0.2699 +%! 0.0000 0.0000 0.0000 0.0000 0.9458 -0.2211 0.2378 +%! 0.0000 0.0000 0.0000 0.5711 0.2648 0.5948 -0.5000 ]; +%! +%! Be = [ -0.5597 0.2363 +%! -0.4843 -0.0498 +%! -0.4727 -0.1491 +%! 0.1802 1.1574 +%! 0.5995 0.1556 +%! -0.1729 -0.3999 +%! 0.0000 0.2500 ]; +%! +%! Ce = [ 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 4.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 3.1524 -1.7500 ]; +%! +%! De = zeros (2, 2); +%! +%!assert (Ar, Ae, 1e-4); +%!assert (Br, Be, 1e-4); +%!assert (Cr, Ce, 1e-4); +%!assert (Dr, De, 1e-4); +%!assert (Er, Ee, 1e-4); - ## ss: sminreal %!shared B, C %! @@ -427,11 +501,184 @@ %!assert (Bc, Bce, 1e-4); +## controllability staircase form of descriptor state-space models (SLICOT TG01HD) +%!shared ac, ec, bc, cc, q, z, ncont, ac_e, ec_e, bc_e, cc_e, q_e, z_e, ncont_e +%! +%! a = [ 2 0 2 0 -1 3 1 +%! 0 1 0 0 1 0 0 +%! 0 0 0 1 0 0 1 +%! 0 0 2 0 -1 3 1 +%! 0 0 0 1 0 0 1 +%! 0 1 0 0 1 0 0 +%! 0 0 0 1 0 0 1 ]; +%! +%! e = [ 0 0 1 0 0 0 0 +%! 0 0 0 0 0 1 0 +%! 0 0 0 0 0 0 1 +%! 0 0 0 0 0 0 1 +%! 0 0 0 1 0 0 0 +%! 0 0 1 0 -1 0 0 +%! 1 3 0 2 0 0 0 ]; +%! +%! b = [ 2 1 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 0 0 0 +%! 1 2 3 ]; +%! +%! c = [ 1 0 0 1 0 0 1 +%! 0 -1 1 0 -1 1 0 ]; +%! +%! tol = 0; +%! +%! [ac, ec, bc, cc, q, z, ncont] = sltg01hd (a, e, b, c, tol); +%! +%! ncont_e = 3; +%! +%! ac_e = [ 0.0000 0.0000 0.0000 0.0000 -1.2627 0.4334 0.4666 +%! 0.0000 2.0000 0.0000 -3.7417 -0.8520 0.2924 -0.4342 +%! 0.0000 0.0000 1.7862 0.3780 -0.2651 -0.7723 0.0000 +%! 0.0000 0.0000 0.0000 3.7417 0.8520 -0.2924 0.4342 +%! 0.0000 0.0000 0.0000 0.0000 -1.5540 0.5334 0.5742 +%! 0.0000 0.0000 0.0000 0.0000 -0.6533 0.2242 0.2414 +%! 0.0000 0.0000 0.0000 0.0000 -0.5892 0.2022 0.2177 ]; +%! +%! ec_e = [ -1.8325 1.0000 2.3752 0.0000 -0.8214 0.2819 1.8016 +%! 0.4887 0.0000 0.3770 -0.5345 0.1874 0.5461 0.0000 +%! -0.1728 0.0000 -0.1333 -1.1339 0.1325 0.3861 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.8520 -0.2924 0.4342 +%! 0.0000 0.0000 0.0000 0.0000 -1.0260 -0.1496 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.1937 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%! bc_e = [ 1.0000 2.0000 3.0000 +%! 2.0000 1.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 ]; +%! +%! cc_e = [ 0.0000 1.0000 0.0000 0.0000 -1.2627 0.4334 0.4666 +%! 0.3665 0.0000 -0.9803 -1.6036 0.1874 0.5461 0.0000 ]; +%! +%! q_e = [ 0.0000 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.7071 0.0000 0.2740 -0.6519 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.8304 0.3491 -0.4342 +%! 0.0000 0.0000 0.0000 -1.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.4003 0.1683 0.9008 +%! 0.0000 0.0000 0.7071 0.0000 -0.2740 0.6519 0.0000 +%! 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! z_e = [ 0.0000 1.0000 0.0000 0.0000 0.0000 0.0000 0.0000 +%! -0.6108 0.0000 0.7917 0.0000 0.0000 0.0000 0.0000 +%! 0.4887 0.0000 0.3770 -0.5345 0.1874 0.5461 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.4107 0.1410 0.9008 +%! 0.6108 0.0000 0.4713 0.2673 -0.1874 -0.5461 0.0000 +%! -0.1222 0.0000 -0.0943 -0.8018 -0.1874 -0.5461 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.8520 0.2924 -0.4342 ]; +%! +%!assert (ac, ac_e, 1e-4); +%!assert (ec, ec_e, 1e-4); +%!assert (bc, bc_e, 1e-4); +%!assert (cc, cc_e, 1e-4); +%!assert (q, q_e, 1e-4); +%!assert (z, z_e, 1e-4); +%!assert (ncont, ncont_e); +## observability staircase form of descriptor state-space models (SLICOT TG01ID) +%!shared ao, eo, bo, co, q, z, nobsv, ao_e, eo_e, bo_e, co_e, q_e, z_e, nobsv_e +%! +%! a = [ 2 0 0 0 0 0 0 +%! 0 1 0 0 0 1 0 +%! 2 0 0 2 0 0 0 +%! 0 0 1 0 1 0 1 +%! -1 1 0 -1 0 1 0 +%! 3 0 0 3 0 0 0 +%! 1 0 1 1 1 0 1 ]; +%! +%! e = [ 0 0 0 0 0 0 1 +%! 0 0 0 0 0 0 3 +%! 1 0 0 0 0 1 0 +%! 0 0 0 0 1 0 2 +%! 0 0 0 0 0 -1 0 +%! 0 1 0 0 0 0 0 +%! 0 0 1 1 0 0 0 ]; +%! +%! b = [ 1 0 +%! 0 -1 +%! 0 1 +%! 1 0 +%! 0 -1 +%! 0 1 +%! 1 0 ]; +%! +%! c = [ 2 0 0 0 0 0 1 +%! 1 0 0 0 0 0 2 +%! 0 0 0 0 0 0 3 ]; +%! +%! tol = 0; +%! +%! [ao, eo, bo, co, q, z, nobsv] = sltg01id (a, e, b, c, tol); +%! +%! nobsv_e = 3; +%! +%! ao_e = [ 0.2177 0.2414 0.5742 0.4342 0.0000 -0.4342 0.4666 +%! 0.2022 0.2242 0.5334 -0.2924 -0.7723 0.2924 0.4334 +%! -0.5892 -0.6533 -1.5540 0.8520 -0.2651 -0.8520 -1.2627 +%! 0.0000 0.0000 0.0000 3.7417 0.3780 -3.7417 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 1.7862 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 2.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! eo_e = [ 1.0000 0.0000 0.0000 0.4342 0.0000 0.0000 1.8016 +%! 0.0000 1.1937 -0.1496 -0.2924 0.3861 0.5461 0.2819 +%! 0.0000 0.0000 -1.0260 0.8520 0.1325 0.1874 -0.8214 +%! 0.0000 0.0000 0.0000 0.0000 -1.1339 -0.5345 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.1333 0.3770 2.3752 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 +%! 0.0000 0.0000 0.0000 0.0000 -0.1728 0.4887 -1.8325 ]; +%! +%! bo_e = [ 0.4666 0.0000 +%! 0.4334 0.5461 +%! -1.2627 0.1874 +%! 0.0000 -1.6036 +%! 0.0000 -0.9803 +%! 1.0000 0.0000 +%! 0.0000 0.3665 ]; +%! +%! co_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 2.0000 1.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 2.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 3.0000 ]; +%! +%! q_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.7917 0.0000 -0.6108 +%! 0.0000 0.5461 0.1874 -0.5345 0.3770 0.0000 0.4887 +%! 0.9008 0.1410 -0.4107 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 -0.5461 -0.1874 0.2673 0.4713 0.0000 0.6108 +%! 0.0000 -0.5461 -0.1874 -0.8018 -0.0943 0.0000 -0.1222 +%! -0.4342 0.2924 -0.8520 0.0000 0.0000 0.0000 0.0000 ]; +%! +%! z_e = [ 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 0.0000 +%! 0.0000 -0.6519 0.2740 0.0000 0.7071 0.0000 0.0000 +%! -0.4342 0.3491 0.8304 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 -1.0000 0.0000 0.0000 0.0000 +%! 0.9008 0.1683 0.4003 0.0000 0.0000 0.0000 0.0000 +%! 0.0000 0.6519 -0.2740 0.0000 0.7071 0.0000 0.0000 +%! 0.0000 0.0000 0.0000 0.0000 0.0000 0.0000 1.0000 ]; +%! +%!assert (ao, ao_e, 1e-4); +%!assert (eo, eo_e, 1e-4); +%!assert (bo, bo_e, 1e-4); +%!assert (co, co_e, 1e-4); +%!assert (q, q_e, 1e-4); +%!assert (z, z_e, 1e-4); +%!assert (nobsv, nobsv_e); - ## Cascade inter-connection of two systems in state-space form ## Test from SLICOT AB05MD ## TODO: order of united state vector: consistency vs. compatibility? This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-09 00:57:24
|
Revision: 7819 http://octave.svn.sourceforge.net/octave/?rev=7819&view=rev Author: paramaniac Date: 2010-10-09 00:57:17 +0000 (Sat, 09 Oct 2010) Log Message: ----------- control: various additions and fixes, related to frequency response Modified Paths: -------------- trunk/octave-forge/main/control/devel/frd_test.m trunk/octave-forge/main/control/inst/@lti/tfdata.m trunk/octave-forge/main/control/inst/@ss/__freqresp__.m trunk/octave-forge/main/control/inst/__frequency_response__.m Added Paths: ----------- trunk/octave-forge/main/control/devel/@frd/__freqresp__.m trunk/octave-forge/main/control/devel/@frd/__get__.m trunk/octave-forge/main/control/devel/@frd/__sys_data__.m trunk/octave-forge/main/control/inst/@lti/frdata.m Added: trunk/octave-forge/main/control/devel/@frd/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__freqresp__.m (rev 0) +++ trunk/octave-forge/main/control/devel/@frd/__freqresp__.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -0,0 +1,72 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## Frequency response of FRD models :-) + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function H = __freqresp__ (sys, w, resptype = 0, cellflag = false) + + ## TODO: handle case dcgain (frdsys) + +% if (! isempty (w)) +% error ("frd: freqresp: frequency vector w must be empty"); +% endif + + H = __sys_data__ (sys); + + [p, m, l] = size (H); + + if (resptype == 0) + + if (cellflag) + H = mat2cell (H, p, m, ones (1, l))(:); + endif + + else + + if (m != p) + error ("tf: freqresp: system must be square for response type %d", resptype); + endif + + H = mat2cell (H, p, m, ones (1, l))(:); + j = eye (p); + + switch (resptype) + case 1 # inversed system + H = cellfun (@inv, H, "uniformoutput", false); + + case 2 # inversed sensitivity + H = cellfun (@(x) j + x, H, "uniformoutput", false); + + case 3 # inversed complementary sensitivity + H = cellfun (@(x) j + inv (x), H, "uniformoutput", false); + + otherwise + error ("frd: freqresp: invalid response type"); + endswitch + + if (! cellflag) + H = cat (3, H{:}); + endif + + endif + +endfunction Added: trunk/octave-forge/main/control/devel/@frd/__get__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__get__.m (rev 0) +++ trunk/octave-forge/main/control/devel/@frd/__get__.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -0,0 +1,39 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## Access property values of FRD objects. + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function val = __get__ (sys, prop) + + switch (prop) # {<internal name>, <user name>} + case {"h", "r", "resp", "response"} + val = sys.H; + + case {"w", "f", "freq", "frequency"} + val = sys.w; + + otherwise + error ("frd: get: invalid property name"); + + endswitch + +endfunction \ No newline at end of file Added: trunk/octave-forge/main/control/devel/@frd/__sys_data__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_data__.m (rev 0) +++ trunk/octave-forge/main/control/devel/@frd/__sys_data__.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -0,0 +1,30 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## Used by frdata instead of multiple get calls. + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function [H, w] = __sys_data__ (sys) + + H = sys.H; + w = sys.w; + +endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/devel/frd_test.m =================================================================== --- trunk/octave-forge/main/control/devel/frd_test.m 2010-10-08 22:17:19 UTC (rev 7818) +++ trunk/octave-forge/main/control/devel/frd_test.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -6,4 +6,54 @@ frd -frd ([], []) \ No newline at end of file +frd ([], []) + + + +P_ss = Boeing707; +w = logspace (-2, 2, 500); +H = freqresp (P_ss, w); +P_frd = frd (H, w); + +figure (1) +subplot (2, 1, 1) +sigma (P_ss) +subplot (2, 1, 2) +sigma (P_frd) + +figure (2) +subplot (2, 1, 1) +sigma (P_ss, [], 1) +subplot (2, 1, 2) +sigma (P_frd, [], 1) + +figure (3) +subplot (2, 1, 1) +sigma (P_ss, [], 2) +subplot (2, 1, 2) +sigma (P_frd, [], 2) + +figure (4) +subplot (2, 1, 1) +sigma (P_ss, [], 3) +subplot (2, 1, 2) +sigma (P_frd, [], 3) + + + +%{ +P = frd ((1:45)*(1-2i), logspace (-2,3,45)) + +figure (1) +sigma (P) +sigma (P, [], 0) + +figure (2) +sigma (P, [], 1) + +figure (3) +sigma (P, [], 2) + +figure (4) +sigma (P, [], 3) +%} \ No newline at end of file Added: trunk/octave-forge/main/control/inst/@lti/frdata.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/frdata.m (rev 0) +++ trunk/octave-forge/main/control/inst/@lti/frdata.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -0,0 +1,42 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## @deftypefn {Function File} {[@var{H}, @var{w}, @var{tsam}] =} frdata (@var{sys}) +## @deftypefnx {Function File} {[@var{H}, @var{w}, @var{tsam}] =} frdata (@var{sys}, @var{"vector"}) +## Access frequency response data. +## @end deftypefn + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function [H, w, tsam] = frdata (sys, rtype = "vector") + + if (! isa (sys, "frd")) + sys = frd (sys); + endif + + [H, w] = __sys_data__ (sys); + + tsam = sys.tsam; + + if (rtype(1) == "v") + H = reshape (H, [], 1); + endif + +endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@lti/tfdata.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/tfdata.m 2010-10-08 22:17:19 UTC (rev 7818) +++ trunk/octave-forge/main/control/inst/@lti/tfdata.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -35,7 +35,7 @@ tsam = sys.tsam; - if (rtype == "vector") + if (rtype(1) == "v") num = cellfun ("@tfpoly/get", num, "uniformoutput", false); den = cellfun ("@tfpoly/get", den, "uniformoutput", false); endif Modified: trunk/octave-forge/main/control/inst/@ss/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-08 22:17:19 UTC (rev 7818) +++ trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -26,9 +26,7 @@ [a, b, c, d, e, tsam] = dssdata (sys); - j = eye (columns (b)); - - if (resptype != 0 && m != p) + if (resptype != 0 && columns (b) != rows (c)) error ("ss: freqresp: system must be square for response type %d", resptype); endif @@ -46,9 +44,11 @@ H = cellfun (@(x) inv (c/(x*e - a)*b + d), s, "uniformoutput", false); case 2 # inversed sensitivity + j = eye (columns (b)); H = cellfun (@(x) j + c/(x*e - a)*b + d, s, "uniformoutput", false); case 3 # inversed complementary sensitivity + j = eye (columns (b)); H = cellfun (@(x) j + inv (c/(x*e - a)*b + d), s, "uniformoutput", false); otherwise Modified: trunk/octave-forge/main/control/inst/__frequency_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-10-08 22:17:19 UTC (rev 7818) +++ trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-10-09 00:57:17 UTC (rev 7819) @@ -34,13 +34,21 @@ error ("frequency_response: require SISO system"); endif - ## find interesting frequency range w if not specified - if (isempty (w)) - ## begin plot at 10^dec_min, end plot at 10^dec_max [rad/s] - [dec_min, dec_max] = __frequency_range__ (sys, wbounds); - w = logspace (dec_min, dec_max, 500); # [rad/s] - elseif (! is_real_vector (w)) - error ("frequency_response: second argument w must be a vector of frequencies"); + if (isa (sys, "frd")) + if (isempty (w)) + w = get (sys, "w"); + else + warning ("frequency_response: second argument w is ignored"); + endif + else + ## find interesting frequency range w if not specified + if (isempty (w)) + ## begin plot at 10^dec_min, end plot at 10^dec_max [rad/s] + [dec_min, dec_max] = __frequency_range__ (sys, wbounds); + w = logspace (dec_min, dec_max, 500); # [rad/s] + elseif (! is_real_vector (w)) + error ("frequency_response: second argument w must be a vector of frequencies"); + endif endif ## frequency response This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-09 01:16:32
|
Revision: 7820 http://octave.svn.sourceforge.net/octave/?rev=7820&view=rev Author: paramaniac Date: 2010-10-09 01:16:26 +0000 (Sat, 09 Oct 2010) Log Message: ----------- control: add sys2frd conversions Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/frd.m Added Paths: ----------- trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-09 00:57:17 UTC (rev 7819) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-09 01:16:26 UTC (rev 7820) @@ -38,15 +38,19 @@ tsam = -1; case 1 - if (isa (H, "frd")) # already in frd form + if (isa (H, "frd")) # already in frd form sys = H; return; + elseif (isa (H, "lti")) # another lti object sys = frd (sys) + [sys, alti] = __sys2frd__ (H); + sys.lti = alti; # preserve lti properties + return; else print_usage (); endif case 2 - if (isa (H, "lti")) # another lti object + if (isa (H, "lti")) # another lti object sys = frd (sys, w) [sys, alti] = __sys2frd__ (H, w); sys.lti = alti; # preserve lti properties return; Added: trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m (rev 0) +++ trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m 2010-10-09 01:16:26 UTC (rev 7820) @@ -0,0 +1,37 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## SS to FRD conversion. + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function [retsys, retlti] = __sys2frd__ (sys, w = []) + + if (isempty (w)) + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); + endif + + H = __freqresp__ (sys, w); + + retsys = frd (H, w); # tsam is set below + retlti = sys.lti; # preserve lti properties + +endfunction \ No newline at end of file Added: trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m (rev 0) +++ trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m 2010-10-09 01:16:26 UTC (rev 7820) @@ -0,0 +1,37 @@ +## Copyright (C) 2010 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this program. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## TF to FRD conversion. + +## Author: Lukas Reichlin <luk...@gm...> +## Created: October 2010 +## Version: 0.1 + +function [retsys, retlti] = __sys2frd__ (sys, w = []) + + if (isempty (w)) + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); + endif + + H = __freqresp__ (sys, w); + + retsys = frd (H, w); # tsam is set below + retlti = sys.lti; # preserve lti properties + +endfunction \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-10 08:20:25
|
Revision: 7834 http://octave.svn.sourceforge.net/octave/?rev=7834&view=rev Author: paramaniac Date: 2010-10-10 08:20:19 +0000 (Sun, 10 Oct 2010) Log Message: ----------- control: various fixes related to sampling times Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/devel/__adjust_frd_data__.m trunk/octave-forge/main/control/devel/__frd_dim__.m trunk/octave-forge/main/control/devel/test_frd.m trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m trunk/octave-forge/main/control/inst/@ss/ss.m trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m trunk/octave-forge/main/control/inst/@tf/tf.m trunk/octave-forge/main/control/inst/issample.m Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -45,6 +45,9 @@ [sys, alti] = __sys2frd__ (H); sys.lti = alti; # preserve lti properties return; + elseif (is_real_matrix (H)) # static gain sys = frd (M) + w = -1; + tsam = -1; else print_usage (); endif @@ -61,7 +64,7 @@ otherwise # default case argc = numel (varargin); - if (issample (varargin{1}, 1)) # sys = frd (H, w, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, 0)) # sys = frd (H, w, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; if (argc > 0) Modified: trunk/octave-forge/main/control/devel/__adjust_frd_data__.m =================================================================== --- trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -25,6 +25,8 @@ function [H, w, tsam] = __adjust_frd_data__ (H, w, tsam); + w = reshape (w, [], 1); + if (ndims (H) != 3 && ! isempty (H)) if (is_real_scalar (H)) # static gain (H is a real scalar) H = reshape (H, 1, 1, []); @@ -46,6 +48,4 @@ tsam = -1; endif - w = reshape (w, [], 1); - endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/devel/__frd_dim__.m =================================================================== --- trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -34,7 +34,7 @@ if (lw > 1 && (! is_real_vector (w) || any (w < 0) \ || ! issorted (w) || w(1) >= w(end) || length (unique (w)) != lw)) error ("frd: w must be a vector of positive real numbers"); - elseif (lw == 1 && ! issample (w, -1)) + elseif (lw == 1 && (! issample (w, -1) || (iscomplex (H) && ! issample (w, 0)))) error ("frd: scalar w must be a valid sampling time"); endif Modified: trunk/octave-forge/main/control/devel/test_frd.m =================================================================== --- trunk/octave-forge/main/control/devel/test_frd.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/devel/test_frd.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -8,8 +8,10 @@ sys5 = frd ([], []) +sys6 = frd ([1, 2; 3, 4]) + P_ss = Boeing707; w = logspace (-2, 2, 500); H = freqresp (P_ss, w); @@ -76,6 +78,12 @@ subplot (2, 1, 2) sigma (T_frd * P_frd) + +k1 = frd (ss ([1, 2; 3, 4])) +% k2 = frd (tf ([1, 2; 3, 4])) +k2 = frd (tf (5)) + + %{ P = frd ((1:45)*(1-2i), logspace (-2,3,45)) Modified: trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -24,9 +24,14 @@ function [retsys, retlti] = __sys2frd__ (sys, w = []) - if (isempty (w)) - [dec_min, dec_max] = __frequency_range__ (sys); - w = logspace (dec_min, dec_max, 500); + if (isempty (w)) # case sys = frd (sys) + tsam = get (sys, "tsam"); + if (tsam == -1) # static gain + w = -1; # value is insignificant + else # dynamic system + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); + endif endif H = __freqresp__ (sys, w); Modified: trunk/octave-forge/main/control/inst/@ss/ss.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -100,7 +100,7 @@ [b, c] = __gain_check__ (b, c, d); argc = numel (varargin); - if (issample (varargin{1}, 1)) # sys = ss (a, b, c, d, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, 0)) # sys = ss (a, b, c, d, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; if (argc > 0) Modified: trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -24,9 +24,14 @@ function [retsys, retlti] = __sys2frd__ (sys, w = []) - if (isempty (w)) - [dec_min, dec_max] = __frequency_range__ (sys); - w = logspace (dec_min, dec_max, 500); + if (isempty (w)) # case sys = frd (sys) + tsam = get (sys, "tsam"); + if (tsam == -1) # static gain + w = -1; # value is insignificant + else # dynamic system + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); + endif endif H = __freqresp__ (sys, w); Modified: trunk/octave-forge/main/control/inst/@tf/tf.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -114,7 +114,7 @@ den = __vec2tfpoly__ (den); argc = numel (varargin); - if (issample (varargin{1}, 1)) # sys = tf (num, den, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, 0)) # sys = tf (num, den, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; Modified: trunk/octave-forge/main/control/inst/issample.m =================================================================== --- trunk/octave-forge/main/control/inst/issample.m 2010-10-09 20:27:54 UTC (rev 7833) +++ trunk/octave-forge/main/control/inst/issample.m 2010-10-10 08:20:19 UTC (rev 7834) @@ -15,11 +15,28 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## @deftypefn {Function File} {} issample (@var{ts}) -## @deftypefnx {Function File} {} issample (@var{ts}, @var{flg}) -## Return true if @var{ts} is a valid sampling time -## (real, scalar, > 0). If a second argument != 0 -## is passed, -1 and 0 become valid sample times as well. +## @deftypefn {Function File} {@var{bool} =} issample (@var{ts}) +## @deftypefnx {Function File} {@var{bool} =} issample (@var{ts}, @var{flg}) +## Return true if @var{ts} is a valid sampling time. +## +## @strong{Inputs} +## @table @var +## @item ts +## Alleged sampling time to be tested. +## @item flg = 1 +## Accept real scalars @var{ts} > 0. Default Value. +## @item flg = 0 +## Accept real scalars @var{ts} >= 0. +## @item flg = -1 +## Accept real scalars @var{ts} >= 0 and @var{ts} == -1. +## @end table +## +## @strong{Outputs} +## @table @var +## @item bool +## True if conditions are met and false otherwise. +## @end table +## ## @end deftypefn ## Author: A. S. Hodel <a.s...@en...> @@ -27,39 +44,62 @@ ## Adapted-By: Lukas Reichlin <luk...@gm...> ## Date: September 2009 -## Version: 0.2 +## Version: 0.3 -function bool = issample (tsam, flg = 0) +function bool = issample (tsam, flg = 1) if (nargin < 1 || nargin > 2) print_usage (); endif - if (flg == 0) # refuse -1 and 0 - bool = is_real_scalar (tsam) && (tsam > 0); - else # allow -1 and 0 - bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1); - endif + switch (flg) + case 1 # refuse -1 and 0 + bool = is_real_scalar (tsam) && (tsam > 0); + case 0 # allow 0, refuse -1 + bool = is_real_scalar (tsam) && (tsam >= 0); + case -1 # allow -1 and 0 + bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1); + otherwise + print_usage (); + endswitch endfunction -## flg == 0 +## flg == 1 %!assert (issample (1), true) %!assert (issample (pi), true) %!assert (issample (0), false) %!assert (issample (-1), false) -%!assert (issample (-1, 0), false) +%!assert (issample (-1, 1), false) %!assert (issample ("a"), false) %!assert (issample (eye (2)), false) %!assert (issample (2+2i), false) -## flg != 0 -%!assert (issample (-1, 1), true) +## flg == 0 +%!assert (issample (1, 0), true) +%!assert (issample (0, 0), true) +%!assert (issample (-1, 0), false) +%!assert (issample (pi, 0), true) +%!assert (issample ("b", 0), false) +%!assert (issample (rand (3,2), 0), false) +%!assert (issample (2+2i, 0), false) +%!assert (issample (0+2i, 0), false) + +## flg == -1 %!assert (issample (-1, -1), true) -%!assert (issample (pi, 1), true) -%!assert (issample (0, 1), true) -%!assert (issample ("b", 1), false) -%!assert (issample (-1, "ab"), true) -%!assert (issample (rand (3,2), 1), false) -%!assert (issample (2+2i, 1), false) +%!assert (issample (0, -1), true) +%!assert (issample (1, -1), true) +%!assert (issample (pi, -1), true) +%!assert (issample (-pi, -1), false) +%!assert (issample ("b", -1), false) +%!assert (issample (rand (3,2), -1), false) +%!assert (issample (-2+2i, -1), false) + +## errors +%!error (issample (-1, "ab")) +%!error (issample ()) +%!error (issample (-1, -1, -1)) +%!error (issample (1, pi)) +%!error (issample (5, rand (2,3))) +%!error (issample (0, 1+2i)) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-10 10:08:32
|
Revision: 7835 http://octave.svn.sourceforge.net/octave/?rev=7835&view=rev Author: paramaniac Date: 2010-10-10 10:08:25 +0000 (Sun, 10 Oct 2010) Log Message: ----------- control: fix design flaw (frd objects are measurements, not models) Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/__c2d__.m trunk/octave-forge/main/control/devel/@frd/__freqresp__.m trunk/octave-forge/main/control/devel/@frd/__minreal__.m trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m trunk/octave-forge/main/control/devel/@frd/__transpose__.m trunk/octave-forge/main/control/devel/@frd/display.m trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/devel/PROJECTS trunk/octave-forge/main/control/devel/__adjust_frd_data__.m trunk/octave-forge/main/control/devel/__frd_dim__.m trunk/octave-forge/main/control/devel/test_frd.m trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m Modified: trunk/octave-forge/main/control/devel/@frd/__c2d__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__c2d__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/__c2d__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,7 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Convert the continuous FRD model into its discrete-time equivalent. +## Convert the continuous FRD object into its discrete-time equivalent. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2010 Modified: trunk/octave-forge/main/control/devel/@frd/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__freqresp__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/__freqresp__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -27,23 +27,19 @@ [H, w_sys, tsam] = frdata (sys, "array"); if (! isempty (w)) # freqresp (frdsys, w), sigma (frdsys, w), ... - if (tsam == -1) # static gains - H = repmat (H, [1, 1, length(w)]); - else - tol = sqrt (eps); - w = num2cell (w); # use oct-file cellfun instead of m-file arrayfun - w_idx = cellfun (@(x) find (abs (w_sys - x) < tol), w, "uniformoutput", false); - w_idx = vertcat (w_idx{:}); + tol = sqrt (eps); + w = num2cell (w); # use oct-file cellfun instead of m-file arrayfun + w_idx = cellfun (@(x) find (abs (w_sys - x) < tol), w, "uniformoutput", false); + w_idx = vertcat (w_idx{:}); - ## NOTE: There are problems when cellfun uses "uniformoutput", true - ## and find returns an empty matrix, + ## NOTE: There are problems when cellfun uses "uniformoutput", true + ## and find returns an empty matrix, - if (length (w_idx) != numel (w)) - error ("frd: freqresp: some frequencies are not within tolerance %g", tol); - endif - - H = H(:, :, w_idx); + if (length (w_idx) != numel (w)) + error ("frd: freqresp: some frequencies are not within tolerance %g", tol); endif + + H = H(:, :, w_idx); endif [p, m, l] = size (H); Modified: trunk/octave-forge/main/control/devel/@frd/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__minreal__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/__minreal__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,7 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Minimal realization of FRD models. +## Minimal realization of FRD objects. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2010 Modified: trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,7 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Inversion of FRD models. +## Inversion of FRD objects. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2010 Modified: trunk/octave-forge/main/control/devel/@frd/__transpose__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__transpose__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/__transpose__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,7 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Transpose of FRD models. +## Transpose of FRD objects. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2010 Modified: trunk/octave-forge/main/control/devel/@frd/display.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,7 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Display routine for SS objects. +## Display routine for FRD objects. ## Author: Lukas Reichlin <luk...@gm...> ## Created: February 2010 Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -16,7 +16,8 @@ ## along with this program. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## @deftypefn {Function File} {@var{sys} =} frd (@var{sys}, @var{w}) +## @deftypefn {Function File} {@var{sys} =} frd (@var{sys}) +## @deftypefnx {Function File} {@var{sys} =} frd (@var{sys}, @var{w}) ## @deftypefnx {Function File} {@var{sys} =} frd (@var{H}, @var{w}) ## @deftypefnx {Function File} {@var{sys} =} frd (@var{H}, @var{w}, @var{tsam}) ## Create or convert to frequency response data. @@ -31,11 +32,22 @@ ## model precedence: frd > ss > zpk > tf > double superiorto ("ss", "zpk", "tf", "double"); + ## NOTE: * There's no such thing as a static gain + ## because FRD objects are measurements, + ## not models. + ## * If something like sys1 = frd (5) existed, + ## it would cause troubles in cases like + ## sys2 = ss (...), sys = sys1 * sys2 + ## because sys2 needs to be converted to FRD, + ## but sys1 contains no valid frequencies. + ## * Because of the reasons given above, + ## tsam = -1 and w = -1 don't make sense + argc = 0; switch (nargin) case 0 - tsam = -1; + tsam = 0; case 1 if (isa (H, "frd")) # already in frd form @@ -45,9 +57,6 @@ [sys, alti] = __sys2frd__ (H); sys.lti = alti; # preserve lti properties return; - elseif (is_real_matrix (H)) # static gain sys = frd (M) - w = -1; - tsam = -1; else print_usage (); endif Modified: trunk/octave-forge/main/control/devel/PROJECTS =================================================================== --- trunk/octave-forge/main/control/devel/PROJECTS 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/PROJECTS 2010-10-10 10:08:25 UTC (rev 7835) @@ -22,16 +22,26 @@ * Improve @lti/parallel.m * n-th order approximation of time delay exp (tau*s) - sys = pade (tau, n) + sys = pade (tau, n) - * Implement frd models (easy) and adapt __frequency_response__.m + * Add delays exp (-T*s) indelay, outdelay, stdelay, ... + -- Support time and frequency responses. + -- Support interconnections. - * Implement zpk models (harder) and @zpset similar to @tfpoly. + * Implement zpk models and @zpset similar to @tfpoly. * SLICOT model and controller reduction. Separate control-reduction package? * SLICOT system identification. Separate control-identification package? +----------------------- +Frequency Response Data: +----------------------- + + * Write a nice display routine (). + + * Tolerances for intersection of frequency vectors in @frd/__sys_group__.m + ------------------ State-Space Models: ------------------ Modified: trunk/octave-forge/main/control/devel/__adjust_frd_data__.m =================================================================== --- trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -26,26 +26,26 @@ function [H, w, tsam] = __adjust_frd_data__ (H, w, tsam); w = reshape (w, [], 1); + lw = length (w); if (ndims (H) != 3 && ! isempty (H)) - if (is_real_scalar (H)) # static gain (H is a real scalar) + if (isscalar (H)) H = reshape (H, 1, 1, []); - tsam = -1; - elseif (isvector (H)) # SISO system (H is a complex vector) + if (lw > 1) + H = repmat (H, [1, 1, lw]); # needed for "frd1 + scalar2" or "scalar1 * frd2) + endif + elseif (isvector (H)) # SISO system (H is a vector) H = reshape (H, 1, 1, []); - elseif (is_real_matrix (H)) # static gain (H is a real matrix) + elseif (ismatrix (H)) H = reshape (H, rows (H), []); - lw = length (w); if (lw > 1) - H = repmat (H, [1, 1, lw]); # needed for "frd1 + matrix2" or "matrix1 * frd2) + H = repmat (H, [1, 1, lw]); # needed for "frd1 + matrix2" or "matrix1 * frd2) endif - tsam = -1; else - error ("frd: static gain matrix must be real"); + error ("frd: first argument H invalid"); endif elseif (isempty (H)) H = zeros (0, 0, 0); - tsam = -1; endif endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/devel/__frd_dim__.m =================================================================== --- trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -25,17 +25,16 @@ function [p, m, l] = __frd_dim__ (H, w) - if (! isnumeric (H)) # TODO: watch out for __set__ vector case + if (! isnumeric (H)) error ("frd: H must be a 3-dimensional numeric array"); endif lw = length (w); - if (lw > 1 && (! is_real_vector (w) || any (w < 0) \ - || ! issorted (w) || w(1) >= w(end) || length (unique (w)) != lw)) + if (! isempty (w) && (! is_real_vector (w) || any (w < 0) \ + || ! issorted (w) || w(1) > w(end) \ + || length (unique (w)) != lw)) error ("frd: w must be a vector of positive real numbers"); - elseif (lw == 1 && (! issample (w, -1) || (iscomplex (H) && ! issample (w, 0)))) - error ("frd: scalar w must be a valid sampling time"); endif [p, m, l] = size (H); Modified: trunk/octave-forge/main/control/devel/test_frd.m =================================================================== --- trunk/octave-forge/main/control/devel/test_frd.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/devel/test_frd.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -8,7 +8,7 @@ sys5 = frd ([], []) -sys6 = frd ([1, 2; 3, 4]) +sys6 = frd ([1, 2; 3, 4], logspace (-1, 1, 10)) @@ -79,9 +79,9 @@ sigma (T_frd * P_frd) -k1 = frd (ss ([1, 2; 3, 4])) +k1 = frd (ss ([1, 2; 3, 4])); % k2 = frd (tf ([1, 2; 3, 4])) -k2 = frd (tf (5)) +k2 = frd (tf (5)); %{ Modified: trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -25,13 +25,8 @@ function [retsys, retlti] = __sys2frd__ (sys, w = []) if (isempty (w)) # case sys = frd (sys) - tsam = get (sys, "tsam"); - if (tsam == -1) # static gain - w = -1; # value is insignificant - else # dynamic system - [dec_min, dec_max] = __frequency_range__ (sys); - w = logspace (dec_min, dec_max, 500); - endif + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); endif H = __freqresp__ (sys, w); Modified: trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m 2010-10-10 08:20:19 UTC (rev 7834) +++ trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m 2010-10-10 10:08:25 UTC (rev 7835) @@ -25,13 +25,8 @@ function [retsys, retlti] = __sys2frd__ (sys, w = []) if (isempty (w)) # case sys = frd (sys) - tsam = get (sys, "tsam"); - if (tsam == -1) # static gain - w = -1; # value is insignificant - else # dynamic system - [dec_min, dec_max] = __frequency_range__ (sys); - w = logspace (dec_min, dec_max, 500); - endif + [dec_min, dec_max] = __frequency_range__ (sys); + w = logspace (dec_min, dec_max, 500); endif H = __freqresp__ (sys, w); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-14 18:30:18
|
Revision: 7844 http://octave.svn.sourceforge.net/octave/?rev=7844&view=rev Author: paramaniac Date: 2010-10-14 18:30:12 +0000 (Thu, 14 Oct 2010) Log Message: ----------- control: minor doc fixes Modified Paths: -------------- trunk/octave-forge/main/control/doc/octave_forge_specific_api.txt trunk/octave-forge/main/control/inst/dss.m Modified: trunk/octave-forge/main/control/doc/octave_forge_specific_api.txt =================================================================== --- trunk/octave-forge/main/control/doc/octave_forge_specific_api.txt 2010-10-13 19:42:09 UTC (rev 7843) +++ trunk/octave-forge/main/control/doc/octave_forge_specific_api.txt 2010-10-14 18:30:12 UTC (rev 7844) @@ -1,10 +1,16 @@ -lti/isstable (sys, tol) +isstable (sys, tol) # -feedback (sys) # equivalent to feedback (sys, eye (size (sys))) -feedback (sys, "+") # equivalent to feedback (sys, eye (size (sys)), +1) +feedback (sys) # equivalent to feedback (sys, eye (size (sys))) +feedback (sys, "+") # equivalent to feedback (sys, eye (size (sys)), +1) -H = sys(w) # equivalent to H = freqresp (sys, w) where w is a frequency vector +H = sys(w) # equivalent to H = freqresp (sys, w) where w is a frequency vector place (sys, p, alpha) # If parameter alpha is specified, poles with real parts place (a, b, p, alpha) # (continuous time) or moduli (discrete time) below alpha - # are left untouched. \ No newline at end of file + # are left untouched. + +sminreal (sys, tol) # Optional tolerance for controllability and observability. + # Entries of the state-space matrices whose moduli are less or + # equal to TOL are assumed to be zero. Default value is 0. + +frd (sys) # calculate interesting frequency range by the zeros and poles of SYS. \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/dss.m =================================================================== --- trunk/octave-forge/main/control/inst/dss.m 2010-10-13 19:42:09 UTC (rev 7843) +++ trunk/octave-forge/main/control/inst/dss.m 2010-10-14 18:30:12 UTC (rev 7844) @@ -48,6 +48,14 @@ ## Descriptor state-space model. ## @end table ## +## @example +## @group +## . +## E x = A x + B u +## y = C x + D u +## @end group +## @end example +## ## @seealso{ss, tf} ## @end deftypefn This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-14 19:46:20
|
Revision: 7845 http://octave.svn.sourceforge.net/octave/?rev=7845&view=rev Author: paramaniac Date: 2010-10-14 19:46:10 +0000 (Thu, 14 Oct 2010) Log Message: ----------- control: try sticking to GNU coding standards Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/__c2d__.m trunk/octave-forge/main/control/devel/@frd/__freqresp__.m trunk/octave-forge/main/control/devel/@frd/__get__.m trunk/octave-forge/main/control/devel/@frd/__minreal__.m trunk/octave-forge/main/control/devel/@frd/__pole__.m trunk/octave-forge/main/control/devel/@frd/__set__.m trunk/octave-forge/main/control/devel/@frd/__sys2ss__.m trunk/octave-forge/main/control/devel/@frd/__sys2tf__.m trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m trunk/octave-forge/main/control/devel/@frd/__sys_data__.m trunk/octave-forge/main/control/devel/@frd/__sys_group__.m trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m trunk/octave-forge/main/control/devel/@frd/__sys_prune__.m trunk/octave-forge/main/control/devel/@frd/__transpose__.m trunk/octave-forge/main/control/devel/@frd/__zero__.m trunk/octave-forge/main/control/devel/@frd/display.m trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/devel/__adjust_frd_data__.m trunk/octave-forge/main/control/devel/__frd_dim__.m trunk/octave-forge/main/control/devel/ss2tf/common.cc trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc trunk/octave-forge/main/control/inst/@lti/__lti_data__.m trunk/octave-forge/main/control/inst/@lti/__lti_group__.m trunk/octave-forge/main/control/inst/@lti/__lti_prune__.m trunk/octave-forge/main/control/inst/@lti/__property_names__.m trunk/octave-forge/main/control/inst/@lti/append.m trunk/octave-forge/main/control/inst/@lti/blkdiag.m trunk/octave-forge/main/control/inst/@lti/c2d.m trunk/octave-forge/main/control/inst/@lti/connect.m trunk/octave-forge/main/control/inst/@lti/dcgain.m trunk/octave-forge/main/control/inst/@lti/display.m trunk/octave-forge/main/control/inst/@lti/dss.m trunk/octave-forge/main/control/inst/@lti/dssdata.m trunk/octave-forge/main/control/inst/@lti/eig.m trunk/octave-forge/main/control/inst/@lti/feedback.m trunk/octave-forge/main/control/inst/@lti/frdata.m trunk/octave-forge/main/control/inst/@lti/freqresp.m trunk/octave-forge/main/control/inst/@lti/get.m trunk/octave-forge/main/control/inst/@lti/horzcat.m trunk/octave-forge/main/control/inst/@lti/inv.m trunk/octave-forge/main/control/inst/@lti/isct.m trunk/octave-forge/main/control/inst/@lti/isdt.m trunk/octave-forge/main/control/inst/@lti/issiso.m trunk/octave-forge/main/control/inst/@lti/isstable.m trunk/octave-forge/main/control/inst/@lti/lft.m trunk/octave-forge/main/control/inst/@lti/lti.m trunk/octave-forge/main/control/inst/@lti/mconnect.m trunk/octave-forge/main/control/inst/@lti/minreal.m trunk/octave-forge/main/control/inst/@lti/minus.m trunk/octave-forge/main/control/inst/@lti/mldivide.m trunk/octave-forge/main/control/inst/@lti/mpower.m trunk/octave-forge/main/control/inst/@lti/mrdivide.m trunk/octave-forge/main/control/inst/@lti/mtimes.m trunk/octave-forge/main/control/inst/@lti/norm.m trunk/octave-forge/main/control/inst/@lti/parallel.m trunk/octave-forge/main/control/inst/@lti/plus.m trunk/octave-forge/main/control/inst/@lti/pole.m trunk/octave-forge/main/control/inst/@lti/series.m trunk/octave-forge/main/control/inst/@lti/set.m trunk/octave-forge/main/control/inst/@lti/size.m trunk/octave-forge/main/control/inst/@lti/sminreal.m trunk/octave-forge/main/control/inst/@lti/ssdata.m trunk/octave-forge/main/control/inst/@lti/subsasgn.m trunk/octave-forge/main/control/inst/@lti/subsref.m trunk/octave-forge/main/control/inst/@lti/tfdata.m trunk/octave-forge/main/control/inst/@lti/transpose.m trunk/octave-forge/main/control/inst/@lti/uminus.m trunk/octave-forge/main/control/inst/@lti/vertcat.m trunk/octave-forge/main/control/inst/@lti/xperm.m trunk/octave-forge/main/control/inst/@lti/zero.m trunk/octave-forge/main/control/inst/@ss/__c2d__.m trunk/octave-forge/main/control/inst/@ss/__freqresp__.m trunk/octave-forge/main/control/inst/@ss/__get__.m trunk/octave-forge/main/control/inst/@ss/__minreal__.m trunk/octave-forge/main/control/inst/@ss/__pole__.m trunk/octave-forge/main/control/inst/@ss/__property_names__.m trunk/octave-forge/main/control/inst/@ss/__set__.m trunk/octave-forge/main/control/inst/@ss/__sys2frd__.m trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m trunk/octave-forge/main/control/inst/@ss/__sys_connect__.m trunk/octave-forge/main/control/inst/@ss/__sys_data__.m trunk/octave-forge/main/control/inst/@ss/__sys_group__.m trunk/octave-forge/main/control/inst/@ss/__sys_inverse__.m trunk/octave-forge/main/control/inst/@ss/__sys_prune__.m trunk/octave-forge/main/control/inst/@ss/__transpose__.m trunk/octave-forge/main/control/inst/@ss/__zero__.m trunk/octave-forge/main/control/inst/@ss/display.m trunk/octave-forge/main/control/inst/@ss/ss.m trunk/octave-forge/main/control/inst/@tf/__c2d__.m trunk/octave-forge/main/control/inst/@tf/__freqresp__.m trunk/octave-forge/main/control/inst/@tf/__get__.m trunk/octave-forge/main/control/inst/@tf/__minreal__.m trunk/octave-forge/main/control/inst/@tf/__pole__.m trunk/octave-forge/main/control/inst/@tf/__property_names__.m trunk/octave-forge/main/control/inst/@tf/__set__.m trunk/octave-forge/main/control/inst/@tf/__sys2frd__.m trunk/octave-forge/main/control/inst/@tf/__sys2ss__.m trunk/octave-forge/main/control/inst/@tf/__sys_connect__.m trunk/octave-forge/main/control/inst/@tf/__sys_data__.m trunk/octave-forge/main/control/inst/@tf/__sys_group__.m trunk/octave-forge/main/control/inst/@tf/__sys_inverse__.m trunk/octave-forge/main/control/inst/@tf/__sys_prune__.m trunk/octave-forge/main/control/inst/@tf/__transpose__.m trunk/octave-forge/main/control/inst/@tf/__zero__.m trunk/octave-forge/main/control/inst/@tf/display.m trunk/octave-forge/main/control/inst/@tf/tf.m trunk/octave-forge/main/control/inst/@tfpoly/__make_equally_long__.m trunk/octave-forge/main/control/inst/@tfpoly/__remove_leading_zeros__.m trunk/octave-forge/main/control/inst/@tfpoly/display.m trunk/octave-forge/main/control/inst/@tfpoly/eq.m trunk/octave-forge/main/control/inst/@tfpoly/get.m trunk/octave-forge/main/control/inst/@tfpoly/length.m trunk/octave-forge/main/control/inst/@tfpoly/minus.m trunk/octave-forge/main/control/inst/@tfpoly/mpower.m trunk/octave-forge/main/control/inst/@tfpoly/mtimes.m trunk/octave-forge/main/control/inst/@tfpoly/ne.m trunk/octave-forge/main/control/inst/@tfpoly/numel.m trunk/octave-forge/main/control/inst/@tfpoly/plus.m trunk/octave-forge/main/control/inst/@tfpoly/roots.m trunk/octave-forge/main/control/inst/@tfpoly/subsref.m trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m trunk/octave-forge/main/control/inst/@tfpoly/tfpoly2str.m trunk/octave-forge/main/control/inst/@tfpoly/uminus.m trunk/octave-forge/main/control/inst/@tfpoly/uplus.m trunk/octave-forge/main/control/inst/__check_name_numel__.m trunk/octave-forge/main/control/inst/__frequency_response__.m trunk/octave-forge/main/control/inst/__labels__.m trunk/octave-forge/main/control/inst/__ss_dim__.m trunk/octave-forge/main/control/inst/__tf_dim__.m trunk/octave-forge/main/control/inst/__time_response__.m trunk/octave-forge/main/control/inst/__vec2tfpoly__.m trunk/octave-forge/main/control/inst/augw.m trunk/octave-forge/main/control/inst/bode.m trunk/octave-forge/main/control/inst/bodemag.m trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/covar.m trunk/octave-forge/main/control/inst/ctrb.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/dlqr.m trunk/octave-forge/main/control/inst/dlyap.m trunk/octave-forge/main/control/inst/dlyapchol.m trunk/octave-forge/main/control/inst/dss.m trunk/octave-forge/main/control/inst/estim.m trunk/octave-forge/main/control/inst/gensig.m trunk/octave-forge/main/control/inst/h2syn.m trunk/octave-forge/main/control/inst/hinfsyn.m trunk/octave-forge/main/control/inst/hsvd.m trunk/octave-forge/main/control/inst/impulse.m trunk/octave-forge/main/control/inst/initial.m trunk/octave-forge/main/control/inst/isctrb.m trunk/octave-forge/main/control/inst/isdetectable.m trunk/octave-forge/main/control/inst/isobsv.m trunk/octave-forge/main/control/inst/isstabilizable.m trunk/octave-forge/main/control/inst/kalman.m trunk/octave-forge/main/control/inst/lqr.m trunk/octave-forge/main/control/inst/lsim.m trunk/octave-forge/main/control/inst/ltimodels.m trunk/octave-forge/main/control/inst/lyap.m trunk/octave-forge/main/control/inst/lyapchol.m trunk/octave-forge/main/control/inst/margin.m trunk/octave-forge/main/control/inst/mixsyn.m trunk/octave-forge/main/control/inst/nichols.m trunk/octave-forge/main/control/inst/nyquist.m trunk/octave-forge/main/control/inst/obsv.m trunk/octave-forge/main/control/inst/place.m trunk/octave-forge/main/control/inst/pzmap.m trunk/octave-forge/main/control/inst/sigma.m trunk/octave-forge/main/control/inst/step.m trunk/octave-forge/main/control/inst/strseq.m trunk/octave-forge/main/control/inst/test_control.m trunk/octave-forge/main/control/inst/tfpolyones.m trunk/octave-forge/main/control/inst/tfpolyzeros.m trunk/octave-forge/main/control/src/common.cc trunk/octave-forge/main/control/src/slab01od.cc trunk/octave-forge/main/control/src/slab08nd.cc trunk/octave-forge/main/control/src/slab13ad.cc trunk/octave-forge/main/control/src/slab13bd.cc trunk/octave-forge/main/control/src/slab13dd.cc trunk/octave-forge/main/control/src/slag08bd.cc trunk/octave-forge/main/control/src/slsb01bd.cc trunk/octave-forge/main/control/src/slsb02od.cc trunk/octave-forge/main/control/src/slsb03md.cc trunk/octave-forge/main/control/src/slsb03od.cc trunk/octave-forge/main/control/src/slsb04md.cc trunk/octave-forge/main/control/src/slsb04qd.cc trunk/octave-forge/main/control/src/slsb10dd.cc trunk/octave-forge/main/control/src/slsb10ed.cc trunk/octave-forge/main/control/src/slsb10fd.cc trunk/octave-forge/main/control/src/slsb10hd.cc trunk/octave-forge/main/control/src/slsg02ad.cc trunk/octave-forge/main/control/src/slsg03ad.cc trunk/octave-forge/main/control/src/slsg03bd.cc trunk/octave-forge/main/control/src/sltb01pd.cc trunk/octave-forge/main/control/src/sltg01hd.cc trunk/octave-forge/main/control/src/sltg01id.cc trunk/octave-forge/main/control/src/sltg01jd.cc Modified: trunk/octave-forge/main/control/devel/@frd/__c2d__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__c2d__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__c2d__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Convert the continuous FRD object into its discrete-time equivalent. Modified: trunk/octave-forge/main/control/devel/@frd/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__freqresp__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__freqresp__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Frequency response of FRD models :-) Modified: trunk/octave-forge/main/control/devel/@frd/__get__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__get__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__get__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Access property values of FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__minreal__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__minreal__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Minimal realization of FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__pole__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__pole__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__pole__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Poles of FRD object. Modified: trunk/octave-forge/main/control/devel/@frd/__set__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__set__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__set__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Set or modify properties of FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__sys2ss__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys2ss__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys2ss__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## FRD to SS conversion. Modified: trunk/octave-forge/main/control/devel/@frd/__sys2tf__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys2tf__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys2tf__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## FRD to TF conversion. Modified: trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{retsys} =} __sys_connect__ (@var{sys}, @var{M}) Modified: trunk/octave-forge/main/control/devel/@frd/__sys_data__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_data__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys_data__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Used by frdata instead of multiple get calls. Modified: trunk/octave-forge/main/control/devel/@frd/__sys_group__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_group__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys_group__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Block diagonal concatenation of two FRD models. Modified: trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys_inverse__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Inversion of FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__sys_prune__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_prune__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__sys_prune__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Submodel extraction and reordering for FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__transpose__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__transpose__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__transpose__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Transpose of FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/__zero__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__zero__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/__zero__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Transmission zeros of FRD object. Modified: trunk/octave-forge/main/control/devel/@frd/display.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Display routine for FRD objects. Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} frd (@var{sys}) Modified: trunk/octave-forge/main/control/devel/__adjust_frd_data__.m =================================================================== --- trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/__adjust_frd_data__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Common code for adjusting FRD model data. Modified: trunk/octave-forge/main/control/devel/__frd_dim__.m =================================================================== --- trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Number of outputs and inputs of transfer function numerator and Modified: trunk/octave-forge/main/control/devel/ss2tf/common.cc =================================================================== --- trunk/octave-forge/main/control/devel/ss2tf/common.cc 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/ss2tf/common.cc 2010-10-14 19:46:10 UTC (rev 7845) @@ -11,11 +11,11 @@ LTI Syncope is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License -along with this program. If not, see <http://www.gnu.org/licenses/>. +along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. Common code for oct-files. Modified: trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc =================================================================== --- trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc 2010-10-14 19:46:10 UTC (rev 7845) @@ -11,11 +11,11 @@ LTI Syncope is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License -along with this program. If not, see <http://www.gnu.org/licenses/>. +along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. Transfer matrix of a given state-space representation (A,B,C,D), using the pole-zeros method. Intended for @ss/__sys2tf__.m Modified: trunk/octave-forge/main/control/inst/@lti/__lti_data__.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/__lti_data__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/__lti_data__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Used by display routines instead of multiple get calls. Modified: trunk/octave-forge/main/control/inst/@lti/__lti_group__.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/__lti_group__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/__lti_group__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Block diagonal concatenation of two LTI models. Modified: trunk/octave-forge/main/control/inst/@lti/__lti_prune__.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/__lti_prune__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/__lti_prune__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Submodel extraction and reordering for LTI objects. Modified: trunk/octave-forge/main/control/inst/@lti/__property_names__.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/__property_names__.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/__property_names__.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -1,17 +1,19 @@ ## Copyright (C) 2009 Lukas F. Reichlin ## -## This program is free software: you can redistribute it and/or modify +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify ## it under the terms of the GNU General Public License as published by ## the Free Software Foundation, either version 3 of the License, or ## (at your option) any later version. ## -## This program is distributed in the hope that it will be useful, +## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{props}, @var{vals}] =} __property_names__ (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/append.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/append.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/append.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} append (@var{sys1}, @var{sys2}) Modified: trunk/octave-forge/main/control/inst/@lti/blkdiag.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/blkdiag.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/blkdiag.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} blkdiag (@var{sys1}, @var{sys2}) Modified: trunk/octave-forge/main/control/inst/@lti/c2d.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/c2d.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/c2d.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} c2d (@var{sys}, @var{tsam}) Modified: trunk/octave-forge/main/control/inst/@lti/connect.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/connect.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/connect.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} connect (@var{sys}, @var{cm}, @var{inputs}, @var{outputs}) Modified: trunk/octave-forge/main/control/inst/@lti/dcgain.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/dcgain.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/dcgain.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{k} =} dcgain (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Display routine for LTI objects. Called by its child classes. Modified: trunk/octave-forge/main/control/inst/@lti/dss.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/dss.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/dss.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Convert to descriptor state-space model. Modified: trunk/octave-forge/main/control/inst/@lti/dssdata.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/dssdata.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/dssdata.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{a}, @var{b}, @var{c}, @var{d}, @var{e}, @var{tsam}] =} dssdata (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/eig.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/eig.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/eig.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{p} =} eig (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/feedback.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/feedback.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/feedback.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} feedback (@var{sys1}) Modified: trunk/octave-forge/main/control/inst/@lti/frdata.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/frdata.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/frdata.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{H}, @var{w}, @var{tsam}] =} frdata (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/freqresp.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -1,4 +1,4 @@ -## Copyright (C) 2009 - 2010 Lukas F. Reichlin +## Copyright (C) 2009, 2010 Lukas F. Reichlin ## ## This file is part of LTI Syncope. ## @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn{Function File} {@var{H} =} freqresp (@var{sys}, @var{w}) Modified: trunk/octave-forge/main/control/inst/@lti/get.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/get.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/get.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} get (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/horzcat.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/horzcat.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/horzcat.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Horizontal concatenation of LTI objects. If necessary, object conversion Modified: trunk/octave-forge/main/control/inst/@lti/inv.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/inv.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/inv.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Inversion of LTI objects. Modified: trunk/octave-forge/main/control/inst/@lti/isct.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/isct.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/isct.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{bool} =} isct (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/isdt.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/isdt.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/isdt.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{bool} =} isdt (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/issiso.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/issiso.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/issiso.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{bool} =} issiso (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/isstable.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/isstable.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/isstable.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{bool} =} isstable (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/lft.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lft.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/lft.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} lft (@var{sys1}, @var{sys2}) Modified: trunk/octave-forge/main/control/inst/@lti/lti.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Constructor for LTI objects. For internal use only. Modified: trunk/octave-forge/main/control/inst/@lti/mconnect.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} mconnect (@var{sys}, @var{m}) Modified: trunk/octave-forge/main/control/inst/@lti/minreal.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/minreal.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/minreal.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -1,4 +1,4 @@ -## Copyright (C) 2009 - 2010 Lukas F. Reichlin +## Copyright (C) 2009, 2010 Lukas F. Reichlin ## ## This file is part of LTI Syncope. ## @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## @deftypefn {Function File} {@var{sys} =} minreal (@var{sys}) Modified: trunk/octave-forge/main/control/inst/@lti/minus.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/minus.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/minus.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Binary subtraction of LTI objects. If necessary, object conversion Modified: trunk/octave-forge/main/control/inst/@lti/mldivide.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mldivide.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/mldivide.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Matrix left division of LTI objects. If necessary, object conversion Modified: trunk/octave-forge/main/control/inst/@lti/mpower.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-14 18:30:12 UTC (rev 7844) +++ trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-14 19:46:10 UTC (rev 7845) @@ -9,11 +9,11 @@ ## ## LTI Syncope is distributed in the hope that it will be useful, ## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the ## GNU General Public License for more details. ## ## You should have received a copy of the GNU General Public License -## along with this program. If not, see <http://www.gnu.org/licenses/>. +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- ## Matrix power of LTI objects. The exponent must be an integer. Modified: trunk/octave-forge/main/control/inst/@lti/mrdivide.m ===================================================================... [truncated message content] |
From: <par...@us...> - 2010-10-17 01:17:28
|
Revision: 7855 http://octave.svn.sourceforge.net/octave/?rev=7855&view=rev Author: paramaniac Date: 2010-10-17 01:17:19 +0000 (Sun, 17 Oct 2010) Log Message: ----------- control: stick to GNU coding standards (double blanks after full stop) Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/devel/__frd_dim__.m trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc trunk/octave-forge/main/control/doc/slicot_readme.txt trunk/octave-forge/main/control/inst/@lti/dcgain.m trunk/octave-forge/main/control/inst/@lti/display.m trunk/octave-forge/main/control/inst/@lti/freqresp.m trunk/octave-forge/main/control/inst/@lti/horzcat.m trunk/octave-forge/main/control/inst/@lti/lti.m trunk/octave-forge/main/control/inst/@lti/mconnect.m trunk/octave-forge/main/control/inst/@lti/minus.m trunk/octave-forge/main/control/inst/@lti/mldivide.m trunk/octave-forge/main/control/inst/@lti/mpower.m trunk/octave-forge/main/control/inst/@lti/mrdivide.m trunk/octave-forge/main/control/inst/@lti/mtimes.m trunk/octave-forge/main/control/inst/@lti/plus.m trunk/octave-forge/main/control/inst/@lti/sminreal.m trunk/octave-forge/main/control/inst/@lti/transpose.m trunk/octave-forge/main/control/inst/@lti/uminus.m trunk/octave-forge/main/control/inst/@lti/vertcat.m trunk/octave-forge/main/control/inst/@ss/__minreal__.m trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m trunk/octave-forge/main/control/inst/@ss/__sys_connect__.m trunk/octave-forge/main/control/inst/@tf/__sys_connect__.m trunk/octave-forge/main/control/inst/@tf/tf.m trunk/octave-forge/main/control/inst/@tfpoly/__make_equally_long__.m trunk/octave-forge/main/control/inst/@tfpoly/__remove_leading_zeros__.m trunk/octave-forge/main/control/inst/@tfpoly/display.m trunk/octave-forge/main/control/inst/@tfpoly/eq.m trunk/octave-forge/main/control/inst/@tfpoly/get.m trunk/octave-forge/main/control/inst/@tfpoly/length.m trunk/octave-forge/main/control/inst/@tfpoly/minus.m trunk/octave-forge/main/control/inst/@tfpoly/mpower.m trunk/octave-forge/main/control/inst/@tfpoly/mtimes.m trunk/octave-forge/main/control/inst/@tfpoly/ne.m trunk/octave-forge/main/control/inst/@tfpoly/numel.m trunk/octave-forge/main/control/inst/@tfpoly/plus.m trunk/octave-forge/main/control/inst/@tfpoly/subsref.m trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m trunk/octave-forge/main/control/inst/@tfpoly/uminus.m trunk/octave-forge/main/control/inst/@tfpoly/uplus.m trunk/octave-forge/main/control/inst/__frequency_response__.m trunk/octave-forge/main/control/inst/__labels__.m trunk/octave-forge/main/control/inst/__tf_dim__.m trunk/octave-forge/main/control/inst/bode.m trunk/octave-forge/main/control/inst/bodemag.m trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/dlqr.m trunk/octave-forge/main/control/inst/dss.m trunk/octave-forge/main/control/inst/estim.m trunk/octave-forge/main/control/inst/gensig.m trunk/octave-forge/main/control/inst/hsvd.m trunk/octave-forge/main/control/inst/impulse.m trunk/octave-forge/main/control/inst/initial.m trunk/octave-forge/main/control/inst/isctrb.m trunk/octave-forge/main/control/inst/isdetectable.m trunk/octave-forge/main/control/inst/isobsv.m trunk/octave-forge/main/control/inst/issample.m trunk/octave-forge/main/control/inst/isstabilizable.m trunk/octave-forge/main/control/inst/kalman.m trunk/octave-forge/main/control/inst/lqr.m trunk/octave-forge/main/control/inst/lsim.m trunk/octave-forge/main/control/inst/margin.m trunk/octave-forge/main/control/inst/nichols.m trunk/octave-forge/main/control/inst/nyquist.m trunk/octave-forge/main/control/inst/place.m trunk/octave-forge/main/control/inst/rlocus.m trunk/octave-forge/main/control/inst/sigma.m trunk/octave-forge/main/control/inst/step.m trunk/octave-forge/main/control/inst/tfpolyones.m trunk/octave-forge/main/control/inst/tfpolyzeros.m trunk/octave-forge/main/control/src/is_real_matrix.cc trunk/octave-forge/main/control/src/is_real_scalar.cc trunk/octave-forge/main/control/src/is_real_square_matrix.cc trunk/octave-forge/main/control/src/is_real_vector.cc Modified: trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/devel/@frd/__sys_connect__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {@var{retsys} =} __sys_connect__ (@var{sys}, @var{M}) -## This function is part of the Model Abstraction Layer. No argument checking. +## This function is part of the Model Abstraction Layer. No argument checking. ## For internal use only. ## @example ## @group Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -25,15 +25,15 @@ ## @strong{Inputs} ## @table @var ## @item sys -## LTI model. If second argument @var{w} is omitted, the interesting +## LTI model. If second argument @var{w} is omitted, the interesting ## frequency range is calculated by the zeros and poles of @var{sys}. ## @item H -## Frequency response array (p-by-m-by-lw). In the SISO case, +## Frequency response array (p-by-m-by-lw). In the SISO case, ## a vector (lw-by-1) or (1-by-lw) is accepted as well. ## @item w ## Frequency vector (lw-by-1) in radian per second [rad/s]. ## @item tsam -## Sampling time. If @var{tsam} is not specified, a continuous-time +## Sampling time. If @var{tsam} is not specified, a continuous-time ## model is assumed. ## @item @dots{} ## Optional pairs of properties and values. Modified: trunk/octave-forge/main/control/devel/__frd_dim__.m =================================================================== --- trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/devel/__frd_dim__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## Number of outputs and inputs of transfer function numerator and -## denominator. For internal use only. +## denominator. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: February 2010 Modified: trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc =================================================================== --- trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/devel/ss2tf/sltb04bd.cc 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,7 +18,7 @@ along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. Transfer matrix of a given state-space representation (A,B,C,D), -using the pole-zeros method. Intended for @ss/__sys2tf__.m +using the pole-zeros method. Intended for @ss/__sys2tf__.m. Uses SLICOT TB04BD by courtesy of NICONET e.V. <http://www.slicot.org> Modified: trunk/octave-forge/main/control/doc/slicot_readme.txt =================================================================== --- trunk/octave-forge/main/control/doc/slicot_readme.txt 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/doc/slicot_readme.txt 2010-10-17 01:17:19 UTC (rev 7855) @@ -2,7 +2,7 @@ ********* If you encounter any bugs in the octave control package, please -DONT bother the great people behind SLICOT. Most likely it's a +DONT bother the great people behind SLICOT. Most likely it's a problem of the control package, not the proven SLICOT library. Therefore, please send any reports to the octave mailing list and the maintainer of the control package. Modified: trunk/octave-forge/main/control/inst/@lti/dcgain.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/dcgain.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/dcgain.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -28,7 +28,7 @@ ## @strong{Outputs} ## @table @var ## @item k -## DC gain matrice. For a system with m inputs and p outputs, the array @var{k} +## DC gain matrice. For a system with m inputs and p outputs, the array @var{k} ## has dimensions [p, m]. ## @end table ## Modified: trunk/octave-forge/main/control/inst/@lti/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Display routine for LTI objects. Called by its child classes. +## Display routine for LTI objects. Called by its child classes. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/freqresp.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/freqresp.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -30,7 +30,7 @@ ## @strong{Outputs} ## @table @var ## @item H -## Array of frequency response. For a system with m inputs and p outputs, the array @var{H} +## Array of frequency response. For a system with m inputs and p outputs, the array @var{H} ## has dimensions [p, m, length (w)]. ## The frequency response at the frequency w(k) is given by H(:,:,k). ## @end table Modified: trunk/octave-forge/main/control/inst/@lti/horzcat.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/horzcat.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/horzcat.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Horizontal concatenation of LTI objects. If necessary, object conversion -## is done by sys_group. Used by Octave for "[lti1, lti2]". +## Horizontal concatenation of LTI objects. If necessary, object conversion +## is done by sys_group. Used by Octave for "[lti1, lti2]". ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/lti.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Constructor for LTI objects. For internal use only. +## Constructor for LTI objects. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/mconnect.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/mconnect.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -25,11 +25,11 @@ ## @item sys ## LTI system. ## @item m -## Connection matrix. Each row belongs to an input and each column represents an output. +## Connection matrix. Each row belongs to an input and each column represents an output. ## @item inputs -## Vector of indices of those inputs which are retained. If not specified, all inputs are kept. +## Vector of indices of those inputs which are retained. If not specified, all inputs are kept. ## @item outputs -## Vector of indices of those outputs which are retained. If not specified, all outputs are kept. +## Vector of indices of those outputs which are retained. If not specified, all outputs are kept. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/@lti/minus.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/minus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/minus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Binary subtraction of LTI objects. If necessary, object conversion -## is done by sys_group. Used by Octave for "lti1 - lti2". +## Binary subtraction of LTI objects. If necessary, object conversion +## is done by sys_group. Used by Octave for "lti1 - lti2". ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/mldivide.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mldivide.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/mldivide.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Matrix left division of LTI objects. If necessary, object conversion -## is done by sys_group in mtimes. Used by Octave for "lti1 \ lti2". +## Matrix left division of LTI objects. If necessary, object conversion +## is done by sys_group in mtimes. Used by Octave for "lti1 \ lti2". ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 Modified: trunk/octave-forge/main/control/inst/@lti/mpower.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/mpower.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Matrix power of LTI objects. The exponent must be an integer. +## Matrix power of LTI objects. The exponent must be an integer. ## Used by Octave for "lti^int". ## Author: Lukas Reichlin <luk...@gm...> Modified: trunk/octave-forge/main/control/inst/@lti/mrdivide.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mrdivide.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/mrdivide.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Matrix right division of LTI objects. If necessary, object conversion -## is done by sys_group in mtimes. Used by Octave for "lti1 / lti2". +## Matrix right division of LTI objects. If necessary, object conversion +## is done by sys_group in mtimes. Used by Octave for "lti1 / lti2". ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 Modified: trunk/octave-forge/main/control/inst/@lti/mtimes.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/mtimes.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/mtimes.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Matrix multiplication of LTI objects. If necessary, object conversion -## is done by sys_group. Used by Octave for "lti1 * lti2". +## Matrix multiplication of LTI objects. If necessary, object conversion +## is done by sys_group. Used by Octave for "lti1 * lti2". ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/plus.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/plus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/plus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Binary addition of LTI objects. If necessary, object conversion -## is done by sys_group. Used by Octave for "lti1 + lti2". +## Binary addition of LTI objects. If necessary, object conversion +## is done by sys_group. Used by Octave for "lti1 + lti2". ## Operation is also known as "parallel connection". ## Author: Lukas Reichlin <luk...@gm...> Modified: trunk/octave-forge/main/control/inst/@lti/sminreal.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/sminreal.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/sminreal.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -29,7 +29,7 @@ ## @item tol ## Optional tolerance for controllability and observability. ## Entries of the state-space matrices whose moduli are less or equal to @var{tol} -## are assumed to be zero. Default value is 0. +## are assumed to be zero. Default value is 0. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/@lti/transpose.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/transpose.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/transpose.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Transpose of LTI objects. Used by Octave for "sys.'". +## Transpose of LTI objects. Used by Octave for "sys.'". ## Author: Lukas Reichlin <luk...@gm...> ## Created: February 2010 Modified: trunk/octave-forge/main/control/inst/@lti/uminus.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/uminus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/uminus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Unary minus of LTI object. Used by Octave for "-lti". +## Unary minus of LTI object. Used by Octave for "-lti". ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@lti/vertcat.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/vertcat.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@lti/vertcat.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,8 +16,8 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Vertical concatenation of LTI objects. If necessary, object conversion -## is done by sys_group. Used by Octave for "[lti1; lti2]". +## Vertical concatenation of LTI objects. If necessary, object conversion +## is done by sys_group. Used by Octave for "[lti1; lti2]". ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@ss/__minreal__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@ss/__minreal__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Minimal realization of SS models. The physical meaning of states is lost. +## Minimal realization of SS models. The physical meaning of states is lost. ## Uses SLICOT TB01PD and TG01JD by courtesy of NICONET e.V. ## <http://www.slicot.org> Modified: trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@ss/__sys2tf__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -40,5 +40,7 @@ retsys = tf (num, den, get (sys, "tsam")); # tsam needed to set appropriate tfvar retlti = sys.lti; # preserve lti properties + + ## FIXME: sys = tf (ss (5)) endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@ss/__sys_connect__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__sys_connect__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@ss/__sys_connect__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {@var{retsys} =} __sys_connect__ (@var{sys}, @var{M}) -## This function is part of the Model Abstraction Layer. No argument checking. +## This function is part of the Model Abstraction Layer. No argument checking. ## For internal use only. ## @example ## @group Modified: trunk/octave-forge/main/control/inst/@tf/__sys_connect__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__sys_connect__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tf/__sys_connect__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {@var{retsys} =} __sys_connect__ (@var{sys}, @var{M}) -## This function is part of the Model Abstraction Layer. No argument checking. +## This function is part of the Model Abstraction Layer. No argument checking. ## For internal use only. ## @example ## @group @@ -44,13 +44,13 @@ num = sys.num; den = sys.den; - ## TODO: Implementation for MIMO models. There are three possibilities: + ## TODO: Implementation for MIMO models. There are three possibilities: ## 1. An _algebraic_ solution of the inversion problem in order - ## to not introduce unwanted zero/pole pairs. Difficult. - ## 2. A numeric solution of the inversion problem. Afterwards, - ## elimination of _all_ zero/pole pairs by minreal. Bad. + ## to not introduce unwanted zero/pole pairs. Difficult. + ## 2. A numeric solution of the inversion problem. Afterwards, + ## elimination of _all_ zero/pole pairs by minreal. Bad. ## 3. Conversion to state-space, solving the problem there and - ## converting back to transfer function. Easier, but obviously, + ## converting back to transfer function. Easier, but obviously, ## this way needs MIMO __sys2ss__ and __sys2tf__ implementations ## as described in Thomas Kailath's classic "Linear Systems". ## Possibly this is the way to go, but it works for proper systems Modified: trunk/octave-forge/main/control/inst/@tf/tf.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -26,13 +26,13 @@ ## @strong{Inputs} ## @table @var ## @item num -## Numerator or cell of numerators. Row vector containing the exponents +## Numerator or cell of numerators. Row vector containing the exponents ## of the polynomial in descending order. ## @item den -## Denominator or cell of denominators. Row vector containing the exponents +## Denominator or cell of denominators. Row vector containing the exponents ## of the polynomial in descending order. ## @item tsam -## Sampling time. If @var{tsam} is not specified, a continuous-time +## Sampling time. If @var{tsam} is not specified, a continuous-time ## model is assumed. ## @item @dots{} ## Optional pairs of properties and values. Modified: trunk/octave-forge/main/control/inst/@tfpoly/__make_equally_long__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/__make_equally_long__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/__make_equally_long__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## Make two polynomials equally long by adding leading zeros -## to the shorter one. For internal use only. +## to the shorter one. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/__remove_leading_zeros__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/__remove_leading_zeros__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/__remove_leading_zeros__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## Remove leading zeros from a polynomial, except for polynomials -## which are of length 1. For internal use only. +## which are of length 1. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/display.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/display.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Display routine. For internal use only. +## Display routine. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/eq.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/eq.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/eq.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Test for equal coefficients. For internal use only. +## Test for equal coefficients. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/get.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/get.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/get.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Return coefficients as a row vector. For internal use only. +## Return coefficients as a row vector. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/length.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/length.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/length.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Number of coefficients. For internal use only. +## Number of coefficients. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/minus.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/minus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/minus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Subtraction of two polynomials. For internal use only. +## Subtraction of two polynomials. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/mpower.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/mpower.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/mpower.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Power of a polynomial. For internal use only. +## Power of a polynomial. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/mtimes.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/mtimes.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/mtimes.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Multiplication of two polynomials. For internal use only. +## Multiplication of two polynomials. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/ne.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/ne.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/ne.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Return true if polynomials are not equal. For internal use only. +## Return true if polynomials are not equal. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/numel.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/numel.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/numel.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Number of coefficients. For internal use only. +## Number of coefficients. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/plus.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/plus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/plus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Addition of two polynomials. For internal use only. +## Addition of two polynomials. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/subsref.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/subsref.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/subsref.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Evaluate polynomial. For internal use only. +## Evaluate polynomial. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/tfpoly.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Class constructor. For internal use only. +## Class constructor. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/uminus.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/uminus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/uminus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Unitary minus operator. For internal use only. +## Unitary minus operator. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/@tfpoly/uplus.m =================================================================== --- trunk/octave-forge/main/control/inst/@tfpoly/uplus.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/@tfpoly/uplus.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -16,7 +16,7 @@ ## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. ## -*- texinfo -*- -## Unitary plus operator. For internal use only. +## Unitary plus operator. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: September 2009 Modified: trunk/octave-forge/main/control/inst/__frequency_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/__frequency_response__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## Return frequency response H and frequency vector w. -## If w is empty, it will be calculated by __frequency_range__ +## If w is empty, it will be calculated by __frequency_range__. ## Author: Lukas Reichlin <luk...@gm...> ## Created: November 2009 Modified: trunk/octave-forge/main/control/inst/__labels__.m =================================================================== --- trunk/octave-forge/main/control/inst/__labels__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/__labels__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,7 +18,7 @@ ## -*- texinfo -*- ## Return default labels if cell "name" contains only empty strings. ## If not, check whether individual strings of the cell "name" are -## empty and mark them with "?". Used by display routines. +## empty and mark them with "?". Used by display routines. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 Modified: trunk/octave-forge/main/control/inst/__tf_dim__.m =================================================================== --- trunk/octave-forge/main/control/inst/__tf_dim__.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/__tf_dim__.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -17,7 +17,7 @@ ## -*- texinfo -*- ## Number of outputs and inputs of transfer function numerator and -## denominator. For internal use only. +## denominator. For internal use only. ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 Modified: trunk/octave-forge/main/control/inst/bode.m =================================================================== --- trunk/octave-forge/main/control/inst/bode.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/bode.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,24 +18,24 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{mag}, @var{pha}, @var{w}] =} bode (@var{sys}) ## @deftypefnx {Function File} {[@var{mag}, @var{pha}, @var{w}] =} bode (@var{sys}, @var{w}) -## Bode diagram of frequency response. If no output arguments are given, +## Bode diagram of frequency response. If no output arguments are given, ## the response is printed on the screen. ## ## @strong{Inputs} ## @table @var ## @item sys -## LTI system. Must be a single-input and single-output (SISO) system. +## LTI system. Must be a single-input and single-output (SISO) system. ## @item w -## Optional vector of frequency values. If @var{w} is not specified, it -## is calculated by the zeros and poles of the system. +## Optional vector of frequency values. If @var{w} is not specified, +## it is calculated by the zeros and poles of the system. ## @end table ## ## @strong{Outputs} ## @table @var ## @item mag -## Vector of magnitude. Has length of frequency vector @var{w}. +## Vector of magnitude. Has length of frequency vector @var{w}. ## @item pha -## Vector of phase. Has length of frequency vector @var{w}. +## Vector of phase. Has length of frequency vector @var{w}. ## @item w ## Vector of frequency values used. ## @end table Modified: trunk/octave-forge/main/control/inst/bodemag.m =================================================================== --- trunk/octave-forge/main/control/inst/bodemag.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/bodemag.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,22 +18,22 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{mag}, @var{w}] =} bodemag (@var{sys}) ## @deftypefnx {Function File} {[@var{mag}, @var{w}] =} bodemag (@var{sys}, @var{w}) -## Bode magnitude diagram of frequency response. If no output arguments are given, +## Bode magnitude diagram of frequency response. If no output arguments are given, ## the response is printed on the screen. ## ## @strong{Inputs} ## @table @var ## @item sys -## LTI system. Must be a single-input and single-output (SISO) system. +## LTI system. Must be a single-input and single-output (SISO) system. ## @item w -## Optional vector of frequency values. If @var{w} is not specified, it -## is calculated by the zeros and poles of the system. +## Optional vector of frequency values. If @var{w} is not specified, +## it is calculated by the zeros and poles of the system. ## @end table ## ## @strong{Outputs} ## @table @var ## @item mag -## Vector of magnitude. Has length of frequency vector @var{w}. +## Vector of magnitude. Has length of frequency vector @var{w}. ## @item w ## Vector of frequency values used. ## @end table Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/care.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -35,9 +35,9 @@ ## @item r ## Real matrix (m-by-m). ## @item s -## Optional real matrix (n-by-m). If @var{s} is not specified, a zero matrix is assumed. +## Optional real matrix (n-by-m). If @var{s} is not specified, a zero matrix is assumed. ## @item e -## Optional descriptor matrix (n-by-n). If @var{e} is not specified, an identity matrix is assumed. +## Optional descriptor matrix (n-by-n). If @var{e} is not specified, an identity matrix is assumed. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/dare.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -35,9 +35,9 @@ ## @item r ## Real matrix (m-by-m). ## @item s -## Optional real matrix (n-by-m). If @var{s} is not specified, a zero matrix is assumed. +## Optional real matrix (n-by-m). If @var{s} is not specified, a zero matrix is assumed. ## @item e -## Optional descriptor matrix (n-by-n). If @var{e} is not specified, an identity matrix is assumed. +## Optional descriptor matrix (n-by-n). If @var{e} is not specified, an identity matrix is assumed. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/dlqr.m =================================================================== --- trunk/octave-forge/main/control/inst/dlqr.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/dlqr.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -37,9 +37,9 @@ ## @item r ## Input weighting matrix. ## @item s -## Optional cross term matrix. If @var{s} is not specified, a zero matrix is assumed. +## Optional cross term matrix. If @var{s} is not specified, a zero matrix is assumed. ## @item e -## Optional descriptor matrix. If @var{e} is not specified, an identity matrix is assumed. +## Optional descriptor matrix. If @var{e} is not specified, an identity matrix is assumed. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/dss.m =================================================================== --- trunk/octave-forge/main/control/inst/dss.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/dss.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -35,7 +35,7 @@ ## @item e ## Descriptor matrix (n-by-n). ## @item tsam -## Sampling time. If @var{tsam} is not specified, a continuous-time +## Sampling time. If @var{tsam} is not specified, a continuous-time ## model is assumed. ## @item @dots{} ## Optional pairs of properties and values. Modified: trunk/octave-forge/main/control/inst/estim.m =================================================================== --- trunk/octave-forge/main/control/inst/estim.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/estim.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,7 +18,7 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {@var{est} =} estim (@var{sys}, @var{l}) ## @deftypefnx {Function File} {@var{est} =} estim (@var{sys}, @var{l}, @var{sensors}, @var{known}) -## Return state estimator for a given estimator gain +## Return state estimator for a given estimator gain. ## ## @strong{Inputs} ## @table @var @@ -27,10 +27,10 @@ ## @item l ## State feedback matrix. ## @item sensors -## Indices of measured output signals y from @var{sys}. If omitted, all outputs are measured. +## Indices of measured output signals y from @var{sys}. If omitted, all outputs are measured. ## @item known -## Indices of known input signals u (deterministic) to @var{sys}. All other inputs to @var{sys} -## are assumed stochastic. If argument @var{known} is omitted, no inputs u are known. +## Indices of known input signals u (deterministic) to @var{sys}. All other inputs to @var{sys} +## are assumed stochastic. If argument @var{known} is omitted, no inputs u are known. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/gensig.m =================================================================== --- trunk/octave-forge/main/control/inst/gensig.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/gensig.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -19,7 +19,7 @@ ## @deftypefn{Function File} {[@var{u}, @var{t}] =} gensig (@var{sigtype}, @var{tau}) ## @deftypefnx{Function File} {[@var{u}, @var{t}] =} gensig (@var{sigtype}, @var{tau}, @var{tfinal}) ## @deftypefnx{Function File} {[@var{u}, @var{t}] =} gensig (@var{sigtype}, @var{tau}, @var{tfinal}, @var{tsam}) -## Generate periodic signal. Useful in combination with lsim. +## Generate periodic signal. Useful in combination with lsim. ## ## @strong{Inputs} ## @table @var @@ -34,9 +34,9 @@ ## @item tau ## Duration of one period in seconds. ## @item tfinal -## Optional duration of the signal in seconds. Default duration is 5 periods. +## Optional duration of the signal in seconds. Default duration is 5 periods. ## @item tsam -## Optional sampling time in seconds. Default spacing is tau/64. +## Optional sampling time in seconds. Default spacing is tau/64. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/hsvd.m =================================================================== --- trunk/octave-forge/main/control/inst/hsvd.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/hsvd.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,7 +18,7 @@ ## -*- texinfo -*- ## @deftypefn{Function File} {@var{hsv} =} hsvd (@var{sys}) ## @deftypefnx{Function File} {@var{hsv} =} hsvd (@var{sys}, @var{"offset"}, @var{alpha}) -## Hankel singular values of the stable part of an LTI model. If no output arguments are +## Hankel singular values of the stable part of an LTI model. If no output arguments are ## given, the Hankel singular values are displayed in a plot. ## Uses SLICOT AB13AD by courtesy of NICONET e.V. ## <http://www.slicot.org> Modified: trunk/octave-forge/main/control/inst/impulse.m =================================================================== --- trunk/octave-forge/main/control/inst/impulse.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/impulse.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -28,25 +28,25 @@ ## @item sys ## LTI model. ## @item t -## Time vector. Should be evenly spaced. If not specified, it is calculated by +## Time vector. Should be evenly spaced. If not specified, it is calculated by ## the poles of the system to reflect adequately the response transients. ## @item tfinal -## Optional simulation horizon. If not specified, it is calculated by +## Optional simulation horizon. If not specified, it is calculated by ## the poles of the system to reflect adequately the response transients. ## @item dt -## Optional sampling time. Be sure to choose it small enough to capture transient -## phenomena. If not specified, it is calculated by the poles of the system. +## Optional sampling time. Be sure to choose it small enough to capture transient +## phenomena. If not specified, it is calculated by the poles of the system. ## @end table ## ## @strong{Outputs} ## @table @var ## @item y -## Output response array. Has as many rows as time samples (length of t) +## Output response array. Has as many rows as time samples (length of t) ## and as many columns as outputs. ## @item t ## Time row vector. ## @item x -## State trajectories array. Has length(t) rows and as many columns as states. +## State trajectories array. Has @code{length (t)} rows and as many columns as states. ## @end table ## ## @seealso{initial, lsim, step} Modified: trunk/octave-forge/main/control/inst/initial.m =================================================================== --- trunk/octave-forge/main/control/inst/initial.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/initial.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -30,25 +30,25 @@ ## @item x0 ## Vector of initial conditions for each state. ## @item t -## Optional time vector. Should be evenly spaced. If not specified, it is calculated +## Optional time vector. Should be evenly spaced. If not specified, it is calculated ## by the poles of the system to reflect adequately the response transients. ## @item tfinal -## Optional simulation horizon. If not specified, it is calculated by +## Optional simulation horizon. If not specified, it is calculated by ## the poles of the system to reflect adequately the response transients. ## @item dt -## Optional sampling time. Be sure to choose it small enough to capture transient -## phenomena. If not specified, it is calculated by the poles of the system. +## Optional sampling time. Be sure to choose it small enough to capture transient +## phenomena. If not specified, it is calculated by the poles of the system. ## @end table ## ## @strong{Outputs} ## @table @var ## @item y -## Output response array. Has as many rows as time samples (length of t) +## Output response array. Has as many rows as time samples (length of t) ## and as many columns as outputs. ## @item t ## Time row vector. ## @item x -## State trajectories array. Has length(t) rows and as many columns as states. +## State trajectories array. Has @code{length (t)} rows and as many columns as states. ## @end table ## ## @strong{Example} Modified: trunk/octave-forge/main/control/inst/isctrb.m =================================================================== --- trunk/octave-forge/main/control/inst/isctrb.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/isctrb.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -37,7 +37,7 @@ ## @item e ## Descriptor matrix. ## @item tol -## Optional roundoff parameter. Default value is 0. +## Optional roundoff parameter. Default value is 0. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/isdetectable.m =================================================================== --- trunk/octave-forge/main/control/inst/isdetectable.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/isdetectable.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -26,8 +26,9 @@ ## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}, @var{[]}, @var{dflg}) ## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{[]}, @var{tol}, @var{dflg}) ## @deftypefnx {Function File} {@var{bool} =} isdetectable (@var{a}, @var{c}, @var{e}, @var{tol}, @var{dflg}) -## Logical test for system detectability. All unstable modes must be observable or -## all unobservable states must be stable. Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. +## Logical test for system detectability. +## All unstable modes must be observable or all unobservable states must be stable. +## Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. ## <http://www.slicot.org> ## ## @strong{Inputs} @@ -41,9 +42,9 @@ ## @item e ## Descriptor matrix. ## @item tol -## Optional tolerance for stability. Default value is 0. +## Optional tolerance for stability. Default value is 0. ## @item dflg = 0 -## Matrices (@var{a}, @var{c}) are part of a continuous-time system. Default Value. +## Matrices (@var{a}, @var{c}) are part of a continuous-time system. Default Value. ## @item dflg = 1 ## Matrices (@var{a}, @var{c}) are part of a discrete-time system. ## @end table Modified: trunk/octave-forge/main/control/inst/isobsv.m =================================================================== --- trunk/octave-forge/main/control/inst/isobsv.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/isobsv.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -37,7 +37,7 @@ ## @item e ## Descriptor matrix. ## @item tol -## Optional roundoff parameter. Default value is 0. +## Optional roundoff parameter. Default value is 0. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/issample.m =================================================================== --- trunk/octave-forge/main/control/inst/issample.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/issample.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -24,7 +24,7 @@ ## @item ts ## Alleged sampling time to be tested. ## @item flg = 1 -## Accept real scalars @var{ts} > 0. Default Value. +## Accept real scalars @var{ts} > 0. Default Value. ## @item flg = 0 ## Accept real scalars @var{ts} >= 0. ## @item flg = -1 Modified: trunk/octave-forge/main/control/inst/isstabilizable.m =================================================================== --- trunk/octave-forge/main/control/inst/isstabilizable.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/isstabilizable.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -26,8 +26,9 @@ ## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}, @var{[]}, @var{dflg}) ## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{[]}, @var{tol}, @var{dflg}) ## @deftypefnx {Function File} {@var{bool} =} isstabilizable (@var{a}, @var{b}, @var{e}, @var{tol}, @var{dflg}) -## Logical check for system stabilizability. All unstable modes must be controllable or -## all uncontrollable states must be stable. Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. +## Logical check for system stabilizability. +## All unstable modes must be controllable or all uncontrollable states must be stable. +## Uses SLICOT AB01OD and TG01HD by courtesy of NICONET e.V. ## <http://www.slicot.org> ## ## @strong{Inputs} @@ -41,9 +42,9 @@ ## @item e ## Descriptor matrix. ## @item tol -## Optional tolerance for stability. Default value is 0. +## Optional tolerance for stability. Default value is 0. ## @item dflg = 0 -## Matrices (@var{a}, @var{b}) are part of a continuous-time system. Default Value. +## Matrices (@var{a}, @var{b}) are part of a continuous-time system. Default Value. ## @item dflg = 1 ## Matrices (@var{a}, @var{b}) are part of a discrete-time system. ## @end table Modified: trunk/octave-forge/main/control/inst/kalman.m =================================================================== --- trunk/octave-forge/main/control/inst/kalman.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/kalman.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -31,12 +31,12 @@ ## @item r ## Covariance of white measurement noise. ## @item s -## Optional cross term covariance. Default value is 0. +## Optional cross term covariance. Default value is 0. ## @item sensors -## Indices of measured output signals y from @var{sys}. If omitted, all outputs are measured. +## Indices of measured output signals y from @var{sys}. If omitted, all outputs are measured. ## @item known -## Indices of known input signals u (deterministic) to @var{sys}. All other inputs to @var{sys} -## are assumed stochastic. If argument @var{known} is omitted, no inputs u are known. +## Indices of known input signals u (deterministic) to @var{sys}. All other inputs to @var{sys} +## are assumed stochastic. If argument @var{known} is omitted, no inputs u are known. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/lqr.m =================================================================== --- trunk/octave-forge/main/control/inst/lqr.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/lqr.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -37,9 +37,9 @@ ## @item r ## Input weighting matrix. ## @item s -## Optional cross term matrix. If @var{s} is not specified, a zero matrix is assumed. +## Optional cross term matrix. If @var{s} is not specified, a zero matrix is assumed. ## @item e -## Optional descriptor matrix. If @var{e} is not specified, an identity matrix is assumed. +## Optional descriptor matrix. If @var{e} is not specified, an identity matrix is assumed. ## @end table ## ## @strong{Outputs} Modified: trunk/octave-forge/main/control/inst/lsim.m =================================================================== --- trunk/octave-forge/main/control/inst/lsim.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/lsim.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -19,7 +19,7 @@ ## @deftypefn{Function File} {[@var{y}, @var{t}, @var{x}] =} lsim (@var{sys}, @var{u}, @var{t}) ## @deftypefnx{Function File} {[@var{y}, @var{t}, @var{x}] =} lsim (@var{sys}, @var{u}, @var{t}, @var{x0}) ## @deftypefnx{Function File} {[@var{y}, @var{t}, @var{x}] =} lsim (@var{sys}, @var{u}, @var{t}, @var{x0}, @var{method}) -## Simulate LTI model response to arbitrary inputs. If no output arguments are given, +## Simulate LTI model response to arbitrary inputs. If no output arguments are given, ## the system response is plotted on the screen. ## ## @strong{Inputs} @@ -27,23 +27,23 @@ ## @item sys ## LTI model. ## @item t -## Time vector. Should be evenly spaced. +## Time vector. Should be evenly spaced. ## @item x0 ## Vector of initial conditions for each state. ## @item method -## Discretization method for continuous-time models. Default value is zoh -## (zero-order hold). All methods from c2d are supported. +## Discretization method for continuous-time models. Default value is zoh +## (zero-order hold). All methods from c2d are supported. ## @end table ## ## @strong{Outputs} ## @table @var ## @item y -## Output response array. Has as many rows as time samples (length of t) +## Output response array. Has as many rows as time samples (length of t) ## and as many columns as outputs. ## @item t ## Time row vector. ## @item x -## State trajectories array. Has length(t) rows and as many columns as states. +## State trajectories array. Has @code{length (t)} rows and as many columns as states. ## @end table ## ## @seealso{impulse, initial, step} Modified: trunk/octave-forge/main/control/inst/margin.m =================================================================== --- trunk/octave-forge/main/control/inst/margin.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/margin.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,14 +18,14 @@ ## -*- texinfo -*- ## @deftypefn{Function File} {[@var{gamma}, @var{phi}, @var{w_gamma}, @var{w_phi}] =} margin (@var{sys}) ## @deftypefnx{Function File} {[@var{gamma}, @var{phi}, @var{w_gamma}, @var{w_phi}] =} margin (@var{sys}, @var{tol}) -## Gain and phase margin of a system. If no output arguments are given, both gain and phase margin -## are plotted on a bode diagram. Otherwise, the margins and their corresponding frequencies are +## Gain and phase margin of a system. If no output arguments are given, both gain and phase margin +## are plotted on a bode diagram. Otherwise, the margins and their corresponding frequencies are ## computed and returned. ## ## @strong{Inputs} ## @table @var ## @item sys -## LTI model. Must be a single-input and single-output (SISO) system. +## LTI model. Must be a single-input and single-output (SISO) system. ## @item tol ## Imaginary parts below @var{tol} are assumed to be zero. ## If not specified, default value @code{sqrt (eps)} is taken. Modified: trunk/octave-forge/main/control/inst/nichols.m =================================================================== --- trunk/octave-forge/main/control/inst/nichols.m 2010-10-16 23:54:18 UTC (rev 7854) +++ trunk/octave-forge/main/control/inst/nichols.m 2010-10-17 01:17:19 UTC (rev 7855) @@ -18,24 +18,24 @@ ## -*- texinfo -*- ## @deftypefn {Function File} {[@var{mag}, @var{pha}, @var{w}] =} nichols (@var{sys}) ## @deftypefnx {Function File} {[@var{mag}, @var{pha}, @var{w}] =} nichols (@var{sys}, @var{w}) -## Nichols chart of frequency response. If no output arguments are given, +## Nichols chart of frequency response. If no output arguments are given, ## the response is printed on the screen. ## ## @strong{Inputs} ## @table @var ## @item sys -## LTI system. Must be a single-input and single-output (SISO) system. +## LTI system. Must be a single-input and single-output (SISO) system. ## @item w -## Optional vector of frequency values. If @var{w} is not specified, it -## is calculated by the zeros and poles of the system. +## Optional vector of frequency values. If @var{w} is not specified, +## it is calculated by the zeros and poles of the system. ## @end table ## ## @strong{Outputs} ## @table @var ## @item mag -## Vector of magnitude. Has length of frequency vector @var{w}. +## Vector of magnitude. Has length of frequency vector @var{w}. ## @item pha -## Vector of phase. Has length of frequency vector @var{w}. +## Vector of phase. Has length of frequency vector @var{w}. ## @... [truncated message content] |
From: <par...@us...> - 2010-10-17 02:40:57
|
Revision: 7859 http://octave.svn.sourceforge.net/octave/?rev=7859&view=rev Author: paramaniac Date: 2010-10-17 02:40:51 +0000 (Sun, 17 Oct 2010) Log Message: ----------- control: texinfo fixes Modified Paths: -------------- trunk/octave-forge/main/control/devel/RELEASE_PACKAGE trunk/octave-forge/main/control/inst/place.m Modified: trunk/octave-forge/main/control/devel/RELEASE_PACKAGE =================================================================== --- trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2010-10-17 02:10:00 UTC (rev 7858) +++ trunk/octave-forge/main/control/devel/RELEASE_PACKAGE 2010-10-17 02:40:51 UTC (rev 7859) @@ -28,6 +28,7 @@ md5 control-html.tar.gz md5 control-html.tar.gz > md5_control_html.txt uuencode control-html.tar.gz < control-html.tar.gz > control-html.tar.gz.uue +cd ===================================================================================== Modified: trunk/octave-forge/main/control/inst/place.m =================================================================== --- trunk/octave-forge/main/control/inst/place.m 2010-10-17 02:10:00 UTC (rev 7858) +++ trunk/octave-forge/main/control/inst/place.m 2010-10-17 02:40:51 UTC (rev 7859) @@ -20,9 +20,9 @@ ## @deftypefnx {Function File} {@var{f} =} place (@var{a}, @var{b}, @var{p}) ## @deftypefnx {Function File} {[@var{f}, @var{nfp}, @var{nap}, @var{nup}] =} place (@var{sys}, @var{p}, @var{alpha}) ## @deftypefnx {Function File} {[@var{f}, @var{nfp}, @var{nap}, @var{nup}] =} place (@var{a}, @var{b}, @var{p}, @var{alpha}) -## Pole assignment for a given matrix pair (@var{a},@var{B}) such that @code{p = eig (A-B*F)}. -## If parameter alpha is specified, poles with real parts (continuous time) -## or moduli (discrete time) below alpha are left untouched. +## Pole assignment for a given matrix pair (@var{A},@var{B}) such that @code{p = eig (A-B*F)}. +## If parameter @var{alpha} is specified, poles with real parts (continuous-time) +## or moduli (discrete-time) below @var{alpha} are left untouched. ## Uses SLICOT SB01BD by courtesy of NICONET e.V. ## <http://www.slicot.org> ## @@ -33,13 +33,13 @@ ## @item a ## State transition matrix (n-by-n) of a continuous-time system. ## @item b -## Input matrix (n-by-m) of a continuous time system. +## Input matrix (n-by-m) of a continuous-time system. ## @item p ## Desired eigenvalues of the closed-loop system state-matrix @var{A-B*F}. -## @code{length (p) <= rows (A)} +## @code{length (p) <= rows (A)}. ## @item alpha ## Specifies the maximum admissible value, either for real -## parts or for moduli, of the eigenvalues of A which will +## parts or for moduli, of the eigenvalues of @var{A} which will ## not be modified by the eigenvalue assignment algorithm. ## @code{alpha >= 0} for discrete-time systems. ## @end table @@ -61,8 +61,8 @@ ## ## @strong{Note} ## @example +## Place is also suitable to design estimator gains: ## @group -## Place is also suitable to design estimator gains: ## L = place (A.', C.', p).' ## L = place (sys.', p).' % useful for discrete-time systems ## @end group This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-10-30 23:38:41
|
Revision: 7896 http://octave.svn.sourceforge.net/octave/?rev=7896&view=rev Author: paramaniac Date: 2010-10-30 23:38:32 +0000 (Sat, 30 Oct 2010) Log Message: ----------- control: support discrete-time models whose sampling times are unspecified Modified Paths: -------------- trunk/octave-forge/main/control/DESCRIPTION trunk/octave-forge/main/control/devel/@frd/display.m trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/inst/@lti/__lti_group__.m trunk/octave-forge/main/control/inst/@lti/display.m trunk/octave-forge/main/control/inst/@lti/isct.m trunk/octave-forge/main/control/inst/@lti/lti.m trunk/octave-forge/main/control/inst/@lti/norm.m trunk/octave-forge/main/control/inst/@lti/set.m trunk/octave-forge/main/control/inst/@ss/__freqresp__.m trunk/octave-forge/main/control/inst/@ss/display.m trunk/octave-forge/main/control/inst/@ss/ss.m trunk/octave-forge/main/control/inst/@tf/__freqresp__.m trunk/octave-forge/main/control/inst/@tf/tf.m trunk/octave-forge/main/control/inst/__adjust_ss_data__.m trunk/octave-forge/main/control/inst/__frequency_vector__.m trunk/octave-forge/main/control/inst/__time_response__.m trunk/octave-forge/main/control/inst/dlqr.m trunk/octave-forge/main/control/inst/issample.m trunk/octave-forge/main/control/inst/lqr.m trunk/octave-forge/main/control/inst/lsim.m trunk/octave-forge/main/control/inst/ltimodels.m trunk/octave-forge/main/control/inst/margin.m trunk/octave-forge/main/control/inst/place.m Modified: trunk/octave-forge/main/control/DESCRIPTION =================================================================== --- trunk/octave-forge/main/control/DESCRIPTION 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/DESCRIPTION 2010-10-30 23:38:32 UTC (rev 7896) @@ -1,11 +1,11 @@ Name: Control Version: 2.0.0 -Date: 2010-09-14 +Date: 2010-10-31 Author: Lukas Reichlin <luk...@gm...> Maintainer: Lukas Reichlin <luk...@gm...> Title: Control Systems -Description: control systems package increasingly based on the SLICOT Fortran library -Depends: octave (>= 3.2.3) +Description: Octave control systems package increasingly based on the SLICOT Fortran library +Depends: octave (>= 3.2.4) Autoload: yes License: GPL version 3 or later Url: http://octave.sf.net, http://www.slicot.org Modified: trunk/octave-forge/main/control/devel/@frd/display.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/devel/@frd/display.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -38,7 +38,7 @@ display (sys.lti); # display sampling time - if (tsam == -1) + if (tsam == -2) disp ("Static gain."); elseif (tsam == 0) disp ("Continuous-time model."); Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -64,7 +64,7 @@ ## because sys2 needs to be converted to FRD, ## but sys1 contains no valid frequencies. ## * Because of the reasons given above, - ## tsam = -1 and w = -1 don't make sense + ## tsam = -2 and w = -1 don't make sense ## model precedence: frd > ss > zpk > tf > double superiorto ("ss", "zpk", "tf", "double"); @@ -73,7 +73,7 @@ switch (nargin) case 0 # empty objet sys = frd () - tsam = 0; # tsam = -1 is *not* possible + tsam = 0; # tsam = -2 is *not* possible case 1 if (isa (H, "frd")) # already in frd form sys = frd (frdsys) @@ -98,7 +98,7 @@ otherwise # default case argc = numel (varargin); # number of additional arguments after H and w - if (issample (varargin{1}, 0)) # sys = frd (H, w, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, -10)) # sys = frd (H, w, tsam, "prop1, "val1", ...) tsam = varargin{1}; # discrete-time argc--; # tsam is not a property-value pair if (argc > 0) # if there are any properties and values ... Modified: trunk/octave-forge/main/control/inst/@lti/__lti_group__.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/__lti_group__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/__lti_group__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -36,10 +36,14 @@ if (lti1.tsam == lti2.tsam) retlti.tsam = lti1.tsam; - elseif (lti1.tsam == -1) + elseif (lti1.tsam == -2) retlti.tsam = lti2.tsam; - elseif (lti2.tsam == -1) + elseif (lti2.tsam == -2) retlti.tsam = lti1.tsam; + elseif (lti1.tsam == -1 && lti2.tsam > 0) + retlti.tsam = lti2.tsam; + elseif (lti2.tsam == -1 && lti1.tsam > 0) + retlti.tsam = lti1.tsam; else error ("lti_group: systems must have identical sampling times"); endif Modified: trunk/octave-forge/main/control/inst/@lti/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/display.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -26,6 +26,8 @@ if (ltisys.tsam > 0) disp (sprintf ("Sampling time: %g s", ltisys.tsam)); + elseif (ltisys.tsam == -1) + disp ("Sampling time: unspecified"); endif endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@lti/isct.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/isct.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/isct.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -30,6 +30,6 @@ print_usage (); endif - bool = (ltisys.tsam == 0 || ltisys.tsam == -1); + bool = (ltisys.tsam == 0 || ltisys.tsam == -2); endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/@lti/lti.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/lti.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -22,7 +22,7 @@ ## Created: September 2009 ## Version: 0.2 -function ltisys = lti (p = 0, m = 0, tsam = -1) +function ltisys = lti (p = 0, m = 0, tsam = -2) inname = repmat ({""}, m, 1); outname = repmat ({""}, p, 1); Modified: trunk/octave-forge/main/control/inst/@lti/norm.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/norm.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/norm.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -104,7 +104,7 @@ if (fpeak(2) > 0) if (discrete) - wpeak = fpeak(1) / tsam; + wpeak = fpeak(1) / abs (tsam); # tsam could be -1 else wpeak = fpeak(1); endif Modified: trunk/octave-forge/main/control/inst/@lti/set.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/set.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@lti/set.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -66,7 +66,7 @@ sys.outname = __adjust_labels__ (val, p); case {"tsam", "ts"} - if (issample (val)) + if (issample (val, -1)) sys.tsam = val; warning ("lti: set: use the editing of property ""%s"" with caution", prop); warning (" it may lead to corrupted models"); Modified: trunk/octave-forge/main/control/inst/@ss/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@ss/__freqresp__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -30,24 +30,24 @@ error ("ss: freqresp: system must be square for response type %d", resptype); endif - if (tsam > 0) # discrete system - s = num2cell (exp (i * w * tsam)); - else # continuous system + if (isct (sys)) # continuous system s = num2cell (i * w); + else # discrete system + s = num2cell (exp (i * w * abs (tsam))); endif switch (resptype) - case 0 # default system + case 0 # default system H = cellfun (@(x) c/(x*e - a)*b + d, s, "uniformoutput", false); - case 1 # inversed system + case 1 # inversed system H = cellfun (@(x) inv (c/(x*e - a)*b + d), s, "uniformoutput", false); - case 2 # inversed sensitivity + case 2 # inversed sensitivity j = eye (columns (b)); H = cellfun (@(x) j + c/(x*e - a)*b + d, s, "uniformoutput", false); - case 3 # inversed complementary sensitivity + case 3 # inversed complementary sensitivity j = eye (columns (b)); H = cellfun (@(x) j + inv (c/(x*e - a)*b + d), s, "uniformoutput", false); Modified: trunk/octave-forge/main/control/inst/@ss/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/display.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@ss/display.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -47,7 +47,7 @@ display (sys.lti); # display sampling time - if (tsam == -1) + if (tsam == -2) disp ("Static gain."); elseif (tsam == 0) disp ("Continuous-time model."); Modified: trunk/octave-forge/main/control/inst/@ss/ss.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@ss/ss.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -118,7 +118,7 @@ endif elseif (nargin > 4) # default case sys = ss (a, b, c, d, "prop1, "val1", ...) argc = numel (varargin); # number of additional arguments after d - if (issample (varargin{1}, 0)) # sys = ss (a, b, c, d, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, -10)) # sys = ss (a, b, c, d, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; if (argc > 0) Modified: trunk/octave-forge/main/control/inst/@tf/__freqresp__.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/__freqresp__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@tf/__freqresp__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -26,10 +26,10 @@ [num, den, tsam] = tfdata (sys); - if (tsam > 0) # discrete system - s = num2cell (exp (i * w * tsam)); - else # continuous system + if (isct (sys)) # continuous system s = num2cell (i * w); + else # discrete system + s = num2cell (exp (i * w * abs (tsam))); endif f = @(z) cellfun (@(x, y) polyval (x, z) / polyval (y, z), num, den); Modified: trunk/octave-forge/main/control/inst/@tf/tf.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/@tf/tf.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -79,32 +79,32 @@ function sys = tf (num = {}, den = {}, varargin) ## model precedence: frd > ss > zpk > tf > double - ## inferiorto ("frd", "ss", "zpk"); # error if de-commented. bug in octave? + ## inferiorto ("frd", "ss", "zpk"); # error if de-commented. bug in octave? superiorto ("double"); argc = 0; switch (nargin) case 0 - tsam = -1; - tfvar = "x"; # undefined + tsam = -2; + tfvar = "x"; # undefined case 1 - if (isa (num, "tf")) # already in tf form + if (isa (num, "tf")) # already in tf form sys = num; return; - elseif (isa (num, "lti")) # another lti object + elseif (isa (num, "lti")) # another lti object [sys, numlti] = __sys2tf__ (num); - sys.lti = numlti; # preserve lti properties + sys.lti = numlti; # preserve lti properties return; - elseif (is_real_matrix (num)) # static gain + elseif (is_real_matrix (num)) # static gain num = num2cell (num); num = __vec2tfpoly__ (num); [p, m] = size (num); den = tfpolyones (p, m); - tsam = -1; - tfvar = "x"; # undefined - elseif (ischar (num)) # s = tf ("s") + tsam = -2; + tfvar = "x"; # undefined + elseif (ischar (num)) # s = tf ("s") tfvar = num; num = __vec2tfpoly__ ([1, 0]); den = __vec2tfpoly__ ([1]); @@ -114,24 +114,24 @@ endif case 2 - if (ischar (num) && issample (den)) # z = tf ("z", 0.3) + if (ischar (num) && issample (den, -1)) # z = tf ("z", 0.3) tfvar = num; tsam = den; num = __vec2tfpoly__ ([1, 0]); den = __vec2tfpoly__ ([1]); - else # sys = tf (num, den) + else # sys = tf (num, den) num = __vec2tfpoly__ (num); den = __vec2tfpoly__ (den); tfvar = "s"; tsam = 0; endif - otherwise # default case + otherwise # default case num = __vec2tfpoly__ (num); den = __vec2tfpoly__ (den); argc = numel (varargin); - if (issample (varargin{1}, 0)) # sys = tf (num, den, tsam, "prop1, "val1", ...) + if (issample (varargin{1}, -10)) # sys = tf (num, den, tsam, "prop1, "val1", ...) tsam = varargin{1}; argc--; @@ -146,7 +146,7 @@ if (argc > 0) varargin = varargin(2:end); endif - else # sys = tf (num, den, "prop1, "val1", ...) + else # sys = tf (num, den, "prop1, "val1", ...) tsam = 0; tfvar = "s"; endif Modified: trunk/octave-forge/main/control/inst/__adjust_ss_data__.m =================================================================== --- trunk/octave-forge/main/control/inst/__adjust_ss_data__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/__adjust_ss_data__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -27,7 +27,7 @@ if (isempty (a)) # static system a = []; # avoid [](nx0) or [](0xn) - tsam = -1; + tsam = -2; endif if (isempty (d)) @@ -42,7 +42,7 @@ if (isempty (b) && isempty (c)) # sys = ss ([], [], [], d) b = zeros (0, columns (d)); c = zeros (rows(d), 0); - tsam = -1; + tsam = -2; endif endfunction \ No newline at end of file Modified: trunk/octave-forge/main/control/inst/__frequency_vector__.m =================================================================== --- trunk/octave-forge/main/control/inst/__frequency_vector__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/__frequency_vector__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -41,8 +41,8 @@ zer = zero (sys); pol = pole (sys); - tsam = get (sys, "tsam"); - discrete = (tsam > 0); # static gains (tsam = -1) are continuous + tsam = abs (get (sys, "tsam")); # tsam could be -1 + discrete = ! isct (sys); # static gains (tsam = -2) are assumed continuous ## make sure zer, pol are row vectors pol = reshape (pol, 1, []); Modified: trunk/octave-forge/main/control/inst/__time_response__.m =================================================================== --- trunk/octave-forge/main/control/inst/__time_response__.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/__time_response__.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -36,6 +36,7 @@ [A, B, C, D, tsam] = ssdata (sys); discrete = ! isct (sys); # static gains are treated as analog systems + tsam = abs (tsam); # use 1 second if tsam is unspecified (-1) if (discrete) if (! isempty (dt)) @@ -156,13 +157,8 @@ stable = isstable (sys); outname = get (sys, "outname"); + outname = __labels__ (outname, "y_"); - if (isempty (outname) || isequal ("", outname{:})) - outname = strseq ("y_", 1 : length (outname)); - else - outname = __mark_empty_names__ (outname); - endif - if (strcmp (resptype, "initial")) cols = 1; else Modified: trunk/octave-forge/main/control/inst/dlqr.m =================================================================== --- trunk/octave-forge/main/control/inst/dlqr.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/dlqr.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -88,7 +88,7 @@ tsam = 1; # any value > 0 could be used here endif - if (tsam > 0) + if (issample (tsam, -1)) [x, l, g] = dare (a, b, q, r, s, e); else [x, l, g] = care (a, b, q, r, s, e); Modified: trunk/octave-forge/main/control/inst/issample.m =================================================================== --- trunk/octave-forge/main/control/inst/issample.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/issample.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -28,7 +28,11 @@ ## @item flg = 0 ## Accept real scalars @var{ts} >= 0. ## @item flg = -1 +## Accept real scalars @var{ts} > 0 and @var{ts} == -1. +## @item flg = -10 ## Accept real scalars @var{ts} >= 0 and @var{ts} == -1. +## @item flg = -2 +## Accept real scalars @var{ts} >= 0, @var{ts} == -1 and @var{ts} == -2. ## @end table ## ## @strong{Outputs} @@ -53,12 +57,16 @@ endif switch (flg) - case 1 # refuse -1 and 0 + case 1 # discrete bool = is_real_scalar (tsam) && (tsam > 0); - case 0 # allow 0, refuse -1 + case 0 # continuous or discrete bool = is_real_scalar (tsam) && (tsam >= 0); - case -1 # allow -1 and 0 + case -1 # discrete, tsam unspecified + bool = is_real_scalar (tsam) && (tsam > 0 || tsam == -1); + case -10 # continuous or discrete, tsam unspecified bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1); + case -2 # accept static gains + bool = is_real_scalar (tsam) && (tsam >= 0 || tsam == -1 || tsam == -2); otherwise print_usage (); endswitch @@ -67,8 +75,8 @@ ## flg == 1 -%!assert (issample (1), true) -%!assert (issample (pi), true) +%!assert (issample (1)) +%!assert (issample (pi)) %!assert (issample (0), false) %!assert (issample (-1), false) %!assert (issample (-1, 1), false) @@ -77,20 +85,20 @@ %!assert (issample (2+2i), false) ## flg == 0 -%!assert (issample (1, 0), true) -%!assert (issample (0, 0), true) +%!assert (issample (1, 0)) +%!assert (issample (0, 0)) %!assert (issample (-1, 0), false) -%!assert (issample (pi, 0), true) +%!assert (issample (pi, 0)) %!assert (issample ("b", 0), false) %!assert (issample (rand (3,2), 0), false) %!assert (issample (2+2i, 0), false) %!assert (issample (0+2i, 0), false) ## flg == -1 -%!assert (issample (-1, -1), true) -%!assert (issample (0, -1), true) -%!assert (issample (1, -1), true) -%!assert (issample (pi, -1), true) +%!assert (issample (-1, -1)) +%!assert (issample (0, -1), false) +%!assert (issample (1, -1)) +%!assert (issample (pi, -1)) %!assert (issample (-pi, -1), false) %!assert (issample ("b", -1), false) %!assert (issample (rand (3,2), -1), false) Modified: trunk/octave-forge/main/control/inst/lqr.m =================================================================== --- trunk/octave-forge/main/control/inst/lqr.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/lqr.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -89,7 +89,7 @@ tsam = 0; endif - if (tsam > 0) + if (issample (tsam, -1)) [x, l, g] = dare (a, b, q, r, s, e); else [x, l, g] = care (a, b, q, r, s, e); Modified: trunk/octave-forge/main/control/inst/lsim.m =================================================================== --- trunk/octave-forge/main/control/inst/lsim.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/lsim.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -68,6 +68,7 @@ [A, B, C, D, tsam] = ssdata (sys); discrete = ! isct (sys); # static gains are treated as analog systems + tsam = abs (tsam); # use 1 second as default if tsam is unspecified (-1) urows = rows (u); ucols = columns (u); @@ -137,13 +138,8 @@ if (! nargout) # plot information str = "Linear Simulation Results"; outname = get (sys, "outname"); + outname = __labels__ (outname, "y_"); - if (isempty (outname) || isequal ("", outname{:})) - outname = strseq ("y_", 1 : length (outname)); - else - outname = __mark_empty_names__ (outname); - endif - if (discrete) # discrete system for k = 1 : p subplot (p, 1, k); Modified: trunk/octave-forge/main/control/inst/ltimodels.m =================================================================== --- trunk/octave-forge/main/control/inst/ltimodels.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/ltimodels.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -73,13 +73,13 @@ ## isct, isdt %!shared ltisys %! ltisys = tf (12); -%!assert (ltisys.ts, -1); +%!assert (ltisys.ts, -2); %!assert (isct (ltisys)); %!assert (isdt (ltisys)); %!shared ltisys %! ltisys = ss (17); -%!assert (ltisys.ts, -1); +%!assert (ltisys.ts, -2); %!assert (isct (ltisys)); %!assert (isdt (ltisys)); Modified: trunk/octave-forge/main/control/inst/margin.m =================================================================== --- trunk/octave-forge/main/control/inst/margin.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/margin.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -140,12 +140,14 @@ endif ## get transfer function - [num, den, Ts] = tfdata (sys); + [num, den, tsam] = tfdata (sys); + continuous = isct (sys); + tsam = abs (tsam); # use 1 second as default if tsam == -1 num = num{1, 1}; den = den{1, 1}; - if (Ts == 0) # CONTINUOUS SYSTEM + if (continuous) # CONTINUOUS SYSTEM ## create polynomials s -> jw l_num = length (num); @@ -162,7 +164,7 @@ w = roots (gm_poly); ## filter results - [gamma, w_gamma] = gm_filter (w, num, den, Ts, tol); + [gamma, w_gamma] = gm_filter (w, num, den, tsam, tol, continuous); ## PHASE MARGIN ## create pm polynomials @@ -179,7 +181,7 @@ w = roots (pm_poly); ## filter results - [phi, w_phi] = pm_filter (w, num, den, Ts, tol); + [phi, w_phi] = pm_filter (w, num, den, tsam, tol, continuous); else # DISCRETE SYSTEM @@ -218,8 +220,8 @@ if (length (idx) > 0) # if z with magnitude 1 exist z_gm = z(idx); - w = log (z_gm) / (i*Ts); # get frequencies w from z - [gamma, w_gamma] = gm_filter (w, num, den, Ts, tol); + w = log (z_gm) / (i*tsam); # get frequencies w from z + [gamma, w_gamma] = gm_filter (w, num, den, tsam, tol, continuous); else # there are no z with magnitude 1 gamma = Inf; w_gamma = NaN; @@ -244,8 +246,8 @@ if (length (idx) > 0) # if z with magnitude 1 exist z_gm = z(idx); - w = log (z_gm) / (i*Ts); # get frequencies w from z - [phi, w_phi] = pm_filter (w, num, den, Ts, tol); + w = log (z_gm) / (i*tsam); # get frequencies w from z + [phi, w_phi] = pm_filter (w, num, den, tsam, tol, continuous); else # there are no z with magnitude 1 phi = 180; w_phi = NaN; @@ -281,7 +283,7 @@ title_str = sprintf ("GM = %g dB (at %g rad/s), PM = %g deg (at %g rad/s)", gamma_db, w_gamma, phi, w_phi); - if (Ts == 0) + if (continuous) xl_str = "Frequency [rad/s]"; else xl_str = sprintf ("Frequency [rad/s] w_N = %g", pi/Ts); @@ -326,17 +328,17 @@ endfunction -function [gamma, w_gamma] = gm_filter (w, num, den, Ts, tol) +function [gamma, w_gamma] = gm_filter (w, num, den, tsam, tol, continuous) idx = find ((abs (imag (w)) < tol) & (real (w) > 0)); # find frequencies in R+ if (length (idx) > 0) # if frequencies in R+ exist w_gm = real (w(idx)); - if (Ts == 0) + if (continuous) s = num2cell (i * w_gm); else - s = num2cell (exp (i * w_gm * Ts)); + s = num2cell (exp (i * w_gm * tsam)); endif f_resp = cellfun (@(x) polyval (num, x) / polyval (den, x), s, "uniformoutput", false); @@ -372,17 +374,17 @@ endfunction -function [phi, w_phi] = pm_filter (w, num, den, Ts, tol) +function [phi, w_phi] = pm_filter (w, num, den, tsam, tol, continuous) idx = find ((abs (imag (w)) < tol) & (real (w) > 0)); # find frequencies in R+ if (length (idx) > 0) # if frequencies in R+ exist w_pm = real (w(idx)); - if (Ts == 0) + if (continuous) s = num2cell (i * w_pm); else - s = num2cell (exp (i * w_pm * Ts)); + s = num2cell (exp (i * w_pm * tsam)); endif f_resp = cellfun (@(x) polyval (num, x) / polyval (den, x), s, "uniformoutput", false); Modified: trunk/octave-forge/main/control/inst/place.m =================================================================== --- trunk/octave-forge/main/control/inst/place.m 2010-10-29 14:44:53 UTC (rev 7895) +++ trunk/octave-forge/main/control/inst/place.m 2010-10-30 23:38:32 UTC (rev 7896) @@ -89,7 +89,7 @@ p = b; sys = a; [a, b] = dssdata (sys, []); # descriptor matrice e should have no influence - discrete = ! isct (sys); # treat tsam = -1 as continuous system + discrete = ! isct (sys); # treat tsam = -2 as continuous system endif else # place (a, b, p), place (a, b, p, alpha), place (a, b, p, alpha, tol) if (nargin < 3) # nargin > 5 already tested This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-12-17 22:17:29
|
Revision: 8026 http://octave.svn.sourceforge.net/octave/?rev=8026&view=rev Author: paramaniac Date: 2010-12-17 22:17:22 +0000 (Fri, 17 Dec 2010) Log Message: ----------- control: move evolving code to /devel Added Paths: ----------- trunk/octave-forge/main/control/devel/ctrbf.m trunk/octave-forge/main/control/devel/minreal.m trunk/octave-forge/main/control/devel/obsvf.m Removed Paths: ------------- trunk/octave-forge/main/control/inst/ctrbf.m trunk/octave-forge/main/control/inst/minreal.m trunk/octave-forge/main/control/inst/obsvf.m Copied: trunk/octave-forge/main/control/devel/ctrbf.m (from rev 8025, trunk/octave-forge/main/control/inst/ctrbf.m) =================================================================== --- trunk/octave-forge/main/control/devel/ctrbf.m (rev 0) +++ trunk/octave-forge/main/control/devel/ctrbf.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -0,0 +1,70 @@ +## Copyright (C) 2010 Benjamin Fernandez <ma...@be...> +## +## This program is free software; you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation; either version 2 of the License, or +## (at your option) any later version. +## +## This program is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with Octave; see the file COPYING. If not, see +## <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## @deftypefn{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} ctrbf (@var{A}, @var{B}, @var{C}) +## @deftypefnx{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} ctrbf (@var{A}, @var{B}, @var{C}, @var{TOL}) +## If Co=ctrb(A,B) has rank r <= n = SIZE(A,1), then there is a +## similarity transformation Tc such that Tc = [t1 t2] where t1 +## is the controlable subspace and t2 is orthogonal to t1 +## +## @example +## @group +## Abar = Tc \ A * Tc , Bbar = Tc \ B , Cbar = C * Tc +## @end group +## @end example +## +## and the transformed system has the form +## +## @example +## @group +## | Ac A12| | Bc | +## Abar = |----------|, Bbar = | ---|, Cbar = [Cc | Cnc]. +## | 0 Anc| | 0 | +## @end group +## @end example +## +## where (Ac,Bc) is controllable, and Cc(sI-Ac)^(-1)Bc = C(sI-A)^(-1)B. +## and the system is stabilizable if Anc has no eigenvalues in +## the right half plane. The last output K is a vector of length n +## containing the number of controllable states. +## @end deftypefn + +## Author: Benjamin Fernandez <benjas@benjas-laptop> +## Created: 2010-04-30 + +function [Abar, Bbar, Cbar, T, K] = ctrbf (A, B, C, TOL) + + if (nargin < 3 || nargin > 4) + print_usage (); + endif + + if (nargin == 3) + TOL = length (A) * norm (A,1) * eps; + endif + + Co = ctrb (A, B); + [nrc, ncc] = size (Co); + rco = rank (Co, TOL); + lr = nrc - rco; + [U, S, V] = svd (Co); + K = U(:, 1:rco); # Basis column space + T = U; # [B orth(B)] + Abar = T \ A * T; + Bbar = T \ B; + Cbar = C * T; + +endfunction \ No newline at end of file Copied: trunk/octave-forge/main/control/devel/minreal.m (from rev 8025, trunk/octave-forge/main/control/inst/minreal.m) =================================================================== --- trunk/octave-forge/main/control/devel/minreal.m (rev 0) +++ trunk/octave-forge/main/control/devel/minreal.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -0,0 +1,45 @@ +## Copyright (C) 2010 Benjamin Fernandez <ma...@be...> +## +## This program is free software; you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation; either version 2 of the License, or +## (at your option) any later version. +## +## This program is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with Octave; see the file COPYING. If not, see +## <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## @deftypefn{Function File} {[@var{Amin}, @var{Bmin}, @var{Cmin}] =} ctrbf (@var{A}, @var{B}, @var{C}) +## @deftypefnx{Function File} {[@var{Amin}, @var{Bmin}, @var{Cmin}] =} ctrbf (@var{A}, @var{B}, @var{C}, @var{TOL}) +## Minimal realization of the system (A,B,C). +## If the system is controlable and observable, the syste es minimal. +## If the system is not controlable or/and observable, a new system created +## with the controlabe and observable subspace is equivalent +## which means that Cco(sI-Aco)^(-1)Bco = C(sI-A)^(-1)B. +## @end deftypefn + +## Author: Benjamin Fernandez <ma...@be...> +## Created: 2010-07-10 + +function [Amin,Bmin,Cmin] = minreal(A,B,C,TOL) + if(nargin<3 || nargin>4) + print_usage(); + endif + n = length(A); + if(nargin == 3) + TOL = n*norm(A,1)*eps; + endif + [Abar,Bbar,Cbar,T,K,Ac,Bc,Cc,Cnc,lc] = ctrbf(A,B,C); + [Abar,Bbar,Cbar,T,K,Amin,Bmin,Cmin,Cno,lo] = obsvf(Ac,Bc,Cc); + l = lc+lo; + disp('States reduced:'); + disp(l); + +endfunction + Copied: trunk/octave-forge/main/control/devel/obsvf.m (from rev 8025, trunk/octave-forge/main/control/inst/obsvf.m) =================================================================== --- trunk/octave-forge/main/control/devel/obsvf.m (rev 0) +++ trunk/octave-forge/main/control/devel/obsvf.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -0,0 +1,70 @@ +## Copyright (C) 2010 Benjamin Fernandez +## +## This program is free software; you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation; either version 2 of the License, or +## (at your option) any later version. +## +## This program is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with Octave; see the file COPYING. If not, see +## <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## @deftypefn{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} obsvf (@var{A}, @var{B}, @var{C}) +## @deftypefnx{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} obsvf (@var{A}, @var{B}, @var{C}, @var{TOL}) +## If Ob=obsv(A,C) has rank r <= n = SIZE(A,1), then there is a +## similarity transformation Tc such that To = [t1;t2] where t1 is c +## and t2 is orthogonal to t1 +## +## @example +## @group +## Abar = To \ A * To , Bbar = To \ B , Cbar = C * To +## @end group +## @end example +## +## and the transformed system has the form +## +## @example +## @group +## | Ao 0 | | Bo | +## Abar = |----------|, Bbar = | --- |, Cbar = [Co | 0 ]. +## | A21 Ano| | Bno | +## @end group +## @end example +## +## where (Ao,Bo) is observable, and Co(sI-Ao)^(-1)Bo = C(sI-A)^(-1)B. And +## system is detectable if Ano has no eigenvalues in the right +## half plane. The last output K is a vector of length n containing the +## number of observable states. +## @end deftypefn + +## Author: Benjamin Fernandez <benjas@benjas-laptop> +## Created: 2010-05-02 + +function [Abar, Bbar, Cbar, T, K] = obsvf (A, B, C, TOL) + + if (nargin < 3 || nargin > 4) + print_usage (); + endif + + if (nargin == 3) + TOL = length (A) * norm (A, 1) * eps; + endif + + Ob = obsv (A, C); + [nro, nco] = size (Ob); + rob = rank (Ob); + lr = nco - rob; + [U, S, V] = svd (Ob); + K = V(:, 1:rob); # Basis raw space + T = V; # [c; orth(c)]; + Abar = T \ A * T; + Bbar = T \ B; + Cbar = C * T; + +endfunction \ No newline at end of file Deleted: trunk/octave-forge/main/control/inst/ctrbf.m =================================================================== --- trunk/octave-forge/main/control/inst/ctrbf.m 2010-12-17 20:34:26 UTC (rev 8025) +++ trunk/octave-forge/main/control/inst/ctrbf.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -1,70 +0,0 @@ -## Copyright (C) 2010 Benjamin Fernandez <ma...@be...> -## -## This program is free software; you can redistribute it and/or modify -## it under the terms of the GNU General Public License as published by -## the Free Software Foundation; either version 2 of the License, or -## (at your option) any later version. -## -## This program is distributed in the hope that it will be useful, -## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -## GNU General Public License for more details. -## -## You should have received a copy of the GNU General Public License -## along with Octave; see the file COPYING. If not, see -## <http://www.gnu.org/licenses/>. - -## -*- texinfo -*- -## @deftypefn{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} ctrbf (@var{A}, @var{B}, @var{C}) -## @deftypefnx{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} ctrbf (@var{A}, @var{B}, @var{C}, @var{TOL}) -## If Co=ctrb(A,B) has rank r <= n = SIZE(A,1), then there is a -## similarity transformation Tc such that Tc = [t1 t2] where t1 -## is the controlable subspace and t2 is orthogonal to t1 -## -## @example -## @group -## Abar = Tc \ A * Tc , Bbar = Tc \ B , Cbar = C * Tc -## @end group -## @end example -## -## and the transformed system has the form -## -## @example -## @group -## | Ac A12| | Bc | -## Abar = |----------|, Bbar = | ---|, Cbar = [Cc | Cnc]. -## | 0 Anc| | 0 | -## @end group -## @end example -## -## where (Ac,Bc) is controllable, and Cc(sI-Ac)^(-1)Bc = C(sI-A)^(-1)B. -## and the system is stabilizable if Anc has no eigenvalues in -## the right half plane. The last output K is a vector of length n -## containing the number of controllable states. -## @end deftypefn - -## Author: Benjamin Fernandez <benjas@benjas-laptop> -## Created: 2010-04-30 - -function [Abar, Bbar, Cbar, T, K] = ctrbf (A, B, C, TOL) - - if (nargin < 3 || nargin > 4) - print_usage (); - endif - - if (nargin == 3) - TOL = length (A) * norm (A,1) * eps; - endif - - Co = ctrb (A, B); - [nrc, ncc] = size (Co); - rco = rank (Co, TOL); - lr = nrc - rco; - [U, S, V] = svd (Co); - K = U(:, 1:rco); # Basis column space - T = U; # [B orth(B)] - Abar = T \ A * T; - Bbar = T \ B; - Cbar = C * T; - -endfunction \ No newline at end of file Deleted: trunk/octave-forge/main/control/inst/minreal.m =================================================================== --- trunk/octave-forge/main/control/inst/minreal.m 2010-12-17 20:34:26 UTC (rev 8025) +++ trunk/octave-forge/main/control/inst/minreal.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -1,45 +0,0 @@ -## Copyright (C) 2010 Benjamin Fernandez <ma...@be...> -## -## This program is free software; you can redistribute it and/or modify -## it under the terms of the GNU General Public License as published by -## the Free Software Foundation; either version 2 of the License, or -## (at your option) any later version. -## -## This program is distributed in the hope that it will be useful, -## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -## GNU General Public License for more details. -## -## You should have received a copy of the GNU General Public License -## along with Octave; see the file COPYING. If not, see -## <http://www.gnu.org/licenses/>. - -## -*- texinfo -*- -## @deftypefn{Function File} {[@var{Amin}, @var{Bmin}, @var{Cmin}] =} ctrbf (@var{A}, @var{B}, @var{C}) -## @deftypefnx{Function File} {[@var{Amin}, @var{Bmin}, @var{Cmin}] =} ctrbf (@var{A}, @var{B}, @var{C}, @var{TOL}) -## Minimal realization of the system (A,B,C). -## If the system is controlable and observable, the syste es minimal. -## If the system is not controlable or/and observable, a new system created -## with the controlabe and observable subspace is equivalent -## which means that Cco(sI-Aco)^(-1)Bco = C(sI-A)^(-1)B. -## @end deftypefn - -## Author: Benjamin Fernandez <ma...@be...> -## Created: 2010-07-10 - -function [Amin,Bmin,Cmin] = minreal(A,B,C,TOL) - if(nargin<3 || nargin>4) - print_usage(); - endif - n = length(A); - if(nargin == 3) - TOL = n*norm(A,1)*eps; - endif - [Abar,Bbar,Cbar,T,K,Ac,Bc,Cc,Cnc,lc] = ctrbf(A,B,C); - [Abar,Bbar,Cbar,T,K,Amin,Bmin,Cmin,Cno,lo] = obsvf(Ac,Bc,Cc); - l = lc+lo; - disp('States reduced:'); - disp(l); - -endfunction - Deleted: trunk/octave-forge/main/control/inst/obsvf.m =================================================================== --- trunk/octave-forge/main/control/inst/obsvf.m 2010-12-17 20:34:26 UTC (rev 8025) +++ trunk/octave-forge/main/control/inst/obsvf.m 2010-12-17 22:17:22 UTC (rev 8026) @@ -1,70 +0,0 @@ -## Copyright (C) 2010 Benjamin Fernandez -## -## This program is free software; you can redistribute it and/or modify -## it under the terms of the GNU General Public License as published by -## the Free Software Foundation; either version 2 of the License, or -## (at your option) any later version. -## -## This program is distributed in the hope that it will be useful, -## but WITHOUT ANY WARRANTY; without even the implied warranty of -## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -## GNU General Public License for more details. -## -## You should have received a copy of the GNU General Public License -## along with Octave; see the file COPYING. If not, see -## <http://www.gnu.org/licenses/>. - -## -*- texinfo -*- -## @deftypefn{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} obsvf (@var{A}, @var{B}, @var{C}) -## @deftypefnx{Function File} {[@var{Abar}, @var{Bbar}, @var{Cbar}, @var{T}, @var{K}] =} obsvf (@var{A}, @var{B}, @var{C}, @var{TOL}) -## If Ob=obsv(A,C) has rank r <= n = SIZE(A,1), then there is a -## similarity transformation Tc such that To = [t1;t2] where t1 is c -## and t2 is orthogonal to t1 -## -## @example -## @group -## Abar = To \ A * To , Bbar = To \ B , Cbar = C * To -## @end group -## @end example -## -## and the transformed system has the form -## -## @example -## @group -## | Ao 0 | | Bo | -## Abar = |----------|, Bbar = | --- |, Cbar = [Co | 0 ]. -## | A21 Ano| | Bno | -## @end group -## @end example -## -## where (Ao,Bo) is observable, and Co(sI-Ao)^(-1)Bo = C(sI-A)^(-1)B. And -## system is detectable if Ano has no eigenvalues in the right -## half plane. The last output K is a vector of length n containing the -## number of observable states. -## @end deftypefn - -## Author: Benjamin Fernandez <benjas@benjas-laptop> -## Created: 2010-05-02 - -function [Abar, Bbar, Cbar, T, K] = obsvf (A, B, C, TOL) - - if (nargin < 3 || nargin > 4) - print_usage (); - endif - - if (nargin == 3) - TOL = length (A) * norm (A, 1) * eps; - endif - - Ob = obsv (A, C); - [nro, nco] = size (Ob); - rob = rank (Ob); - lr = nco - rob; - [U, S, V] = svd (Ob); - K = V(:, 1:rob); # Basis raw space - T = V; # [c; orth(c)]; - Abar = T \ A * T; - Bbar = T \ B; - Cbar = C * T; - -endfunction \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2010-12-24 13:45:25
|
Revision: 8039 http://octave.svn.sourceforge.net/octave/?rev=8039&view=rev Author: paramaniac Date: 2010-12-24 13:45:18 +0000 (Fri, 24 Dec 2010) Log Message: ----------- control: minor changes related to inputname function Modified Paths: -------------- trunk/octave-forge/main/control/devel/@frd/frd.m trunk/octave-forge/main/control/inst/@ss/display.m trunk/octave-forge/main/control/inst/@tf/display.m trunk/octave-forge/main/control/inst/augw.m trunk/octave-forge/main/control/inst/care.m trunk/octave-forge/main/control/inst/dare.m trunk/octave-forge/main/control/inst/dlyap.m trunk/octave-forge/main/control/inst/dlyapchol.m trunk/octave-forge/main/control/inst/impulse.m trunk/octave-forge/main/control/inst/initial.m trunk/octave-forge/main/control/inst/lyap.m trunk/octave-forge/main/control/inst/lyapchol.m trunk/octave-forge/main/control/inst/step.m Modified: trunk/octave-forge/main/control/devel/@frd/frd.m =================================================================== --- trunk/octave-forge/main/control/devel/@frd/frd.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/devel/@frd/frd.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -72,7 +72,7 @@ argc = 0; # initialize argument count switch (nargin) - case 0 # empty objet sys = frd () + case 0 # empty object sys = frd () tsam = 0; # tsam = -2 is *not* possible case 1 Modified: trunk/octave-forge/main/control/inst/@ss/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@ss/display.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/@ss/display.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -24,7 +24,7 @@ function display (sys) - inputname_str = inputname(1); + inputname_str = inputname (1); [inname, outname, tsam] = __lti_data__ (sys.lti); stname = sys.stname; Modified: trunk/octave-forge/main/control/inst/@tf/display.m =================================================================== --- trunk/octave-forge/main/control/inst/@tf/display.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/@tf/display.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -24,7 +24,7 @@ function display (sys) - inputname_str = inputname(1); + inputname_str = inputname (1); [inname, outname] = __lti_data__ (sys.lti); [inname, m] = __labels__ (inname, "u"); Modified: trunk/octave-forge/main/control/inst/augw.m =================================================================== --- trunk/octave-forge/main/control/inst/augw.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/augw.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -149,7 +149,7 @@ endfor [p, m] = size (W); # weighting function now of correct size else # model is MIMO or MISO - error ("augw: %s must have 1 or %d inputs", inputname(1), s); + error ("augw: %s must have 1 or %d inputs", inputname (1), s); endif endfunction Modified: trunk/octave-forge/main/control/inst/care.m =================================================================== --- trunk/octave-forge/main/control/inst/care.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/care.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -87,7 +87,7 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: November 2009 -## Version: 0.5 +## Version: 0.5.1 function [x, l, g] = care (a, b, q, r, s = [], e = []) @@ -98,29 +98,41 @@ endif if (! is_real_square_matrix (a, q, r)) - error ("care: a, q, r must be real and square"); + ## error ("care: a, q, r must be real and square"); + error ("care: %s, %s, %s must be real and square", \ + inputname (1), inputname (3), inputname (4)); endif if (! is_real_matrix (b) || rows (a) != rows (b)) - error ("care: a and b must have the same number of rows"); + ## error ("care: a and b must have the same number of rows"); + error ("care: %s and %s must have the same number of rows", \ + inputname (1), inputname (2)); endif if (columns (r) != columns (b)) - error ("care: b and r must have the same number of columns"); + ## error ("care: b and r must have the same number of columns"); + error ("care: %s and %s must have the same number of columns", \ + inputname (2), inputname (4)); endif if (! is_real_matrix (s) && ! size_equal (s, b)) - error ("care: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", - rows (s), columns (s), rows (b), columns (b)); + ## error ("care: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", + ## rows (s), columns (s), rows (b), columns (b)); + error ("care: %s(%dx%d) must be real and identically dimensioned with %s(%dx%d)", \ + inputname (5), rows (s), columns (s), inputname (2), rows (b), columns (b)); endif if (! isempty (e) && (! is_real_square_matrix (e) || ! size_equal (e, a))) - error ("care: a and e must have the same number of rows"); + ## error ("care: a and e must have the same number of rows"); + error ("care: %s and %s must have the same number of rows", \ + inputname (1), inputname (6)); endif ## check stabilizability if (! isstabilizable (a, b, e, [], 0)) - error ("care: (a, b) not stabilizable"); + ## error ("care: (a, b) not stabilizable"); + error ("care: (%s, %s) not stabilizable", \ + inputname (1), inputname (2)); endif ## check positive semi-definiteness @@ -133,7 +145,9 @@ m = [q, t; t.', r]; if (isdefinite (m) < 0) - error ("care: require [q, s; s.', r] >= 0"); + ## error ("care: require [q, s; s.', r] >= 0"); + error ("care: require [%s, %s; %s.', %s] >= 0", \ + inputname (3), inputname (5), inputname (5), inputname (4)); endif ## solve the riccati equation Modified: trunk/octave-forge/main/control/inst/dare.m =================================================================== --- trunk/octave-forge/main/control/inst/dare.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/dare.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -87,7 +87,7 @@ ## Author: Lukas Reichlin <luk...@gm...> ## Created: October 2009 -## Version: 0.5 +## Version: 0.5.1 function [x, l, g] = dare (a, b, q, r, s = [], e = []) @@ -98,29 +98,41 @@ endif if (! is_real_square_matrix (a, q, r)) - error ("dare: a, q, r must be real and square"); + ## error ("dare: a, q, r must be real and square"); + error ("dare: %s, %s, %s must be real and square", \ + inputname (1), inputname (3), inputname (4)); endif if (! is_real_matrix (b) || rows (a) != rows (b)) - error ("dare: a and b must have the same number of rows"); + ## error ("dare: a and b must have the same number of rows"); + error ("dare: %s and %s must have the same number of rows", \ + inputname (1), inputname (2)); endif if (columns (r) != columns (b)) - error ("dare: b and r must have the same number of columns"); + ## error ("dare: b and r must have the same number of columns"); + error ("dare: %s and %s must have the same number of columns", \ + inputname (2), inputname (4)); endif if (! is_real_matrix (s) && ! size_equal (s, b)) - error ("dare: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", - rows (s), columns (s), rows (b), columns (b)); + ## error ("dare: s(%dx%d) must be real and identically dimensioned with b(%dx%d)", + ## rows (s), columns (s), rows (b), columns (b)); + error ("dare: %s(%dx%d) must be real and identically dimensioned with %s(%dx%d)", \ + inputname (5), rows (s), columns (s), inputname (2), rows (b), columns (b)); endif if (! isempty (e) && (! is_real_square_matrix (e) || ! size_equal (e, a))) - error ("dare: a and e must have the same number of rows"); + ## error ("dare: a and e must have the same number of rows"); + error ("dare: %s and %s must have the same number of rows", \ + inputname (1), inputname (6)); endif ## check stabilizability if (! isstabilizable (a, b, e, [], 1)) - error ("dare: (a, b) not stabilizable"); + ## error ("dare: (a, b) not stabilizable"); + error ("dare: (%s, %s) not stabilizable", \ + inputname (1), inputname (2)); endif ## check positive semi-definiteness @@ -133,7 +145,9 @@ m = [q, t; t.', r]; if (isdefinite (m) < 0) - error ("dare: require [q, s; s.', r] >= 0"); + ## error ("dare: require [q, s; s.', r] >= 0"); + error ("dare: require [%s, %s; %s.', %s] >= 0", \ + inputname (3), inputname (5), inputname (5), inputname (4)); endif ## solve the riccati equation Modified: trunk/octave-forge/main/control/inst/dlyap.m =================================================================== --- trunk/octave-forge/main/control/inst/dlyap.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/dlyap.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -51,13 +51,13 @@ if (! is_real_square_matrix (a, b)) ## error ("dlyap: a, b must be real and square"); error ("dlyap: %s, %s must be real and square", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif if (rows (a) != rows (b)) ## error ("dlyap: a, b must have the same number of rows"); error ("dlyap: %s, %s must have the same number of rows", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif [x, scale] = slsb03md (a, -b, true); # AXA' - X = -B @@ -69,13 +69,13 @@ if (! is_real_square_matrix (a, b)) ## error ("dlyap: a, b must be real and square"); error ("dlyap: %s, %s must be real and square", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif if (! is_real_matrix (c) || rows (c) != rows (a) || columns (c) != columns (b)) ## error ("dlyap: c must be a real (%dx%d) matrix", rows (a), columns (b)); error ("dlyap: %s must be a real (%dx%d) matrix", \ - rows (a), columns (b), inputname(3)); + rows (a), columns (b), inputname (3)); endif x = slsb04qd (-a, b, c); # AXB' - X = -C @@ -89,19 +89,19 @@ if (! is_real_square_matrix (a, b, e)) ## error ("dlyap: a, b, e must be real and square"); error ("dlyap: %s, %s, %s must be real and square", \ - inputname(1), inputname(2), inputname(4)); + inputname (1), inputname (2), inputname (4)); endif if (rows (b) != rows (a) || rows (e) != rows (a)) ## error ("dlyap: a, b, e must have the same number of rows"); error ("dlyap: %s, %s, %s must have the same number of rows", \ - inputname(1), inputname(2), inputname(4)); + inputname (1), inputname (2), inputname (4)); endif if (! issymmetric (b)) ## error ("dlyap: b must be symmetric"); error ("dlyap: %s must be symmetric", \ - inputname(2)); + inputname (2)); endif [x, scale] = slsg03ad (a, e, -b, true); # AXA' - EXE' = -B Modified: trunk/octave-forge/main/control/inst/dlyapchol.m =================================================================== --- trunk/octave-forge/main/control/inst/dlyapchol.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/dlyapchol.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -46,19 +46,19 @@ if (! is_real_square_matrix (a)) ## error ("dlyapchol: a must be real and square"); error ("dlyapchol: %s must be real and square", \ - inputname(1)); + inputname (1)); endif if (! is_real_matrix (b)) ## error ("dlyapchol: b must be real") error ("dlyapchol: %s must be real", \ - inputname(2)) + inputname (2)) endif if (rows (a) != rows (b)) ## error ("dlyapchol: a and b must have the same number of rows"); error ("dlyapchol: %s and %s must have the same number of rows", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif [u, scale] = slsb03od (a.', b.', true); @@ -70,19 +70,19 @@ if (! is_real_square_matrix (a, e)) ## error ("dlyapchol: a, e must be real and square"); error ("dlyapchol: %s, %s must be real and square", \ - inputname(1), inputname(3)); + inputname (1), inputname (3)); endif if (! is_real_matrix (b)) ## error ("dlyapchol: b must be real"); error ("dlyapchol: %s must be real", \ - inputname(2)); + inputname (2)); endif if (rows (b) != rows (a) || rows (e) != rows (a)) ## error ("dlyapchol: a, b, e must have the same number of rows"); error ("dlyapchol: %s, %s, %s must have the same number of rows", \ - inputname(1), inputname(2), inputname(3)); + inputname (1), inputname (2), inputname (3)); endif [u, scale] = slsg03bd (a.', e.', b.', true); Modified: trunk/octave-forge/main/control/inst/impulse.m =================================================================== --- trunk/octave-forge/main/control/inst/impulse.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/impulse.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -64,7 +64,7 @@ print_usage (); endif - [y, t, x] = __time_response__ (sys, "impulse", ! nargout, tfinal, dt, [], inputname(1)); + [y, t, x] = __time_response__ (sys, "impulse", ! nargout, tfinal, dt, [], inputname (1)); if (nargout) y_r = y; Modified: trunk/octave-forge/main/control/inst/initial.m =================================================================== --- trunk/octave-forge/main/control/inst/initial.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/initial.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -76,7 +76,7 @@ print_usage (); endif - [y, t, x] = __time_response__ (sys, "initial", ! nargout, tfinal, dt, x0, inputname(1)); + [y, t, x] = __time_response__ (sys, "initial", ! nargout, tfinal, dt, x0, inputname (1)); if (nargout) y_r = y; Modified: trunk/octave-forge/main/control/inst/lyap.m =================================================================== --- trunk/octave-forge/main/control/inst/lyap.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/lyap.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -51,13 +51,13 @@ if (! is_real_square_matrix (a, b)) ## error ("lyap: a, b must be real and square"); error ("lyap: %s, %s must be real and square", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif if (rows (a) != rows (b)) ## error ("lyap: a, b must have the same number of rows"); error ("lyap: %s, %s must have the same number of rows", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif @@ -70,13 +70,13 @@ if (! is_real_square_matrix (a, b)) ## error ("lyap: a, b must be real and square"); error ("lyap: %s, %s must be real and square", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif if (! is_real_matrix (c) || rows (c) != rows (a) || columns (c) != columns (b)) ## error ("lyap: c must be a real (%dx%d) matrix", rows (a), columns (b)); error ("lyap: %s must be a real (%dx%d) matrix", \ - rows (a), columns (b), inputname(3)); + rows (a), columns (b), inputname (3)); endif x = slsb04md (a, b, -c); # AX + XB = -C @@ -90,19 +90,19 @@ if (! is_real_square_matrix (a, b, e)) ## error ("lyap: a, b, e must be real and square"); error ("lyap: %s, %s, %s must be real and square", \ - inputname(1), inputname(2), inputname(4)); + inputname (1), inputname (2), inputname (4)); endif if (rows (b) != rows (a) || rows (e) != rows (a)) ## error ("lyap: a, b, e must have the same number of rows"); error ("lyap: %s, %s, %s must have the same number of rows", \ - inputname(1), inputname(2), inputname(4)); + inputname (1), inputname (2), inputname (4)); endif if (! issymmetric (b)) ## error ("lyap: b must be symmetric"); error ("lyap: %s must be symmetric", \ - inputname(2)); + inputname (2)); endif [x, scale] = slsg03ad (a, e, -b, false); # AXE' + EXA' = -B Modified: trunk/octave-forge/main/control/inst/lyapchol.m =================================================================== --- trunk/octave-forge/main/control/inst/lyapchol.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/lyapchol.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -46,19 +46,19 @@ if (! is_real_square_matrix (a)) ## error ("lyapchol: a must be real and square"); error ("lyapchol: %s must be real and square", \ - inputname(1)); + inputname (1)); endif if (! is_real_matrix (b)) ## error ("lyapchol: b must be real") error ("lyapchol: %s must be real", \ - inputname(2)) + inputname (2)) endif if (rows (a) != rows (b)) ## error ("lyapchol: a and b must have the same number of rows"); error ("lyapchol: %s and %s must have the same number of rows", \ - inputname(1), inputname(2)); + inputname (1), inputname (2)); endif [u, scale] = slsb03od (a.', b.', false); @@ -70,19 +70,19 @@ if (! is_real_square_matrix (a, e)) ## error ("lyapchol: a, e must be real and square"); error ("lyapchol: %s, %s must be real and square", \ - inputname(1), inputname(3)); + inputname (1), inputname (3)); endif if (! is_real_matrix (b)) ## error ("lyapchol: b must be real"); error ("lyapchol: %s must be real", \ - inputname(2)); + inputname (2)); endif if (rows (b) != rows (a) || rows (e) != rows (a)) ## error ("lyapchol: a, b, e must have the same number of rows"); error ("lyapchol: %s, %s, %s must have the same number of rows", \ - inputname(1), inputname(2), inputname(3)); + inputname (1), inputname (2), inputname (3)); endif [u, scale] = slsg03bd (a.', e.', b.', false); Modified: trunk/octave-forge/main/control/inst/step.m =================================================================== --- trunk/octave-forge/main/control/inst/step.m 2010-12-23 15:27:50 UTC (rev 8038) +++ trunk/octave-forge/main/control/inst/step.m 2010-12-24 13:45:18 UTC (rev 8039) @@ -64,7 +64,7 @@ print_usage (); endif - [y, t, x] = __time_response__ (sys, "step", ! nargout, tfinal, dt, [], inputname(1)); + [y, t, x] = __time_response__ (sys, "step", ! nargout, tfinal, dt, [], inputname (1)); if (nargout) y_r = y; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2011-01-01 11:48:00
|
Revision: 8044 http://octave.svn.sourceforge.net/octave/?rev=8044&view=rev Author: paramaniac Date: 2011-01-01 11:47:54 +0000 (Sat, 01 Jan 2011) Log Message: ----------- control: add check for minimum-phase systems Modified Paths: -------------- trunk/octave-forge/main/control/INDEX Added Paths: ----------- trunk/octave-forge/main/control/inst/@lti/isminimumphase.m Modified: trunk/octave-forge/main/control/INDEX =================================================================== --- trunk/octave-forge/main/control/INDEX 2010-12-28 02:13:58 UTC (rev 8043) +++ trunk/octave-forge/main/control/INDEX 2011-01-01 11:47:54 UTC (rev 8044) @@ -35,6 +35,7 @@ isctrb isdetectable @lti/isdt + @lti/isminimumphase isobsv @lti/issiso isstabilizable Added: trunk/octave-forge/main/control/inst/@lti/isminimumphase.m =================================================================== --- trunk/octave-forge/main/control/inst/@lti/isminimumphase.m (rev 0) +++ trunk/octave-forge/main/control/inst/@lti/isminimumphase.m 2011-01-01 11:47:54 UTC (rev 8044) @@ -0,0 +1,40 @@ +## Copyright (C) 2011 Lukas F. Reichlin +## +## This file is part of LTI Syncope. +## +## LTI Syncope is free software: you can redistribute it and/or modify +## it under the terms of the GNU General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## LTI Syncope is distributed in the hope that it will be useful, +## but WITHOUT ANY WARRANTY; without even the implied warranty of +## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +## GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with LTI Syncope. If not, see <http://www.gnu.org/licenses/>. + +## -*- texinfo -*- +## @deftypefn {Function File} {@var{bool} =} isminimumphase (@var{sys}) +## @deftypefnx {Function File} {@var{bool} =} isminimumphase (@var{sys}, @var{tol}) +## Determine whether LTI system is minimum phase. +## If a square system @var{P} is minimum-phase, its inverse @var{P^-1} is stable. +## @end deftypefn + +## Author: Lukas Reichlin <luk...@gm...> +## Created: January 2011 +## Version: 0.1 + +function bool = isminimumphase (sys, tol = 0) + + if (nargin > 2) + print_usage (); + endif + + z = zero (sys); + ct = isct (sys); + + bool = __is_stable__ (z, ct, tol); + +endfunction \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <par...@us...> - 2011-01-23 22:52:35
|
Revision: 8065 http://octave.svn.sourceforge.net/octave/?rev=8065&view=rev Author: paramaniac Date: 2011-01-23 22:52:28 +0000 (Sun, 23 Jan 2011) Log Message: ----------- control: minor cosmetic changes Modified Paths: -------------- trunk/octave-forge/main/control/doc/references.txt trunk/octave-forge/main/control/inst/Boeing707.m trunk/octave-forge/main/control/inst/optiPID.m trunk/octave-forge/main/control/inst/optiPIDfun.m Modified: trunk/octave-forge/main/control/doc/references.txt =================================================================== --- trunk/octave-forge/main/control/doc/references.txt 2011-01-21 23:05:47 UTC (rev 8064) +++ trunk/octave-forge/main/control/doc/references.txt 2011-01-23 22:52:28 UTC (rev 8065) @@ -4,55 +4,53 @@ German ****** +Geering, H.P. +Regelungstechnik +Springer +2004 + Meyer, M. Signalverarbeitung Vieweg & Teubner 2009 -Geering, H.P. -Regelungstechnik -Springer -2004 - English ******* -Guzzella, L. -Analysis and Design of SISO Control Systems -VDF Hochschulverlag ETH Zurich -2007 - -Kailath, T. -Linear Systems -Prentice Hall -1980 - Anderson, B.D.O. and Moore, J.B. Optimal Control Linear Quadratic Methods Dover Publications 1990 -Skogestad, S. and Postlethwaite, I. -Multivariable Feedback Control -Analysis and Design +Astr\x9Am, K. and H\x8Agglund, T. +PID Controllers +Theory, Design and Tuning Second Edition -Wiley -2005 +Instrument Society of America +1995 Doyle, J.C., Francis, B.A. and Tannenbaum, A.R. Feedback Control Theory Dover Publications 1992 -Astr\x9Am, K. and H\x8Agglund, T. -PID Controllers -Theory, Design and Tuning -Second Edition -Instrument Society of America -1995 +Geering, H.P. +Optimal Control with Engineering Applications +Springer +2007 +Guzzella, L. +Analysis and Design of SISO Control Systems +VDF Hochschulverlag ETH Zurich +2007 + +Kailath, T. +Linear Systems +Prentice Hall +1980 + Leigh, J.R. Applied Digital Control Theory, Design and Implementation @@ -60,14 +58,16 @@ Dover Publications 1992 -Geering, H.P. -Optimal Control with Engineering Applications -Springer -2007 - Ljung, L. System Identification Theory for the User Second Edition Prentice Hall 1999 + +Skogestad, S. and Postlethwaite, I. +Multivariable Feedback Control +Analysis and Design +Second Edition +Wiley +2005 Modified: trunk/octave-forge/main/control/inst/Boeing707.m =================================================================== --- trunk/octave-forge/main/control/inst/Boeing707.m 2011-01-21 23:05:47 UTC (rev 8064) +++ trunk/octave-forge/main/control/inst/Boeing707.m 2011-01-23 22:52:28 UTC (rev 8065) @@ -62,8 +62,8 @@ inam = {"thrust"; "rudder"}; onam = {"speed"; "pitch"}; - snam = {"x1"; "x2"; "x3"; "x4"}; + ## snam = {"x1"; "x2"; "x3"; "x4"}; - outsys = ss (a, b, c, d, "stname", snam, "inname", inam, "outname", onam); + outsys = ss (a, b, c, d, "inname", inam, "outname", onam); endfunction Modified: trunk/octave-forge/main/control/inst/optiPID.m =================================================================== --- trunk/octave-forge/main/control/inst/optiPID.m 2011-01-21 23:05:47 UTC (rev 8064) +++ trunk/octave-forge/main/control/inst/optiPID.m 2011-01-23 22:52:28 UTC (rev 8065) @@ -2,7 +2,7 @@ % optiPID Lukas Reichlin July 2009 % =============================================================================== % Numerical Optimization of an A/H PID Controller -% Required OCTAVE Packages: control, miscellaneous, optim +% Required OCTAVE Packages: control, optim (and its dependencies) % Required MATLAB Toolboxes: Control, Optimization % =============================================================================== @@ -18,9 +18,9 @@ P = tf (numP, denP); % Relative Weighting Factors: PLAY AROUND WITH THESE! -mu_1 = 1; % Minimize ITAE Criterion -mu_2 = 10; % Minimize Max Overshoot -mu_3 = 20; % Minimize Sensitivity Ms +mu_1 = 1; % Minimize ITAE Criterion +mu_2 = 10; % Minimize Max Overshoot +mu_3 = 20; % Minimize Sensitivity Ms % Simulation Settings: PLANT-DEPENDENT! t_sim = 30; % Simulation Time [s] Modified: trunk/octave-forge/main/control/inst/optiPIDfun.m =================================================================== --- trunk/octave-forge/main/control/inst/optiPIDfun.m 2011-01-21 23:05:47 UTC (rev 8064) +++ trunk/octave-forge/main/control/inst/optiPIDfun.m 2011-01-23 22:52:28 UTC (rev 8065) @@ -2,8 +2,8 @@ % optiPIDfun Lukas Reichlin July 2009 % =============================================================================== % Objective Function -% See "Analysis and Synthesis of SISO Control Systems" -% by Lino Guzzella for further details +% Reference: Guzzella, L. (2007) Analysis and Synthesis of SISO Control Systems. +% vdf, Zurich % =============================================================================== function J = optiPIDfun (C_par) @@ -18,8 +18,8 @@ tau = Td / 10; % PID Controller with Roll-Off - numC = kp * [Ti * Td, Ti, 1]; - denC = conv ([Ti, 0], [tau^2, 2 * tau, 1]); + numC = kp * [Ti*Td, Ti, 1]; + denC = conv ([Ti, 0], [tau^2, 2*tau, 1]); C = tf (numC, denC); % Open Loop @@ -32,11 +32,11 @@ SUML = append (SUM, L); % Build System Interconnections - CM = [3, 1; % Controller Input with Sum Block Output - 2, 2]; % Sum Block Negative Input with Plant Output + CM = [3, 1; % Controller Input with Sum Block Output + 2, 2]; % Sum Block Negative Input with Plant Output - inputs = [1]; % Input 1: reference r(t) - outputs = [1, 2]; % Output 1: error e(t), Output 2: output y(t) + inputs = [1]; % Input 1: reference r(t) + outputs = [1, 2]; % Output 1: error e(t), Output 2: output y(t) SUML = connect (SUML, CM, inputs, outputs); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |