diff --git a/control/iosys.py b/control/iosys.py index 16ef633b7..ac150a1bd 100644 --- a/control/iosys.py +++ b/control/iosys.py @@ -111,11 +111,11 @@ class for a set of subclasses that are used to implement specific The :class:`~control.InputOuputSystem` class (and its subclasses) makes use of two special methods for implementing much of the work of the class: - * _rhs(t, x, u): compute the right hand side of the differential or + * dynamics(t, x, u): compute the right hand side of the differential or difference equation for the system. This must be specified by the subclass for the system. - * _out(t, x, u): compute the output for the current state of the system. + * output(t, x, u): compute the output for the current state of the system. The default is to return the entire system state. """ @@ -353,28 +353,69 @@ def _process_signal_list(self, signals, prefix='s'): # Find a signal by name def _find_signal(self, name, sigdict): return sigdict.get(name, None) - # Update parameters used for _rhs, _out (used by subclasses) + # Update parameters used for dynamics, _out (used by subclasses) def _update_params(self, params, warning=False): if (warning): warn("Parameters passed to InputOutputSystem ignored.") - def _rhs(self, t, x, u): - """Evaluate right hand side of a differential or difference equation. + def dynamics(self, t, x, u): + """Compute the dynamics of a differential or difference equation. - Private function used to compute the right hand side of an - input/output system model. + Given time `t`, input `u` and state `x`, returns the dynamics of the + system. If the system is continuous, returns the time derivative + ``dx/dt = f(t, x, u)`` + + where `f` is the system's (possibly nonlinear) dynamics function. + If the system is discrete-time, returns the next value of `x`: + + ``x[t+dt] = f(t, x[t], u[t])`` + + Where `t` is a scalar. + + The inputs `x` and `u` must be of the correct length. + + Parameters + ---------- + t : float + the time at which to evaluate + x : array_like + current state + u : array_like + input + + Returns + ------- + `dx/dt` or `x[t+dt]` : ndarray """ - NotImplemented("Evaluation not implemented for system of type ", + + NotImplemented("Dynamics not implemented for system of type ", type(self)) - def _out(self, t, x, u, params={}): - """Evaluate the output of a system at a given state, input, and time + def output(self, t, x, u, params={}): + """Compute the output of the system - Private function used to compute the output of of an input/output - system model given the state, input, parameters, and time. + Given time `t`, input `u` and state `x`, returns the output of the + system: + ``y = g(t, x, u)`` + + The inputs `x` and `u` must be of the correct length. + + Parameters + ---------- + t : float + the time at which to evaluate + x : array_like + current state + u : array_like + input + + Returns + ------- + y : ndarray """ + # If no output function was defined in subclass, return state return x @@ -533,7 +574,7 @@ def linearize(self, x0, u0, t=0, params={}, eps=1e-6, """ # # If the linearization is not defined by the subclass, perform a - # numerical linearization use the `_rhs()` and `_out()` member + # numerical linearization use the `dynamics()` and `output()` member # functions. # @@ -548,14 +589,14 @@ def linearize(self, x0, u0, t=0, params={}, eps=1e-6, u0 = np.ones((ninputs,)) * u0 # Compute number of outputs by evaluating the output function - noutputs = _find_size(self.noutputs, self._out(t, x0, u0)) + noutputs = _find_size(self.noutputs, self.output(t, x0, u0)) # Update the current parameters self._update_params(params) # Compute the nominal value of the update law and output - F0 = self._rhs(t, x0, u0) - H0 = self._out(t, x0, u0) + F0 = self.dynamics(t, x0, u0) + H0 = self.output(t, x0, u0) # Create empty matrices that we can fill up with linearizations A = np.zeros((nstates, nstates)) # Dynamics matrix @@ -567,15 +608,15 @@ def linearize(self, x0, u0, t=0, params={}, eps=1e-6, for i in range(nstates): dx = np.zeros((nstates,)) dx[i] = eps - A[:, i] = (self._rhs(t, x0 + dx, u0) - F0) / eps - C[:, i] = (self._out(t, x0 + dx, u0) - H0) / eps + A[:, i] = (self.dynamics(t, x0 + dx, u0) - F0) / eps + C[:, i] = (self.output(t, x0 + dx, u0) - H0) / eps # Perturb each of the input variables and compute linearization for i in range(ninputs): du = np.zeros((ninputs,)) du[i] = eps - B[:, i] = (self._rhs(t, x0, u0 + du) - F0) / eps - D[:, i] = (self._out(t, x0, u0 + du) - H0) / eps + B[:, i] = (self.dynamics(t, x0, u0 + du) - F0) / eps + D[:, i] = (self.output(t, x0, u0 + du) - H0) / eps # Create the state space system linsys = LinearIOSystem( @@ -694,17 +735,8 @@ def _update_params(self, params={}, warning=True): if params and warning: warn("Parameters passed to LinearIOSystems are ignored.") - def _rhs(self, t, x, u): - # Convert input to column vector and then change output to 1D array - xdot = np.dot(self.A, np.reshape(x, (-1, 1))) \ - + np.dot(self.B, np.reshape(u, (-1, 1))) - return np.array(xdot).reshape((-1,)) - - def _out(self, t, x, u): - # Convert input to column vector and then change output to 1D array - y = np.dot(self.C, np.reshape(x, (-1, 1))) \ - + np.dot(self.D, np.reshape(u, (-1, 1))) - return np.array(y).reshape((-1,)) + dynamics = StateSpace.dynamics + output = StateSpace.output class NonlinearIOSystem(InputOutputSystem): @@ -849,12 +881,12 @@ def __call__(sys, u, params=None, squeeze=None): "function evaluation is only supported for static " "input/output systems") - # If we received any parameters, update them before calling _out() + # If we received any parameters, update them before calling output() if params is not None: sys._update_params(params) # Evaluate the function on the argument - out = sys._out(0, np.array((0,)), np.asarray(u)) + out = sys.output(0, np.array((0,)), np.asarray(u)) _, out = _process_time_response(sys, None, out, None, squeeze=squeeze) return out @@ -863,12 +895,12 @@ def _update_params(self, params, warning=False): self._current_params = self.params.copy() self._current_params.update(params) - def _rhs(self, t, x, u): + def dynamics(self, t, x, u): xdot = self.updfcn(t, x, u, self._current_params) \ if self.updfcn is not None else [] return np.array(xdot).reshape((-1,)) - def _out(self, t, x, u): + def output(self, t, x, u): y = self.outfcn(t, x, u, self._current_params) \ if self.outfcn is not None else x return np.array(y).reshape((-1,)) @@ -1033,7 +1065,7 @@ def _update_params(self, params, warning=False): local.update(params) # update with locally passed parameters sys._update_params(local, warning=warning) - def _rhs(self, t, x, u): + def dynamics(self, t, x, u): # Make sure state and input are vectors x = np.array(x, ndmin=1) u = np.array(u, ndmin=1) @@ -1047,7 +1079,7 @@ def _rhs(self, t, x, u): for sys in self.syslist: # Update the right hand side for this subsystem if sys.nstates != 0: - xdot[state_index:state_index + sys.nstates] = sys._rhs( + xdot[state_index:state_index + sys.nstates] = sys.dynamics( t, x[state_index:state_index + sys.nstates], ulist[input_index:input_index + sys.ninputs]) @@ -1057,7 +1089,7 @@ def _rhs(self, t, x, u): return xdot - def _out(self, t, x, u): + def output(self, t, x, u): # Make sure state and input are vectors x = np.array(x, ndmin=1) u = np.array(u, ndmin=1) @@ -1089,7 +1121,7 @@ def _compute_static_io(self, t, x, u): state_index, input_index, output_index = 0, 0, 0 for sys in self.syslist: # Compute outputs for each system from current state - ysys = sys._out( + ysys = sys.output( t, x[state_index:state_index + sys.nstates], ulist[input_index:input_index + sys.ninputs]) @@ -1480,10 +1512,10 @@ def input_output_response(sys, T, U=0., X0=0, params={}, method='RK45', if nstates == 0: # No states => map input to output u = U[0] if len(U.shape) == 1 else U[:, 0] - y = np.zeros((np.shape(sys._out(T[0], X0, u))[0], len(T))) + y = np.zeros((np.shape(sys.output(T[0], X0, u))[0], len(T))) for i in range(len(T)): u = U[i] if len(U.shape) == 1 else U[:, i] - y[:, i] = sys._out(T[i], [], u) + y[:, i] = sys.output(T[i], [], u) return _process_time_response( sys, T, y, np.array((0, 0, np.asarray(T).size)), transpose=transpose, return_x=return_x, squeeze=squeeze) @@ -1497,23 +1529,23 @@ def input_output_response(sys, T, U=0., X0=0, params={}, method='RK45', # Create a lambda function for the right hand side u = sp.interpolate.interp1d(T, U, fill_value="extrapolate") - def ivp_rhs(t, x): return sys._rhs(t, x, u(t)) + def ivp_dynamics(t, x): return sys.dynamics(t, x, u(t)) # Perform the simulation if isctime(sys): if not hasattr(sp.integrate, 'solve_ivp'): raise NameError("scipy.integrate.solve_ivp not found; " "use SciPy 1.0 or greater") - soln = sp.integrate.solve_ivp(ivp_rhs, (T0, Tf), X0, t_eval=T, + soln = sp.integrate.solve_ivp(ivp_dynamics, (T0, Tf), X0, t_eval=T, method=method, vectorized=False) # Compute the output associated with the state (and use sys.out to # figure out the number of outputs just in case it wasn't specified) u = U[0] if len(U.shape) == 1 else U[:, 0] - y = np.zeros((np.shape(sys._out(T[0], X0, u))[0], len(T))) + y = np.zeros((np.shape(sys.output(T[0], X0, u))[0], len(T))) for i in range(len(T)): u = U[i] if len(U.shape) == 1 else U[:, i] - y[:, i] = sys._out(T[i], soln.y[:, i], u) + y[:, i] = sys.output(T[i], soln.y[:, i], u) elif isdtime(sys): # Make sure the time vector is uniformly spaced @@ -1546,10 +1578,10 @@ def ivp_rhs(t, x): return sys._rhs(t, x, u(t)) for i in range(len(T)): # Store the current state and output soln.y.append(x) - y.append(sys._out(T[i], x, u(T[i]))) + y.append(sys.output(T[i], x, u(T[i]))) # Update the state for the next iteration - x = sys._rhs(T[i], x, u(T[i])) + x = sys.dynamics(T[i], x, u(T[i])) # Convert output to numpy arrays soln.y = np.transpose(np.array(soln.y)) @@ -1670,9 +1702,9 @@ def find_eqpt(sys, x0, u0=[], y0=None, t=0, params={}, if y0 is None: # Take u0 as fixed and minimize over x # TODO: update to allow discrete time systems - def ode_rhs(z): return sys._rhs(t, z, u0) - result = root(ode_rhs, x0, **kw) - z = (result.x, u0, sys._out(t, result.x, u0)) + def ode_dynamics(z): return sys.dynamics(t, z, u0) + result = root(ode_dynamics, x0, **kw) + z = (result.x, u0, sys.output(t, result.x, u0)) else: # Take y0 as fixed and minimize over x and u def rootfun(z): @@ -1680,11 +1712,11 @@ def rootfun(z): x, u = np.split(z, [nstates]) # TODO: update to allow discrete time systems return np.concatenate( - (sys._rhs(t, x, u), sys._out(t, x, u) - y0), axis=0) + (sys.dynamics(t, x, u), sys.output(t, x, u) - y0), axis=0) z0 = np.concatenate((x0, u0), axis=0) # Put variables together result = root(rootfun, z0, **kw) # Find the eq point x, u = np.split(result.x, [nstates]) # Split result back in two - z = (x, u, sys._out(t, x, u)) + z = (x, u, sys.output(t, x, u)) else: # General case: figure out what variables to constrain @@ -1782,10 +1814,10 @@ def rootfun(z): u[input_vars] = z[nstate_vars:] # Compute the update and output maps - dx = sys._rhs(t, x, u) - dx0 + dx = sys.dynamics(t, x, u) - dx0 if dtime: dx -= x # TODO: check - dy = sys._out(t, x, u) - y0 + dy = sys.output(t, x, u) - y0 # Map the results into the constrained variables return np.concatenate((dx[deriv_vars], dy[output_vars]), axis=0) @@ -1799,7 +1831,7 @@ def rootfun(z): # Extract out the results and insert into x and u x[state_vars] = result.x[:nstate_vars] u[input_vars] = result.x[nstate_vars:] - z = (x, u, sys._out(t, x, u)) + z = (x, u, sys.output(t, x, u)) # Return the result based on what the user wants and what we found if not return_y: diff --git a/control/sisotool.py b/control/sisotool.py index bfd93736e..38c7148d4 100644 --- a/control/sisotool.py +++ b/control/sisotool.py @@ -101,7 +101,7 @@ def sisotool(sys, kvect=None, xlim_rlocus=None, ylim_rlocus=None, # First time call to setup the bode and step response plots _SisotoolUpdate(sys, fig, - 1 if kvect is None else kvect[0], bode_plot_params) + 1 if kvect is None else kvect[0], bode_plot_params, tvect=tvect) # Setup the root-locus plot window root_locus(sys, kvect=kvect, xlim=xlim_rlocus, diff --git a/control/statesp.py b/control/statesp.py index abd55ad15..6103053fe 100644 --- a/control/statesp.py +++ b/control/statesp.py @@ -1215,9 +1215,94 @@ def dcgain(self): def _isstatic(self): """True if and only if the system has no dynamics, that is, - if A and B are zero. """ + if `self.A` and `self.B` are zero. + """ return not np.any(self.A) and not np.any(self.B) + def dynamics(self, t=None, x=None, u=None): + """Compute the dynamics of the system + + Given input `u` and state `x`, returns the dynamics of the state-space + system. If the system is continuous, returns the time derivative dx/dt + + dx/dt = A x + B u + + where A and B are the state-space matrices of the system. If the + system is discrete-time, returns the next value of `x`: + + x[t+dt] = A x[t] + B u[t] + + The inputs `x` and `u` must be of the correct length. The argument + `t` is included for consistency with :class:`IOSystem` systems, but + is ignored in :class:`StateSpace` systems, which are time-invariant. + + Parameters + ---------- + t : float (ignored) + time + x : array_like (optional) + current state, zero if omitted + u : array_like (optional) + input, zero if omitted + + Returns + ------- + dx/dt or x[t+dt] : ndarray of shape (self.nstates,) + """ + + out = np.zeros((self.nstates, 1)) + if x is not None: + if np.size(x) != self.nstates: + raise ValueError("len(x) must be equal to number of states") + x = np.reshape(x, (-1, 1)) # x must be column vector + out = out + self.A.dot(x) + if u is not None: + if np.size(u) != self.ninputs: + raise ValueError("len(u) must be equal to number of inputs") + u = np.reshape(u, (-1, 1)) # u as column vector + out = out + self.B.dot(u) + return out.reshape((-1,)) # return as row vector + + def output(self, t=None, x=None, u=None): + """Compute the output of the system + + Given input `u` and state `x`, returns the output `y` of the + state-space system: + + y = C x + D u + + where A and B are the state-space matrices of the system. The inputs + `x` and `u` must be of the correct length. The argument `t` is + included for consistency with :class:`IOSystem` systems, but is + ignored in :class:`StateSpace` systems, which are time-invariant. + + Parameters + ---------- + t : float (ignored) + time + x : array_like (optional) + current state (zero if omitted) + u : array_like (optional) + input (zero if omitted) + + Returns + ------- + y : ndarray of shape (self.noutputs,) + """ + y = np.zeros((self.noutputs,1)) + if x is not None: + if np.size(x) != self.nstates: + raise ValueError("len(x) must be equal to number of states") + x = np.reshape(x, (-1, 1)) # force x to be column vector + y = y + self.C.dot(x) + if u is not None: + if np.size(u) != self.ninputs: + raise ValueError("len(u) must be equal to number of inputs") + u = np.reshape(u, (-1, 1)) # force u to be column vector + y = y + self.D.dot(u) + return y.reshape((-1,)) # return as row vector + + # TODO: add discrete time check def _convert_to_statespace(sys, **kw): diff --git a/control/tests/iosys_test.py b/control/tests/iosys_test.py index 9a15e83f4..2ecb14559 100644 --- a/control/tests/iosys_test.py +++ b/control/tests/iosys_test.py @@ -56,7 +56,7 @@ def test_linear_iosys(self, tsys): # Make sure that the right hand side matches linear system for x, u in (([0, 0], 0), ([1, 0], 0), ([0, 1], 0), ([0, 0], 1)): np.testing.assert_array_almost_equal( - np.reshape(iosys._rhs(0, x, u), (-1, 1)), + np.reshape(iosys.dynamics(0, x, u), (-1, 1)), np.dot(linsys.A, np.reshape(x, (-1, 1))) + np.dot(linsys.B, u)) # Make sure that simulations also line up @@ -687,7 +687,7 @@ def test_find_eqpts(self, tsys): assert result.success np.testing.assert_array_almost_equal(xeq, [1.64705879, 1.17923874]) np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((2,))) + nlsys.dynamics(0, xeq, ueq), np.zeros((2,))) # Ducted fan dynamics with output = velocity nlsys = ios.NonlinearIOSystem(pvtol, lambda t, x, u, params: x[0:2]) @@ -697,7 +697,7 @@ def test_find_eqpts(self, tsys): nlsys, [0, 0, 0, 0], [0, 4*9.8], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((4,))) + nlsys.dynamics(0, xeq, ueq), np.zeros((4,))) np.testing.assert_array_almost_equal(xeq, [0, 0, 0, 0]) # Use a small lateral force to cause motion @@ -705,7 +705,7 @@ def test_find_eqpts(self, tsys): nlsys, [0, 0, 0, 0], [0.01, 4*9.8], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((4,)), decimal=5) + nlsys.dynamics(0, xeq, ueq), np.zeros((4,)), decimal=5) # Equilibrium point with fixed output xeq, ueq, result = ios.find_eqpt( @@ -713,9 +713,9 @@ def test_find_eqpts(self, tsys): y0=[0.1, 0.1], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys._out(0, xeq, ueq), [0.1, 0.1], decimal=5) + nlsys.output(0, xeq, ueq), [0.1, 0.1], decimal=5) np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((4,)), decimal=5) + nlsys.dynamics(0, xeq, ueq), np.zeros((4,)), decimal=5) # Specify outputs to constrain (replicate previous) xeq, ueq, result = ios.find_eqpt( @@ -723,17 +723,17 @@ def test_find_eqpts(self, tsys): iy = [0, 1], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys._out(0, xeq, ueq), [0.1, 0.1], decimal=5) + nlsys.output(0, xeq, ueq), [0.1, 0.1], decimal=5) np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((4,)), decimal=5) + nlsys.dynamics(0, xeq, ueq), np.zeros((4,)), decimal=5) # Specify inputs to constrain (replicate previous), w/ no result xeq, ueq = ios.find_eqpt( nlsys, [0, 0, 0, 0], [0.01, 4*9.8], y0=[0.1, 0.1], iu = []) np.testing.assert_array_almost_equal( - nlsys._out(0, xeq, ueq), [0.1, 0.1], decimal=5) + nlsys.output(0, xeq, ueq), [0.1, 0.1], decimal=5) np.testing.assert_array_almost_equal( - nlsys._rhs(0, xeq, ueq), np.zeros((4,)), decimal=5) + nlsys.dynamics(0, xeq, ueq), np.zeros((4,)), decimal=5) # Now solve the problem with the original PVTOL variables # Constrain the output angle and x velocity @@ -744,9 +744,9 @@ def test_find_eqpts(self, tsys): idx=[2, 3, 4, 5], ix=[0, 1], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys_full._out(0, xeq, ueq)[[2, 3]], [0.1, 0.1], decimal=5) + nlsys_full.output(0, xeq, ueq)[[2, 3]], [0.1, 0.1], decimal=5) np.testing.assert_array_almost_equal( - nlsys_full._rhs(0, xeq, ueq)[-4:], np.zeros((4,)), decimal=5) + nlsys_full.dynamics(0, xeq, ueq)[-4:], np.zeros((4,)), decimal=5) # Fix one input and vary the other nlsys_full = ios.NonlinearIOSystem(pvtol_full, None) @@ -757,9 +757,9 @@ def test_find_eqpts(self, tsys): assert result.success np.testing.assert_almost_equal(ueq[1], 4*9.8, decimal=5) np.testing.assert_array_almost_equal( - nlsys_full._out(0, xeq, ueq)[[3]], [0.1], decimal=5) + nlsys_full.output(0, xeq, ueq)[[3]], [0.1], decimal=5) np.testing.assert_array_almost_equal( - nlsys_full._rhs(0, xeq, ueq)[-4:], np.zeros((4,)), decimal=5) + nlsys_full.dynamics(0, xeq, ueq)[-4:], np.zeros((4,)), decimal=5) # PVTOL with output = y velocity xeq, ueq, result = ios.find_eqpt( @@ -769,9 +769,9 @@ def test_find_eqpts(self, tsys): ix=[0, 1], return_result=True) assert result.success np.testing.assert_array_almost_equal( - nlsys_full._out(0, xeq, ueq)[-3:], [0.1, 0, 0], decimal=5) + nlsys_full.output(0, xeq, ueq)[-3:], [0.1, 0, 0], decimal=5) np.testing.assert_array_almost_equal( - nlsys_full._rhs(0, xeq, ueq)[-5:], np.zeros((5,)), decimal=5) + nlsys_full.dynamics(0, xeq, ueq)[-5:], np.zeros((5,)), decimal=5) # Unobservable system linsys = ct.StateSpace( diff --git a/control/tests/statesp_test.py b/control/tests/statesp_test.py index 1c76efbc0..52ad5a50f 100644 --- a/control/tests/statesp_test.py +++ b/control/tests/statesp_test.py @@ -8,6 +8,7 @@ """ import numpy as np +from numpy.testing import assert_allclose, assert_array_almost_equal import pytest import operator from numpy.linalg import solve @@ -42,14 +43,26 @@ def sys322ABCD(self): [0., 1.]] return (A322, B322, C322, D322) + + @pytest.fixture + def sys121(self): + """2 state, 1 input, 1 output (siso) system""" + A121 = [[4., 1.], + [2., -3]] + B121 = [[5.], + [-3.]] + C121 = [[2., -4]] + D121 = [[3.]] + return StateSpace(A121, B121, C121, D121) + @pytest.fixture def sys322(self, sys322ABCD): - """3-states square system (2 inputs x 2 outputs)""" + """3-state square system (2 inputs x 2 outputs)""" return StateSpace(*sys322ABCD) @pytest.fixture def sys222(self): - """2-states square system (2 inputs x 2 outputs)""" + """2-state square system (2 inputs x 2 outputs)""" A222 = [[4., 1.], [2., -3]] B222 = [[5., 2.], @@ -744,6 +757,66 @@ def test_horner(self, sys322): np.squeeze(sys322.horner(1.j)), mag[:, :, 0] * np.exp(1.j * phase[:, :, 0])) + @pytest.mark.parametrize('x', + [None, [1, 1], [[1], [1]], np.atleast_2d([1,1]).T]) + @pytest.mark.parametrize('u', [None, 0, 1, np.atleast_1d(2)]) + def test_dynamics_output_siso(self, x, u, sys121): + assert_array_almost_equal( + sys121.dynamics(0, x, u), + np.zeros(2) + \ + (0 if x is None else sys121.A.dot(x).reshape((-1,))) + \ + (0 if u is None else sys121.B.dot(u).reshape((-1,)))) + assert_array_almost_equal( + sys121.output(0, x, u), + np.zeros(1) + \ + (0 if x is None else sys121.C.dot(x).reshape((-1,))) + \ + (0 if u is None else sys121.D.dot(u).reshape((-1,)))) + + # too few and too many states and inputs + @pytest.mark.parametrize('x', [0, 1, [], [1, 2, 3], np.atleast_1d(2)]) + def test_error_x_dynamics_output_siso(self, x, sys121): + with pytest.raises(ValueError): + sys121.dynamics(0, x, None) + with pytest.raises(ValueError): + sys121.output(0, x, None) + @pytest.mark.parametrize('u', [[1, 1], np.atleast_1d((2, 2))]) + def test_error_u_dynamics_output_siso(self, u, sys121): + with pytest.raises(ValueError): + sys121.dynamics(0, None, u) + with pytest.raises(ValueError): + sys121.output(0, None, u) + + @pytest.mark.parametrize('x', + [None, [1, 1], [[1], [1]], np.atleast_2d([1,1]).T]) + @pytest.mark.parametrize('u', + [None, [1, 1], [[1], [1]], np.atleast_2d([1,1]).T]) + def test_dynamics_output_mimo(self, x, u, sys222): + assert_array_almost_equal( + sys222.dynamics(0, x, u), + np.zeros(2) + \ + (0 if x is None else sys222.A.dot(x).reshape((-1,))) + \ + (0 if u is None else sys222.B.dot(u).reshape((-1,)))) + assert_array_almost_equal( + sys222.output(0, x, u), + np.zeros(2) + \ + (0 if x is None else sys222.C.dot(x).reshape((-1,))) + \ + (0 if u is None else sys222.D.dot(u).reshape((-1,)))) + #sys222.C.dot(x) + (0 if u is None else sys222.D.dot(u))) + + # too few and too many states and inputs + @pytest.mark.parametrize('x', [0, 1, [1, 1, 1]]) + def test_error_x_dynamics_mimo(self, x, sys222): + with pytest.raises(ValueError): + sys222.dynamics(0, x) + with pytest.raises(ValueError): + sys222.output(0, x) + @pytest.mark.parametrize('u', [0, 1, [1, 1, 1]]) + def test_error_u_dynamics_mimo(self, u, sys222): + with pytest.raises(ValueError): + sys222.dynamics(0, None, u) + with pytest.raises(ValueError): + sys222.output(0, None, u) + class TestRss: """These are tests for the proper functionality of statesp.rss.""" diff --git a/control/tests/type_conversion_test.py b/control/tests/type_conversion_test.py index 3f51c2bbc..ffb8bb9ed 100644 --- a/control/tests/type_conversion_test.py +++ b/control/tests/type_conversion_test.py @@ -19,7 +19,7 @@ def sys_dict(): sdict['frd'] = ct.frd([10+0j, 9 + 1j, 8 + 2j], [1,2,3]) sdict['lio'] = ct.LinearIOSystem(ct.ss([[-1]], [[5]], [[5]], [[0]])) sdict['ios'] = ct.NonlinearIOSystem( - sdict['lio']._rhs, sdict['lio']._out, 1, 1, 1) + sdict['lio'].dynamics, sdict['lio'].output, 1, 1, 1) sdict['arr'] = np.array([[2.0]]) sdict['flt'] = 3. return sdict @@ -66,7 +66,7 @@ def sys_dict(): ('add', 'ios', ['xos', 'xos', 'E', 'ios', 'ios', 'xos', 'xos']), ('add', 'arr', ['ss', 'tf', 'xrd', 'xio', 'xos', 'arr', 'arr']), ('add', 'flt', ['ss', 'tf', 'xrd', 'xio', 'xos', 'arr', 'flt']), - + # op left ss tf frd lio ios arr flt ('sub', 'ss', ['ss', 'ss', 'xrd', 'ss', 'xos', 'ss', 'ss' ]), ('sub', 'tf', ['tf', 'tf', 'xrd', 'tf', 'xos', 'tf', 'tf' ]), @@ -75,7 +75,7 @@ def sys_dict(): ('sub', 'ios', ['xos', 'xio', 'E', 'ios', 'xos' 'xos', 'xos']), ('sub', 'arr', ['ss', 'tf', 'xrd', 'xio', 'xos', 'arr', 'arr']), ('sub', 'flt', ['ss', 'tf', 'xrd', 'xio', 'xos', 'arr', 'flt']), - + # op left ss tf frd lio ios arr flt ('mul', 'ss', ['ss', 'ss', 'xrd', 'ss', 'xos', 'ss', 'ss' ]), ('mul', 'tf', ['tf', 'tf', 'xrd', 'tf', 'xos', 'tf', 'tf' ]), @@ -84,7 +84,7 @@ def sys_dict(): ('mul', 'ios', ['xos', 'xos', 'E', 'ios', 'ios', 'xos', 'xos']), ('mul', 'arr', ['ss', 'tf', 'xrd', 'xio', 'xos', 'arr', 'arr']), ('mul', 'flt', ['ss', 'tf', 'frd', 'xio', 'xos', 'arr', 'flt']), - + # op left ss tf frd lio ios arr flt ('truediv', 'ss', ['xs', 'tf', 'xrd', 'xio', 'xos', 'xs', 'xs' ]), ('truediv', 'tf', ['tf', 'tf', 'xrd', 'tf', 'xos', 'tf', 'tf' ]), @@ -100,7 +100,7 @@ def sys_dict(): for rtype, expected in zip(rtype_list, expected_list): # Add this to the list of tests to run test_matrix.append([opname, ltype, rtype, expected]) - + @pytest.mark.parametrize("opname, ltype, rtype, expected", test_matrix) def test_operator_type_conversion(opname, ltype, rtype, expected, sys_dict): op = getattr(operator, opname) @@ -110,7 +110,7 @@ def test_operator_type_conversion(opname, ltype, rtype, expected, sys_dict): # Get rid of warnings for InputOutputSystem objects by making a copy if isinstance(leftsys, ct.InputOutputSystem) and leftsys == rightsys: rightsys = leftsys.copy() - + # Make sure we get the right result if expected == 'E' or expected[0] == 'x': # Exception expected @@ -119,7 +119,7 @@ def test_operator_type_conversion(opname, ltype, rtype, expected, sys_dict): else: # Operation should work and return the given type result = op(leftsys, rightsys) - + # Print out what we are testing in case something goes wrong assert isinstance(result, type_dict[expected]) @@ -138,7 +138,7 @@ def test_operator_type_conversion(opname, ltype, rtype, expected, sys_dict): # # * For IOS/LTI, convert to IOS. In the case of a linear I/O system (LIO), # this will preserve the linear structure since the LTI system will -# be converted to state space. +# be converted to state space. # # * When combining state space or transfer with linear I/O systems, the # * output should be of type Linear IO system, since that maintains the @@ -149,7 +149,7 @@ def test_operator_type_conversion(opname, ltype, rtype, expected, sys_dict): type_list = ['ss', 'tf', 'tfx', 'frd', 'lio', 'ios', 'arr', 'flt'] conversion_table = [ - # L \ R ['ss', 'tf', 'tfx', 'frd', 'lio', 'ios', 'arr', 'flt'] + # L \ R ['ss', 'tf', 'tfx', 'frd', 'lio', 'ios', 'arr', 'flt'] ('ss', ['ss', 'ss', 'tf' 'frd', 'lio', 'ios', 'ss', 'ss' ]), ('tf', ['tf', 'tf', 'tf' 'frd', 'lio', 'ios', 'tf', 'tf' ]), ('tfx', ['tf', 'tf', 'tf', 'frd', 'E', 'E', 'tf', 'tf' ]), diff --git a/doc/iosys.rst b/doc/iosys.rst index 1b160bad1..58d0f849f 100644 --- a/doc/iosys.rst +++ b/doc/iosys.rst @@ -29,8 +29,8 @@ Input/output systems can be created from state space LTI systems by using the io_sys = LinearIOSystem(ss_sys) Nonlinear input/output systems can be created using the -:class:`~control.NonlinearIOSystem` class, which requires the definition of an -update function (for the right hand side of the differential or different +:class:`~control.NonlinearIOSystem` class, which requires the definition of a +dynamics function (the right hand side of the differential or difference equation) and and output function (computes the outputs from the state):: io_sys = NonlinearIOSystem(updfcn, outfcn, inputs=M, outputs=P, states=N) @@ -68,7 +68,7 @@ We begin by defining the dynamics of the system import numpy as np import matplotlib.pyplot as plt - def predprey_rhs(t, x, u, params): + def predprey_dynamics(t, x, u, params): # Parameter setup a = params.get('a', 3.2) b = params.get('b', 0.6) @@ -76,18 +76,18 @@ We begin by defining the dynamics of the system d = params.get('d', 0.56) k = params.get('k', 125) r = params.get('r', 1.6) - + # Map the states into local variable names H = x[0] L = x[1] # Compute the control action (only allow addition of food) u_0 = u if u > 0 else 0 - + # Compute the discrete updates dH = (r + u_0) * H * (1 - H/k) - (a * H * L)/(c + H) dL = b * (a * H * L)/(c + H) - d * L - + return [dH, dL] We now create an input/output system using these dynamics: @@ -95,7 +95,7 @@ We now create an input/output system using these dynamics: .. code-block:: python io_predprey = control.NonlinearIOSystem( - predprey_rhs, None, inputs=('u'), outputs=('H', 'L'), + predprey_dynamics, None, inputs=('u'), outputs=('H', 'L'), states=('H', 'L'), name='predprey') Note that since we have not specified an output function, the entire state @@ -108,10 +108,10 @@ of the system: X0 = [25, 20] # Initial H, L T = np.linspace(0, 70, 500) # Simulation 70 years of time - + # Simulate the system t, y = control.input_output_response(io_predprey, T, 0, X0) - + # Plot the response plt.figure(1) plt.plot(t, y[0]) @@ -171,14 +171,14 @@ function: inplist=['control.Ld'], outlist=['predprey.H', 'predprey.L', 'control.y[0]'] ) - + Finally, we simulate the closed loop system: .. code-block:: python # Simulate the system t, y = control.input_output_response(io_closed, T, 30, [15, 20]) - + # Plot the response plt.figure(2) plt.subplot(2, 1, 1) pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy