• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

python-control / python-control / 12266904606

11 Dec 2024 12:03AM UTC coverage: 94.73% (+0.009%) from 94.721%
12266904606

Pull #1078

github

web-flow
Merge 0b9be7a84 into e2c0ff85f
Pull Request #1078: fix issue with multiplying MIMO LTI system by scalar

9330 of 9849 relevant lines covered (94.73%)

8.27 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

95.41
control/statefbk.py
1
# statefbk.py - tools for state feedback control
2
#
3
# Author: Richard M. Murray, Roberto Bucher
4
# Date: 31 May 2010
5
#
6
# This file contains routines for designing state space controllers
7
#
8
# Copyright (c) 2010 by California Institute of Technology
9
# All rights reserved.
10
#
11
# Redistribution and use in source and binary forms, with or without
12
# modification, are permitted provided that the following conditions
13
# are met:
14
#
15
# 1. Redistributions of source code must retain the above copyright
16
#    notice, this list of conditions and the following disclaimer.
17
#
18
# 2. Redistributions in binary form must reproduce the above copyright
19
#    notice, this list of conditions and the following disclaimer in the
20
#    documentation and/or other materials provided with the distribution.
21
#
22
# 3. Neither the name of the California Institute of Technology nor
23
#    the names of its contributors may be used to endorse or promote
24
#    products derived from this software without specific prior
25
#    written permission.
26
#
27
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
28
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
29
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
30
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED.  IN NO EVENT SHALL CALTECH
31
# OR THE CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
32
# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
33
# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
34
# USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
35
# ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
36
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
37
# OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
38
# SUCH DAMAGE.
39
#
40
# $Id$
41

42
import warnings
9✔
43

44
import numpy as np
9✔
45
import scipy as sp
9✔
46

47
from . import statesp
9✔
48
from .config import _process_legacy_keyword
9✔
49
from .exception import ControlArgument, ControlDimension, \
9✔
50
    ControlNotImplemented, ControlSlycot
51
from .iosys import _process_indices, _process_labels, isctime, isdtime
9✔
52
from .lti import LTI
9✔
53
from .mateqn import _check_shape, care, dare
9✔
54
from .nlsys import NonlinearIOSystem, interconnect
9✔
55
from .statesp import StateSpace, _convert_to_statespace, _ssmatrix, ss
9✔
56

57
# Make sure we have access to the right slycot routines
58
try:
9✔
59
    from slycot import sb03md57
9✔
60

61
    # wrap without the deprecation warning
62
    def sb03md(n, C, A, U, dico, job='X',fact='N',trana='N',ldwork=None):
5✔
63
        ret = sb03md57(A, U, C, dico, job, fact, trana, ldwork)
5✔
64
        return ret[2:]
5✔
65
except ImportError:
4✔
66
    try:
4✔
67
        from slycot import sb03md
4✔
68
    except ImportError:
4✔
69
        sb03md = None
4✔
70

71
try:
9✔
72
    from slycot import sb03od
9✔
73
except ImportError:
4✔
74
    sb03od = None
4✔
75

76

77
__all__ = ['ctrb', 'obsv', 'gram', 'place', 'place_varga', 'lqr',
9✔
78
           'dlqr', 'acker', 'create_statefbk_iosystem']
79

80

81
# Pole placement
82
def place(A, B, p):
9✔
83
    """Place closed loop eigenvalues.
84

85
    K = place(A, B, p)
86

87
    Parameters
88
    ----------
89
    A : 2D array_like
90
        Dynamics matrix
91
    B : 2D array_like
92
        Input matrix
93
    p : 1D array_like
94
        Desired eigenvalue locations
95

96
    Returns
97
    -------
98
    K : 2D array (or matrix)
99
        Gain such that A - B K has eigenvalues given in p
100

101
    Notes
102
    -----
103
    Algorithm
104
        This is a wrapper function for :func:`scipy.signal.place_poles`, which
105
        implements the Tits and Yang algorithm [1]_. It will handle SISO,
106
        MISO, and MIMO systems. If you want more control over the algorithm,
107
        use :func:`scipy.signal.place_poles` directly.
108

109
    Limitations
110
        The algorithm will not place poles at the same location more
111
        than rank(B) times.
112

113
    References
114
    ----------
115
    .. [1] A.L. Tits and Y. Yang, "Globally convergent algorithms for robust
116
       pole assignment by state feedback, IEEE Transactions on Automatic
117
       Control, Vol. 41, pp. 1432-1452, 1996.
118

119
    Examples
120
    --------
121
    >>> A = [[-1, -1], [0, 1]]
122
    >>> B = [[0], [1]]
123
    >>> K = ct.place(A, B, [-2, -5])
124

125
    See Also
126
    --------
127
    place_varga, acker
128

129
    """
130
    from scipy.signal import place_poles
9✔
131

132
    # Convert the system inputs to NumPy arrays
133
    A_mat = np.array(A)
9✔
134
    B_mat = np.array(B)
9✔
135
    if (A_mat.shape[0] != A_mat.shape[1]):
9✔
136
        raise ControlDimension("A must be a square matrix")
9✔
137

138
    if (A_mat.shape[0] != B_mat.shape[0]):
9✔
139
        err_str = "The number of rows of A must equal the number of rows in B"
9✔
140
        raise ControlDimension(err_str)
9✔
141

142
    # Convert desired poles to numpy array
143
    placed_eigs = np.atleast_1d(np.squeeze(np.asarray(p)))
9✔
144

145
    result = place_poles(A_mat, B_mat, placed_eigs, method='YT')
9✔
146
    K = result.gain_matrix
9✔
147
    return _ssmatrix(K)
9✔
148

149

150
def place_varga(A, B, p, dtime=False, alpha=None):
9✔
151
    """Place closed loop eigenvalues.
152
    K = place_varga(A, B, p, dtime=False, alpha=None)
153

154
    Parameters
155
    ----------
156
    A : 2D array_like
157
        Dynamics matrix
158
    B : 2D array_like
159
        Input matrix
160
    p : 1D array_like
161
        Desired eigenvalue locations
162
    dtime : bool, optional
163
        False for continuous time pole placement or True for discrete time.
164
        The default is dtime=False.
165
    alpha : float, optional
166
        If `dtime` is false then place_varga will leave the eigenvalues with
167
        real part less than alpha untouched.  If `dtime` is true then
168
        place_varga will leave eigenvalues with modulus less than alpha
169
        untouched.
170

171
        By default (alpha=None), place_varga computes alpha such that all
172
        poles will be placed.
173

174
    Returns
175
    -------
176
    K : 2D array (or matrix)
177
        Gain such that A - B K has eigenvalues given in p.
178

179
    See Also
180
    --------
181
    place, acker
182

183
    Notes
184
    -----
185
    This function is a wrapper for the slycot function sb01bd, which
186
    implements the pole placement algorithm of Varga [1]_. In contrast to the
187
    algorithm used by place(), the Varga algorithm can place multiple poles at
188
    the same location. The placement, however, may not be as robust.
189

190
    References
191
    ----------
192
    .. [1] Varga A. "A Schur method for pole assignment."  IEEE Trans. Automatic
193
       Control, Vol. AC-26, pp. 517-519, 1981.
194

195
    Examples
196
    --------
197
    >>> A = [[-1, -1], [0, 1]]
198
    >>> B = [[0], [1]]
199
    >>> K = ct.place_varga(A, B, [-2, -5])
200
    """
201

202
    # Make sure that SLICOT is installed
203
    try:
5✔
204
        from slycot import sb01bd
5✔
205
    except ImportError:
×
206
        raise ControlSlycot("can't find slycot module 'sb01bd'")
×
207

208
    # Convert the system inputs to NumPy arrays
209
    A_mat = np.array(A)
5✔
210
    B_mat = np.array(B)
5✔
211
    if (A_mat.shape[0] != A_mat.shape[1] or A_mat.shape[0] != B_mat.shape[0]):
5✔
212
        raise ControlDimension("matrix dimensions are incorrect")
×
213

214
    # Compute the system eigenvalues and convert poles to numpy array
215
    system_eigs = np.linalg.eig(A_mat)[0]
5✔
216
    placed_eigs = np.atleast_1d(np.squeeze(np.asarray(p)))
5✔
217

218
    # Need a character parameter for SB01BD
219
    if dtime:
5✔
220
        DICO = 'D'
5✔
221
    else:
222
        DICO = 'C'
5✔
223

224
    if alpha is None:
5✔
225
        # SB01BD ignores eigenvalues with real part less than alpha
226
        # (if DICO='C') or with modulus less than alpha
227
        # (if DICO = 'D').
228
        if dtime:
5✔
229
            # For discrete time, slycot only cares about modulus, so just make
230
            # alpha the smallest it can be.
231
            alpha = 0.0
5✔
232
        else:
233
            # Choosing alpha=min_eig is insufficient and can lead to an
234
            # error or not having all the eigenvalues placed that we wanted.
235
            # Evidently, what python thinks are the eigs is not precisely
236
            # the same as what slicot thinks are the eigs. So we need some
237
            # numerical breathing room. The following is pretty heuristic,
238
            # but does the trick
239
            alpha = -2*abs(min(system_eigs.real))
5✔
240
    elif dtime and alpha < 0.0:
5✔
241
        raise ValueError("Discrete time systems require alpha > 0")
×
242

243
    # Call SLICOT routine to place the eigenvalues
244
    A_z, w, nfp, nap, nup, F, Z = \
5✔
245
        sb01bd(B_mat.shape[0], B_mat.shape[1], len(placed_eigs), alpha,
246
               A_mat, B_mat, placed_eigs, DICO)
247

248
    # Return the gain matrix, with MATLAB gain convention
249
    return _ssmatrix(-F)
5✔
250

251

252
# Contributed by Roberto Bucher <roberto.bucher@supsi.ch>
253
def acker(A, B, poles):
9✔
254
    """Pole placement using Ackermann method.
255

256
    Call:
257
    K = acker(A, B, poles)
258

259
    Parameters
260
    ----------
261
    A, B : 2D array_like
262
        State and input matrix of the system
263
    poles : 1D array_like
264
        Desired eigenvalue locations
265

266
    Returns
267
    -------
268
    K : 2D array (or matrix)
269
        Gains such that A - B K has given eigenvalues
270
    
271
    See Also
272
    --------
273
    place, place_varga
274

275
    """
276
    # Convert the inputs to matrices
277
    a = _ssmatrix(A)
9✔
278
    b = _ssmatrix(B)
9✔
279

280
    # Make sure the system is controllable
281
    ct = ctrb(A, B)
9✔
282
    if np.linalg.matrix_rank(ct) != a.shape[0]:
9✔
283
        raise ValueError("System not reachable; pole placement invalid")
×
284

285
    # Compute the desired characteristic polynomial
286
    p = np.real(np.poly(poles))
9✔
287

288
    # Place the poles using Ackermann's method
289
    # TODO: compute pmat using Horner's method (O(n) instead of O(n^2))
290
    n = np.size(p)
9✔
291
    pmat = p[n-1] * np.linalg.matrix_power(a, 0)
9✔
292
    for i in np.arange(1, n):
9✔
293
        pmat = pmat + p[n-i-1] * np.linalg.matrix_power(a, i)
9✔
294
    K = np.linalg.solve(ct, pmat)
9✔
295

296
    K = K[-1][:]                # Extract the last row
9✔
297
    return _ssmatrix(K)
9✔
298

299

300
def lqr(*args, **kwargs):
9✔
301
    r"""lqr(A, B, Q, R[, N])
302

303
    Linear quadratic regulator design.
304

305
    The lqr() function computes the optimal state feedback controller
306
    u = -K x that minimizes the quadratic cost
307

308
    .. math:: J = \int_0^\infty (x' Q x + u' R u + 2 x' N u) dt
309

310
    The function can be called with either 3, 4, or 5 arguments:
311

312
    * ``K, S, E = lqr(sys, Q, R)``
313
    * ``K, S, E = lqr(sys, Q, R, N)``
314
    * ``K, S, E = lqr(A, B, Q, R)``
315
    * ``K, S, E = lqr(A, B, Q, R, N)``
316

317
    where `sys` is an `LTI` object, and `A`, `B`, `Q`, `R`, and `N` are
318
    2D arrays or matrices of appropriate dimension.
319

320
    Parameters
321
    ----------
322
    A, B : 2D array_like
323
        Dynamics and input matrices
324
    sys : LTI StateSpace system
325
        Linear system
326
    Q, R : 2D array
327
        State and input weight matrices
328
    N : 2D array, optional
329
        Cross weight matrix
330
    integral_action : ndarray, optional
331
        If this keyword is specified, the controller includes integral
332
        action in addition to state feedback.  The value of the
333
        `integral_action` keyword should be an ndarray that will be
334
        multiplied by the current state to generate the error for the
335
        internal integrator states of the control law.  The number of
336
        outputs that are to be integrated must match the number of
337
        additional rows and columns in the `Q` matrix.
338
    method : str, optional
339
        Set the method used for computing the result.  Current methods are
340
        'slycot' and 'scipy'.  If set to None (default), try 'slycot' first
341
        and then 'scipy'.
342

343
    Returns
344
    -------
345
    K : 2D array (or matrix)
346
        State feedback gains
347
    S : 2D array (or matrix)
348
        Solution to Riccati equation
349
    E : 1D array
350
        Eigenvalues of the closed loop system
351

352
    See Also
353
    --------
354
    lqe, dlqr, dlqe
355

356
    Notes
357
    -----
358
    If the first argument is an LTI object, then this object will be used
359
    to define the dynamics and input matrices.  Furthermore, if the LTI
360
    object corresponds to a discrete time system, the ``dlqr()`` function
361
    will be called.
362

363
    Examples
364
    --------
365
    >>> K, S, E = lqr(sys, Q, R, [N])                           # doctest: +SKIP
366
    >>> K, S, E = lqr(A, B, Q, R, [N])                          # doctest: +SKIP
367

368
    """
369
    #
370
    # Process the arguments and figure out what inputs we received
371
    #
372

373
    # If we were passed a discrete time system as the first arg, use dlqr()
374
    if isinstance(args[0], LTI) and isdtime(args[0], strict=True):
9✔
375
        # Call dlqr
376
        return dlqr(*args, **kwargs)
9✔
377

378
    # Get the system description
379
    if (len(args) < 3):
9✔
380
        raise ControlArgument("not enough input arguments")
9✔
381

382
    # If we were passed a state space  system, use that to get system matrices
383
    if isinstance(args[0], StateSpace):
9✔
384
        A = np.array(args[0].A, ndmin=2, dtype=float)
9✔
385
        B = np.array(args[0].B, ndmin=2, dtype=float)
9✔
386
        index = 1
9✔
387

388
    elif isinstance(args[0], LTI):
9✔
389
        # Don't allow other types of LTI systems
390
        raise ControlArgument("LTI system must be in state space form")
9✔
391

392
    else:
393
        # Arguments should be A and B matrices
394
        A = np.array(args[0], ndmin=2, dtype=float)
9✔
395
        B = np.array(args[1], ndmin=2, dtype=float)
9✔
396
        index = 2
9✔
397

398
    # Get the weighting matrices (converting to matrices, if needed)
399
    Q = np.array(args[index], ndmin=2, dtype=float)
9✔
400
    R = np.array(args[index+1], ndmin=2, dtype=float)
9✔
401
    if (len(args) > index + 2):
9✔
402
        N = np.array(args[index+2], ndmin=2, dtype=float)
9✔
403
    else:
404
        N = None
9✔
405

406
    #
407
    # Process keywords
408
    #
409

410
    # Get the method to use (if specified as a keyword)
411
    method = kwargs.pop('method', None)
9✔
412

413
    # See if we should augment the controller with integral feedback
414
    integral_action = kwargs.pop('integral_action', None)
9✔
415
    if integral_action is not None:
9✔
416
        # Figure out the size of the system
417
        nstates = A.shape[0]
9✔
418
        ninputs = B.shape[1]
9✔
419

420
        # Make sure that the integral action argument is the right type
421
        if not isinstance(integral_action, np.ndarray):
9✔
422
            raise ControlArgument("Integral action must pass an array")
9✔
423
        elif integral_action.shape[1] != nstates:
9✔
424
            raise ControlArgument(
9✔
425
                "Integral gain size must match system state size")
426

427
        # Process the states to be integrated
428
        nintegrators = integral_action.shape[0]
9✔
429
        C = integral_action
9✔
430

431
        # Augment the system with integrators
432
        A = np.block([
9✔
433
            [A, np.zeros((nstates, nintegrators))],
434
            [C, np.zeros((nintegrators, nintegrators))]
435
        ])
436
        B = np.vstack([B, np.zeros((nintegrators, ninputs))])
9✔
437

438
    if kwargs:
9✔
439
        raise TypeError("unrecognized keywords: ", str(kwargs))
9✔
440

441
    # Compute the result (dimension and symmetry checking done in care())
442
    X, L, G = care(A, B, Q, R, N, None, method=method, _Ss="N")
9✔
443
    return G, X, L
9✔
444

445

446
def dlqr(*args, **kwargs):
9✔
447
    r"""dlqr(A, B, Q, R[, N])
448

449
    Discrete-time linear quadratic regulator design.
450

451
    The dlqr() function computes the optimal state feedback controller
452
    u[n] = - K x[n] that minimizes the quadratic cost
453

454
    .. math:: J = \sum_0^\infty (x[n]' Q x[n] + u[n]' R u[n] + 2 x[n]' N u[n])
455

456
    The function can be called with either 3, 4, or 5 arguments:
457

458
    * ``dlqr(dsys, Q, R)``
459
    * ``dlqr(dsys, Q, R, N)``
460
    * ``dlqr(A, B, Q, R)``
461
    * ``dlqr(A, B, Q, R, N)``
462

463
    where `dsys` is a discrete-time :class:`StateSpace` system, and `A`, `B`,
464
    `Q`, `R`, and `N` are 2d arrays of appropriate dimension (`dsys.dt` must
465
    not be 0.)
466

467
    Parameters
468
    ----------
469
    A, B : 2D array
470
        Dynamics and input matrices
471
    dsys : LTI :class:`StateSpace`
472
        Discrete-time linear system
473
    Q, R : 2D array
474
        State and input weight matrices
475
    N : 2D array, optional
476
        Cross weight matrix
477
    integral_action : ndarray, optional
478
        If this keyword is specified, the controller includes integral
479
        action in addition to state feedback.  The value of the
480
        `integral_action` keyword should be an ndarray that will be
481
        multiplied by the current state to generate the error for the
482
        internal integrator states of the control law.  The number of
483
        outputs that are to be integrated must match the number of
484
        additional rows and columns in the `Q` matrix.
485
    method : str, optional
486
        Set the method used for computing the result.  Current methods are
487
        'slycot' and 'scipy'.  If set to None (default), try 'slycot' first
488
        and then 'scipy'.
489

490
    Returns
491
    -------
492
    K : 2D array (or matrix)
493
        State feedback gains
494
    S : 2D array (or matrix)
495
        Solution to Riccati equation
496
    E : 1D array
497
        Eigenvalues of the closed loop system
498

499
    See Also
500
    --------
501
    lqr, lqe, dlqe
502

503
    Examples
504
    --------
505
    >>> K, S, E = dlqr(dsys, Q, R, [N])                         # doctest: +SKIP
506
    >>> K, S, E = dlqr(A, B, Q, R, [N])                         # doctest: +SKIP
507
    """
508

509
    #
510
    # Process the arguments and figure out what inputs we received
511
    #
512

513
    # Get the system description
514
    if (len(args) < 3):
9✔
515
        raise ControlArgument("not enough input arguments")
9✔
516

517
    # If we were passed a continus time system as the first arg, raise error
518
    if isinstance(args[0], LTI) and isctime(args[0], strict=True):
9✔
519
        raise ControlArgument("dsys must be discrete time (dt != 0)")
9✔
520

521
    # If we were passed a state space  system, use that to get system matrices
522
    if isinstance(args[0], StateSpace):
9✔
523
        A = np.array(args[0].A, ndmin=2, dtype=float)
9✔
524
        B = np.array(args[0].B, ndmin=2, dtype=float)
9✔
525
        index = 1
9✔
526

527
    elif isinstance(args[0], LTI):
9✔
528
        # Don't allow other types of LTI systems
529
        raise ControlArgument("LTI system must be in state space form")
9✔
530

531
    else:
532
        # Arguments should be A and B matrices
533
        A = np.array(args[0], ndmin=2, dtype=float)
9✔
534
        B = np.array(args[1], ndmin=2, dtype=float)
9✔
535
        index = 2
9✔
536

537
    # Get the weighting matrices (converting to matrices, if needed)
538
    Q = np.array(args[index], ndmin=2, dtype=float)
9✔
539
    R = np.array(args[index+1], ndmin=2, dtype=float)
9✔
540
    if (len(args) > index + 2):
9✔
541
        N = np.array(args[index+2], ndmin=2, dtype=float)
9✔
542
    else:
543
        N = np.zeros((Q.shape[0], R.shape[1]))
9✔
544

545
    #
546
    # Process keywords
547
    #
548

549
    # Get the method to use (if specified as a keyword)
550
    method = kwargs.pop('method', None)
9✔
551

552
    # See if we should augment the controller with integral feedback
553
    integral_action = kwargs.pop('integral_action', None)
9✔
554
    if integral_action is not None:
9✔
555
        # Figure out the size of the system
556
        nstates = A.shape[0]
9✔
557
        ninputs = B.shape[1]
9✔
558

559
        if not isinstance(integral_action, np.ndarray):
9✔
560
            raise ControlArgument("Integral action must pass an array")
9✔
561
        elif integral_action.shape[1] != nstates:
9✔
562
            raise ControlArgument(
9✔
563
                "Integral gain size must match system state size")
564
        else:
565
            nintegrators = integral_action.shape[0]
9✔
566
            C = integral_action
9✔
567

568
            # Augment the system with integrators
569
            A = np.block([
9✔
570
                [A, np.zeros((nstates, nintegrators))],
571
                [C, np.eye(nintegrators)]
572
            ])
573
            B = np.vstack([B, np.zeros((nintegrators, ninputs))])
9✔
574

575
    if kwargs:
9✔
576
        raise TypeError("unrecognized keywords: ", str(kwargs))
9✔
577

578
    # Compute the result (dimension and symmetry checking done in dare())
579
    S, E, K = dare(A, B, Q, R, N, method=method, _Ss="N")
9✔
580
    return _ssmatrix(K), _ssmatrix(S), E
9✔
581

582

583
# Function to create an I/O sytems representing a state feedback controller
584
def create_statefbk_iosystem(
9✔
585
        sys, gain, feedfwd_gain=None, integral_action=None, estimator=None,
586
        controller_type=None, xd_labels=None, ud_labels=None, ref_labels=None,
587
        feedfwd_pattern='trajgen', gainsched_indices=None,
588
        gainsched_method='linear', control_indices=None, state_indices=None,
589
        name=None, inputs=None, outputs=None, states=None, **kwargs):
590
    r"""Create an I/O system using a (full) state feedback controller.
591

592
    This function creates an input/output system that implements a
593
    state feedback controller of the form
594

595
    .. math:: u = u_d - K_p (x - x_d) - K_i \int(C x - C x_d)
596

597
    by calling
598

599
        ctrl, clsys = ct.create_statefbk_iosystem(sys, K)
600

601
    where `sys` is the process dynamics and `K` is the state (+ integral)
602
    feedback gain (eg, from LQR).  The function returns the controller
603
    `ctrl` and the closed loop systems `clsys`, both as I/O systems.
604

605
    A gain scheduled controller can also be created, by passing a list of
606
    gains and a corresponding list of values of a set of scheduling
607
    variables.  In this case, the controller has the form
608

609
    .. math:: u = u_d - K_p(\mu) (x - x_d) - K_i(\mu) \int(C x - C x_d)
610

611
    where :math:`\mu` represents the scheduling variable.
612

613
    Alternatively, a controller of the form
614

615
    .. math:: u = k_f r - K_p x - K_i \int(C x - r)
616

617
    can be created by calling
618

619
        ctrl, clsys = ct.create_statefbk_iosystem(
620
            sys, K, kf, feedfwd_pattern='refgain')
621

622
    In either form, an estimator can also be used to compute the estimated
623
    state from the input and output measurements.
624

625
    Parameters
626
    ----------
627
    sys : NonlinearIOSystem
628
        The I/O system that represents the process dynamics.  If no estimator
629
        is given, the output of this system should represent the full state.
630

631
    gain : ndarray, tuple, or I/O system
632
        If an array is given, it represents the state feedback gain (`K`).
633
        This matrix defines the gains to be applied to the system.  If
634
        `integral_action` is None, then the dimensions of this array
635
        should be (sys.ninputs, sys.nstates).  If `integral action` is
636
        set to a matrix or a function, then additional columns
637
        represent the gains of the integral states of the controller.
638

639
        If a tuple is given, then it specifies a gain schedule.  The tuple
640
        should be of the form `(gains, points)` where gains is a list of
641
        gains `K_j` and points is a list of values `mu_j` at which the
642
        gains are computed.  The `gainsched_indices` parameter should be
643
        used to specify the scheduling variables.
644

645
        If an I/O system is given, the error e = x - xd is passed to the
646
        system and the output is used as the feedback compensation term.
647

648
    feedfwd_gain : array_like, optional
649
        Specify the feedforward gain, `k_f`.  Used only for the reference
650
        gain design pattern.  If not given and if `sys` is a `StateSpace`
651
        (linear) system, will be computed as -1/(C (A-BK)^{-1}) B.
652

653
    feedfwd_pattern : str, optional
654
        If set to 'refgain', the reference gain design pattern is used to
655
        create the controller instead of the trajectory generation
656
        ('trajgen') pattern.
657

658
    integral_action : ndarray, optional
659
        If this keyword is specified, the controller can include integral
660
        action in addition to state feedback.  The value of the
661
        `integral_action` keyword should be an ndarray that will be
662
        multiplied by the current and desired state to generate the error
663
        for the internal integrator states of the control law.
664

665
    estimator : NonlinearIOSystem, optional
666
        If an estimator is provided, use the states of the estimator as
667
        the system inputs for the controller.
668

669
    gainsched_indices : int, slice, or list of int or str, optional
670
        If a gain scheduled controller is specified, specify the indices of
671
        the controller input to use for scheduling the gain. The input to
672
        the controller is the desired state `x_d`, the desired input `u_d`,
673
        and the system state `x` (or state estimate `xhat`, if an
674
        estimator is given). If value is an integer `q`, the first `q`
675
        values of the `[x_d, u_d, x]` vector are used.  Otherwise, the
676
        value should be a slice or a list of indices.  The list of indices
677
        can be specified as either integer offsets or as signal names. The
678
        default is to use the desired state `x_d`.
679

680
    gainsched_method : str, optional
681
        The method to use for gain scheduling.  Possible values are 'linear'
682
        (default), 'nearest', and 'cubic'.  More information is available in
683
        :func:`scipy.interpolate.griddata`. For points outside of the convex
684
        hull of the scheduling points, the gain at the nearest point is
685
        used.
686

687
    controller_type : 'linear' or 'nonlinear', optional
688
        Set the type of controller to create. The default for a linear gain
689
        is a linear controller implementing the LQR regulator. If the type
690
        is 'nonlinear', a :class:NonlinearIOSystem is created instead, with
691
        the gain `K` as a parameter (allowing modifications of the gain at
692
        runtime). If the gain parameter is a tuple, then a nonlinear,
693
        gain-scheduled controller is created.
694

695
    Returns
696
    -------
697
    ctrl : NonlinearIOSystem
698
        Input/output system representing the controller.  For the 'trajgen'
699
        design pattern (default), this system takes as inputs the desired
700
        state `x_d`, the desired input `u_d`, and either the system state
701
        `x` or the estimated state `xhat`.  It outputs the controller
702
        action `u` according to the formula `u = u_d - K(x - x_d)`.  For
703
        the 'refgain' design pattern, the system takes as inputs the
704
        reference input `r` and the system or estimated state. If the
705
        keyword `integral_action` is specified, then an additional set of
706
        integrators is included in the control system (with the gain matrix
707
        `K` having the integral gains appended after the state gains).  If
708
        a gain scheduled controller is specified, the gain (proportional
709
        and integral) are evaluated using the scheduling variables
710
        specified by `gainsched_indices`.
711

712
    clsys : NonlinearIOSystem
713
        Input/output system representing the closed loop system.  This
714
        system takes as inputs the desired trajectory `(x_d, u_d)` and
715
        outputs the system state `x` and the applied input `u`
716
        (vertically stacked).
717

718
    Other Parameters
719
    ----------------
720
    control_indices : int, slice, or list of int or str, optional
721
        Specify the indices of the system inputs that should be determined
722
        by the state feedback controller.  If value is an integer `m`, the
723
        first `m` system inputs are used.  Otherwise, the value should be a
724
        slice or a list of indices.  The list of indices can be specified
725
        as either integer offsets or as system input signal names.  If not
726
        specified, defaults to the system inputs.
727

728
    state_indices : int, slice, or list of int or str, optional
729
        Specify the indices of the system (or estimator) outputs that should
730
        be used by the state feedback controller.  If value is an integer
731
        `n`, the first `n` system states are used.  Otherwise, the value
732
        should be a slice or a list of indices.  The list of indices can be
733
        specified as either integer offsets or as estimator/system output
734
        signal names.  If not specified, defaults to the system states.
735

736
    xd_labels, ud_labels, ref_labels : str or list of str, optional
737
        Set the name of the signals to use for the desired state and inputs
738
        or the reference inputs (for the 'refgain' design pattern).  If a
739
        single string is specified, it should be a format string using the
740
        variable `i` as an index.  Otherwise, a list of strings matching
741
        the size of `x_d` and `u_d`, respectively, should be used.  Default
742
        is "xd[{i}]" for xd_labels and "ud[{i}]" for ud_labels.  These
743
        settings can also be overridden using the `inputs` keyword.
744

745
    inputs, outputs, states : str, or list of str, optional
746
        List of strings that name the individual signals of the transformed
747
        system.  If not given, the inputs, outputs, and states are the same
748
        as the original system.
749

750
    name : string, optional
751
        System name. If unspecified, a generic name <sys[id]> is generated
752
        with a unique integer id.
753

754
    Examples
755
    --------
756
    >>> import control as ct
757
    >>> import numpy as np
758
    >>>
759
    >>> A = [[0, 1], [-0.5, -0.1]]
760
    >>> B = [[0], [1]]
761
    >>> C = np.eye(2)
762
    >>> D = np.zeros((2, 1))
763
    >>> sys = ct.ss(A, B, C, D)
764
    >>>
765
    >>> Q = np.eye(2)
766
    >>> R = np.eye(1)
767
    >>>
768
    >>> K, _, _ = ct.lqr(sys,Q,R)
769
    >>> ctrl, clsys = ct.create_statefbk_iosystem(sys, K)
770

771
    """
772
    # Make sure that we were passed an I/O system as an input
773
    if not isinstance(sys, NonlinearIOSystem):
9✔
774
        raise ControlArgument("Input system must be I/O system")
9✔
775

776
    # Process (legacy) keywords
777
    controller_type = _process_legacy_keyword(
9✔
778
        kwargs, 'type', 'controller_type', controller_type)
779
    if kwargs:
9✔
780
        raise TypeError("unrecognized keywords: ", str(kwargs))
9✔
781

782
    # Check for consistency of positional parameters
783
    if feedfwd_gain is not None and feedfwd_pattern != 'refgain':
9✔
784
        raise ControlArgument(
9✔
785
            "feedfwd_gain specified but feedfwd_pattern != 'refgain'")
786

787
    # Figure out what inputs to the system to use
788
    control_indices = _process_indices(
9✔
789
        control_indices, 'control', sys.input_labels, sys.ninputs)
790
    sys_ninputs = len(control_indices)
9✔
791

792
    # Decide what system is going to pass the states to the controller
793
    if estimator is None:
9✔
794
        estimator = sys
9✔
795

796
    # Figure out what outputs (states) from the system/estimator to use
797
    state_indices = _process_indices(
9✔
798
        state_indices, 'state', estimator.state_labels, sys.nstates)
799
    sys_nstates = len(state_indices)
9✔
800

801
    # Make sure the system/estimator states are proper dimension
802
    if estimator.noutputs < sys_nstates:
9✔
803
        # If no estimator, make sure that the system has all states as outputs
804
        raise ControlArgument(
9✔
805
            ("system" if estimator == sys else "estimator") +
806
            " output must include the full state")
807
    elif estimator == sys:
9✔
808
        # Issue a warning if we can't verify state output
809
        if (isinstance(sys, NonlinearIOSystem) and
9✔
810
            not isinstance(sys, StateSpace) and sys.outfcn is not None) or \
811
           (isinstance(sys, StateSpace) and
812
            not (np.all(sys.C[np.ix_(state_indices, state_indices)] ==
813
                        np.eye(sys_nstates)) and
814
                 np.all(sys.D[state_indices, :] == 0))):
815
            warnings.warn("cannot verify system output is system state")
9✔
816

817
    # See whether we should implement integral action
818
    nintegrators = 0
9✔
819
    if integral_action is not None:
9✔
820
        if not isinstance(integral_action, np.ndarray):
9✔
821
            raise ControlArgument("Integral action must pass an array")
9✔
822
        elif integral_action.shape[1] != sys_nstates:
9✔
823
            raise ControlArgument(
×
824
                "Integral gain size must match system state size")
825
        else:
826
            nintegrators = integral_action.shape[0]
9✔
827
            C = integral_action
9✔
828
    else:
829
        # Create a C matrix with no outputs, just in case update gets called
830
        C = np.zeros((0, sys_nstates))
9✔
831

832
    # Check to make sure that state feedback has the right shape
833
    if isinstance(gain, np.ndarray):
9✔
834
        K = gain
9✔
835
        if K.shape != (sys_ninputs, estimator.noutputs + nintegrators):
9✔
836
            raise ControlArgument(
9✔
837
                f'control gain must be an array of size {sys_ninputs}'
838
                f' x {sys_nstates}' +
839
                (f'+{nintegrators}' if nintegrators > 0 else ''))
840
        gainsched = False
9✔
841

842
    elif isinstance(gain, tuple):
9✔
843
        # Check for gain scheduled controller
844
        if len(gain) != 2:
9✔
845
            raise ControlArgument("gain must be a 2-tuple for gain scheduling")
9✔
846
        elif feedfwd_pattern != 'trajgen':
9✔
847
            raise NotImplementedError(
848
                "Gain scheduling is not implemented for pattern "
849
                f"'{feedfwd_pattern}'")
850
        gains, points = gain[0:2]
9✔
851

852
        # Stack gains and points if past as a list
853
        gains = np.stack(gains)
9✔
854
        points = np.stack(points)
9✔
855
        gainsched = True
9✔
856

857
    elif isinstance(gain, NonlinearIOSystem) and feedfwd_pattern != 'refgain':
9✔
858
        if controller_type not in ['iosystem', None]:
9✔
859
            raise ControlArgument(
×
860
                f"incompatible controller type '{controller_type}'")
861
        fbkctrl = gain
9✔
862
        controller_type = 'iosystem'
9✔
863
        gainsched = False
9✔
864

865
    else:
866
        raise ControlArgument("gain must be an array or a tuple")
9✔
867

868
    # Decide on the type of system to create
869
    if gainsched and controller_type == 'linear':
9✔
870
        raise ControlArgument(
×
871
            "controller_type 'linear' not allowed for"
872
            " gain scheduled controller")
873
    elif controller_type is None:
9✔
874
        controller_type = 'nonlinear' if gainsched else 'linear'
9✔
875
    elif controller_type not in {'linear', 'nonlinear', 'iosystem'}:
9✔
876
        raise ControlArgument(f"unknown controller_type '{controller_type}'")
9✔
877

878
    # Figure out the labels to use
879
    if feedfwd_pattern == 'trajgen':
9✔
880
        xd_labels = _process_labels(xd_labels, 'xd', [
9✔
881
            'xd[{i}]'.format(i=i) for i in range(sys_nstates)])
882
        ud_labels = _process_labels(ud_labels, 'ud', [
9✔
883
            'ud[{i}]'.format(i=i) for i in range(sys_ninputs)])
884

885
        # Create the signal and system names
886
        if inputs is None:
9✔
887
            inputs = xd_labels + ud_labels + estimator.output_labels
9✔
888
    elif feedfwd_pattern == 'refgain':
9✔
889
        ref_labels = _process_labels(ref_labels, 'r', [
9✔
890
            f'r[{i}]' for i in range(sys_ninputs)])
891
        if inputs is None:
9✔
892
            inputs = ref_labels + estimator.output_labels
9✔
893
    else:
894
        raise NotImplementedError(f"unknown pattern '{feedfwd_pattern}'")
895

896
    if outputs is None:
9✔
897
        outputs = [sys.input_labels[i] for i in control_indices]
9✔
898
    if states is None:
9✔
899
        states = nintegrators
9✔
900

901
    # Process gain scheduling variables, if present
902
    if gainsched:
9✔
903
        # Create a copy of the scheduling variable indices (default = xd)
904
        gainsched_indices = _process_indices(
9✔
905
            gainsched_indices, 'gainsched', inputs, sys_nstates)
906

907
        # If points is a 1D list, convert to 2D
908
        if points.ndim == 1:
9✔
909
            points = points.reshape(-1, 1)
9✔
910

911
        # Make sure the scheduling variable indices are the right length
912
        if len(gainsched_indices) != points.shape[1]:
9✔
913
            raise ControlArgument(
9✔
914
                "length of gainsched_indices must match dimension of"
915
                " scheduling variables")
916

917
        # Create interpolating function
918
        if points.shape[1] < 2:
9✔
919
            _interp = sp.interpolate.interp1d(
9✔
920
                points[:, 0], gains, axis=0, kind=gainsched_method)
921
            _nearest = sp.interpolate.interp1d(
9✔
922
                points[:, 0], gains, axis=0, kind='nearest')
923
        elif gainsched_method == 'nearest':
9✔
924
            _interp = sp.interpolate.NearestNDInterpolator(points, gains)
9✔
925
            def _nearest(mu):
9✔
926
                raise SystemError(f"could not find nearest gain at mu = {mu}")
×
927
        elif gainsched_method == 'linear':
9✔
928
            _interp = sp.interpolate.LinearNDInterpolator(points, gains)
9✔
929
            _nearest = sp.interpolate.NearestNDInterpolator(points, gains)
9✔
930
        elif gainsched_method == 'cubic':
9✔
931
            _interp = sp.interpolate.CloughTocher2DInterpolator(points, gains)
9✔
932
            _nearest = sp.interpolate.NearestNDInterpolator(points, gains)
9✔
933
        else:
934
            raise ControlArgument(
9✔
935
                f"unknown gain scheduling method '{gainsched_method}'")
936

937
        def _compute_gain(mu):
9✔
938
            K = _interp(mu)
9✔
939
            if np.isnan(K).any():
9✔
940
                K = _nearest(mu)
9✔
941
            return K
9✔
942

943
    # Define the controller system
944
    if controller_type == 'nonlinear' and feedfwd_pattern == 'trajgen':
9✔
945
        # Create an I/O system for the state feedback gains
946
        def _control_update(t, states, inputs, params):
9✔
947
            # Split input into desired state, nominal input, and current state
948
            xd_vec = inputs[0:sys_nstates]
9✔
949
            x_vec = inputs[-sys_nstates:]
9✔
950

951
            # Compute the integral error in the xy coordinates
952
            return C @ (x_vec - xd_vec)
9✔
953

954
        def _control_output(t, states, inputs, params):
9✔
955
            if gainsched:
9✔
956
                mu = inputs[gainsched_indices]
9✔
957
                K_ = _compute_gain(mu)
9✔
958
            else:
959
                K_ = params.get('K')
9✔
960

961
            # Split input into desired state, nominal input, and current state
962
            xd_vec = inputs[0:sys_nstates]
9✔
963
            ud_vec = inputs[sys_nstates:sys_nstates + sys_ninputs]
9✔
964
            x_vec = inputs[-sys_nstates:]
9✔
965

966
            # Compute the control law
967
            u = ud_vec - K_[:, 0:sys_nstates] @ (x_vec - xd_vec)
9✔
968
            if nintegrators > 0:
9✔
969
                u -= K_[:, sys_nstates:] @ states
9✔
970

971
            return u
9✔
972

973
        params = {} if gainsched else {'K': K}
9✔
974
        ctrl = NonlinearIOSystem(
9✔
975
            _control_update, _control_output, name=name, inputs=inputs,
976
            outputs=outputs, states=states, params=params)
977

978
    elif controller_type == 'iosystem' and feedfwd_pattern == 'trajgen':
9✔
979
        # Use the passed system to compute feedback compensation
980
        def _control_update(t, states, inputs, params):
9✔
981
            # Split input into desired state, nominal input, and current state
982
            xd_vec = inputs[0:sys_nstates]
9✔
983
            x_vec = inputs[-sys_nstates:]
9✔
984

985
            # Compute the integral error in the xy coordinates
986
            return fbkctrl.updfcn(t, states, (x_vec - xd_vec), params)
9✔
987

988
        def _control_output(t, states, inputs, params):
9✔
989
            # Split input into desired state, nominal input, and current state
990
            xd_vec = inputs[0:sys_nstates]
9✔
991
            ud_vec = inputs[sys_nstates:sys_nstates + sys_ninputs]
9✔
992
            x_vec = inputs[-sys_nstates:]
9✔
993

994
            # Compute the control law
995
            return ud_vec + fbkctrl.outfcn(t, states, (x_vec - xd_vec), params)
9✔
996

997
        # TODO: add a way to pass parameters
998
        ctrl = NonlinearIOSystem(
9✔
999
            _control_update, _control_output, name=name, inputs=inputs,
1000
            outputs=outputs, states=fbkctrl.state_labels, dt=fbkctrl.dt)
1001

1002
    elif controller_type in 'linear' and feedfwd_pattern == 'trajgen':
9✔
1003
        # Create the matrices implementing the controller
1004
        if isctime(sys):
9✔
1005
            # Continuous time: integrator
1006
            A_lqr = np.zeros((C.shape[0], C.shape[0]))
9✔
1007
        else:
1008
            # Discrete time: summer
1009
            A_lqr = np.eye(C.shape[0])
9✔
1010
        B_lqr = np.hstack([-C, np.zeros((C.shape[0], sys_ninputs)), C])
9✔
1011
        C_lqr = -K[:, sys_nstates:]
9✔
1012
        D_lqr = np.hstack([
9✔
1013
            K[:, 0:sys_nstates], np.eye(sys_ninputs), -K[:, 0:sys_nstates]
1014
        ])
1015

1016
        ctrl = ss(
9✔
1017
            A_lqr, B_lqr, C_lqr, D_lqr, dt=sys.dt, name=name,
1018
            inputs=inputs, outputs=outputs, states=states)
1019

1020
    elif feedfwd_pattern == 'refgain':
9✔
1021
        if controller_type not in ['linear', 'iosystem']:
9✔
1022
            raise ControlArgument(
×
1023
                "refgain design pattern only supports linear controllers")
1024

1025
        if feedfwd_gain is None:
9✔
1026
            raise ControlArgument(
9✔
1027
                "'feedfwd_gain' required for reference gain pattern")
1028

1029
        # Check to make sure the reference gain is valid
1030
        Kf = np.atleast_2d(feedfwd_gain)
9✔
1031
        if Kf.ndim != 2 or Kf.shape[0] != sys.ninputs or \
9✔
1032
           Kf.shape[1] != sys.ninputs:
1033
            raise ControlArgument("feedfwd_gain is not the right shape")
×
1034

1035
        # Create the matrices implementing the controller
1036
        # [r, x]->[u]: u = k_f r - K_p x - K_i \int(C x - r)
1037
        if isctime(sys):
9✔
1038
            # Continuous time: integrator
1039
            A_lqr = np.zeros((C.shape[0], C.shape[0]))
9✔
1040
        else:
1041
            # Discrete time: summer
1042
            A_lqr = np.eye(C.shape[0])
×
1043
        B_lqr = np.hstack([-np.eye(C.shape[0], sys_ninputs), C])
9✔
1044
        C_lqr = -K[:, sys_nstates:]                     # integral gain (opt)
9✔
1045
        D_lqr = np.hstack([Kf, -K])
9✔
1046

1047
        ctrl = ss(
9✔
1048
            A_lqr, B_lqr, C_lqr, D_lqr, dt=sys.dt, name=name,
1049
            inputs=inputs, outputs=outputs, states=states)
1050

1051
    else:
1052
        raise ControlArgument(f"unknown controller_type '{controller_type}'")
×
1053

1054
    # Define the closed loop system
1055
    inplist=inputs[:-sys.nstates]
9✔
1056
    input_labels=inputs[:-sys.nstates]
9✔
1057
    outlist=sys.output_labels + [sys.input_labels[i] for i in control_indices]
9✔
1058
    output_labels=sys.output_labels + \
9✔
1059
        [sys.input_labels[i] for i in control_indices]
1060
    closed = interconnect(
9✔
1061
        [sys, ctrl] if estimator == sys else [sys, ctrl, estimator],
1062
        name=sys.name + "_" + ctrl.name, add_unused=True,
1063
        inplist=inplist, inputs=input_labels,
1064
        outlist=outlist, outputs=output_labels
1065
    )
1066
    return ctrl, closed
9✔
1067

1068

1069
def ctrb(A, B, t=None):
9✔
1070
    """Controllabilty matrix.
1071

1072
    Parameters
1073
    ----------
1074
    A, B : array_like or string
1075
        Dynamics and input matrix of the system
1076
    t : None or integer
1077
        maximum time horizon of the controllability matrix, max = A.shape[0]
1078

1079
    Returns
1080
    -------
1081
    C : 2D array (or matrix)
1082
        Controllability matrix
1083

1084
    Examples
1085
    --------
1086
    >>> G = ct.tf2ss([1], [1, 2, 3])
1087
    >>> C = ct.ctrb(G.A, G.B)
1088
    >>> np.linalg.matrix_rank(C)
1089
    np.int64(2)
1090

1091
    """
1092

1093
    # Convert input parameters to matrices (if they aren't already)
1094
    amat = _ssmatrix(A)
9✔
1095
    bmat = _ssmatrix(B)
9✔
1096
    n = np.shape(amat)[0]
9✔
1097
    m = np.shape(bmat)[1]
9✔
1098

1099
    if t is None or t > n:
9✔
1100
        t = n
9✔
1101

1102
    # Construct the controllability matrix
1103
    ctrb = np.zeros((n, t * m))
9✔
1104
    ctrb[:, :m] = bmat
9✔
1105
    for k in range(1, t):
9✔
1106
        ctrb[:, k * m:(k + 1) * m] = np.dot(amat, ctrb[:, (k - 1) * m:k * m])
9✔
1107

1108
    return _ssmatrix(ctrb)
9✔
1109

1110

1111
def obsv(A, C, t=None):
9✔
1112
    """Observability matrix.
1113

1114
    Parameters
1115
    ----------
1116
    A, C : array_like or string
1117
        Dynamics and output matrix of the system
1118
    t : None or integer
1119
        maximum time horizon of the controllability matrix, max = A.shape[0]
1120

1121
    Returns
1122
    -------
1123
    O : 2D array (or matrix)
1124
        Observability matrix
1125

1126
    Examples
1127
    --------
1128
    >>> G = ct.tf2ss([1], [1, 2, 3])
1129
    >>> C = ct.obsv(G.A, G.C)
1130
    >>> np.linalg.matrix_rank(C)
1131
    np.int64(2)
1132

1133
    """
1134

1135
    # Convert input parameters to matrices (if they aren't already)
1136
    amat = _ssmatrix(A)
9✔
1137
    cmat = _ssmatrix(C)
9✔
1138
    n = np.shape(amat)[0]
9✔
1139
    p = np.shape(cmat)[0]
9✔
1140

1141
    if t is None or t > n:
9✔
1142
        t = n
9✔
1143

1144
    # Construct the observability matrix
1145
    obsv = np.zeros((t * p, n))
9✔
1146
    obsv[:p, :] = cmat
9✔
1147

1148
    for k in range(1, t):
9✔
1149
        obsv[k * p:(k + 1) * p, :] = np.dot(obsv[(k - 1) * p:k * p, :], amat)
9✔
1150

1151
    return _ssmatrix(obsv)
9✔
1152

1153

1154
def gram(sys, type):
9✔
1155
    """Gramian (controllability or observability).
1156

1157
    Parameters
1158
    ----------
1159
    sys : StateSpace
1160
        System description
1161
    type : String
1162
        Type of desired computation.  `type` is either 'c' (controllability)
1163
        or 'o' (observability). To compute the Cholesky factors of Gramians
1164
        use 'cf' (controllability) or 'of' (observability)
1165

1166
    Returns
1167
    -------
1168
    gram : 2D array (or matrix)
1169
        Gramian of system
1170

1171
    Raises
1172
    ------
1173
    ValueError
1174
        * if system is not instance of StateSpace class
1175
        * if `type` is not 'c', 'o', 'cf' or 'of'
1176
        * if system is unstable (sys.A has eigenvalues not in left half plane)
1177

1178
    ControlSlycot
1179
        if slycot routine sb03md cannot be found
1180
        if slycot routine sb03od cannot be found
1181

1182
    Examples
1183
    --------
1184
    >>> G = ct.rss(4)
1185
    >>> Wc = ct.gram(G, 'c')
1186
    >>> Wo = ct.gram(G, 'o')
1187
    >>> Rc = ct.gram(G, 'cf')  # where Wc = Rc' * Rc
1188
    >>> Ro = ct.gram(G, 'of')  # where Wo = Ro' * Ro
1189

1190
    """
1191

1192
    # Check for ss system object
1193
    if not isinstance(sys, statesp.StateSpace):
9✔
1194
        raise ValueError("System must be StateSpace!")
9✔
1195
    if type not in ['c', 'o', 'cf', 'of']:
9✔
1196
        raise ValueError("That type is not supported!")
×
1197

1198
    # Check if system is continuous or discrete
1199
    if sys.isctime():
9✔
1200
        dico = 'C'
5✔
1201

1202
        # TODO: Check system is stable, perhaps a utility in ctrlutil.py
1203
        # or a method of the StateSpace class?
1204
        if np.any(np.linalg.eigvals(sys.A).real >= 0.0):
5✔
1205
            raise ValueError("Oops, the system is unstable!")
×
1206

1207
    else:
1208
        assert sys.isdtime()
9✔
1209
        dico = 'D'
9✔
1210

1211
        if np.any(np.abs(sys.poles()) >= 1.):
9✔
1212
            raise ValueError("Oops, the system is unstable!")
9✔
1213

1214
    if type == 'c' or type == 'o':
5✔
1215
        # Compute Gramian by the Slycot routine sb03md
1216
        # make sure Slycot is installed
1217
        if sb03md is None:
5✔
1218
            raise ControlSlycot("can't find slycot module 'sb03md'")
×
1219
        if type == 'c':
5✔
1220
            tra = 'T'
5✔
1221
            C = -sys.B @ sys.B.T
5✔
1222
        elif type == 'o':
5✔
1223
            tra = 'N'
5✔
1224
            C = -sys.C.T @ sys.C
5✔
1225
        n = sys.nstates
5✔
1226
        U = np.zeros((n, n))
5✔
1227
        A = np.array(sys.A)         # convert to NumPy array for slycot
5✔
1228
        X, scale, sep, ferr, w = sb03md(
5✔
1229
            n, C, A, U, dico, job='X', fact='N', trana=tra)
1230
        gram = X
5✔
1231
        return _ssmatrix(gram)
5✔
1232

1233
    elif type == 'cf' or type == 'of':
5✔
1234
        # Compute cholesky factored gramian from slycot routine sb03od
1235
        if sb03od is None:
5✔
1236
            raise ControlSlycot("can't find slycot module 'sb03od'")
×
1237
        tra = 'N'
5✔
1238
        n = sys.nstates
5✔
1239
        Q = np.zeros((n, n))
5✔
1240
        A = np.array(sys.A)         # convert to NumPy array for slycot
5✔
1241
        if type == 'cf':
5✔
1242
            m = sys.B.shape[1]
5✔
1243
            B = np.zeros_like(A)
5✔
1244
            B[0:m, 0:n] = sys.B.transpose()
5✔
1245
            X, scale, w = sb03od(
5✔
1246
                n, m, A.transpose(), Q, B, dico, fact='N', trans=tra)
1247
        elif type == 'of':
5✔
1248
            m = sys.C.shape[0]
5✔
1249
            C = np.zeros_like(A)
5✔
1250
            C[0:n, 0:m] = sys.C.transpose()
5✔
1251
            X, scale, w = sb03od(
5✔
1252
                n, m, A, Q, C.transpose(), dico, fact='N', trans=tra)
1253
        gram = X
5✔
1254
        return _ssmatrix(gram)
5✔
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc