Shortcuts

pypose.module.LTV

class pypose.module.LTV(A=None, B=None, C=None, D=None, c1=None, c2=None)[source]

Discrete-time Linear Time-Variant (LTV) system.

Parameters:
  • A (Tensor, optional) – The stacked state matrix of LTI system. Default: None

  • B (Tensor, optional) – The stacked input matrix of LTI system. Default: None

  • C (Tensor, optional) – The stacked output matrix of LTI system. Default: None

  • D (Tensor, optional) – The stacked observation matrix of LTI system. Default: None

  • c1 (Tensor, optional) – The stacked constant input of LTI system. Default: None

  • c2 (Tensor, optional) – The stacked constant output of LTI system. Default: None

A linear time-variant lumped system can be described by state-space equation of the form:

\[\begin{align*} \mathbf{x}_{k+1} = \mathbf{A}_k\mathbf{x}_k + \mathbf{B}\mathbf{u}_k + \mathbf{c}^1_k \\ \mathbf{y}_k = \mathbf{C}_k\mathbf{x}_k + \mathbf{D}\mathbf{u}_k + \mathbf{c}^2_k \\ \end{align*} \]

where \(\mathbf{x}_k\) and \(\mathbf{u}_k\) are state and input at the timestamp \(k\) of LTI system.

Note

The forward method implicitly increments the time step via forward_hook. state_transition and observation still accept time for the flexiblity such as time-varying system. One can directly access the current system time via the property systime or _t.

Note

The variables including state and input are row vectors, which is the last dimension of a Tensor. A, B, C, D, x, u could be a single matrix or batched matrices. In the batch case, their dimensions must be consistent so that they can be multiplied for each channel.

Example

A periodic linear time variant system.

>>> n_batch, n_state, n_ctrl, T = 2, 4, 3, 5
>>> n_sc = n_state + n_ctrl
>>> A = torch.randn(n_batch, T, n_state, n_state)
>>> B = torch.randn(n_batch, T, n_state, n_ctrl)
>>> C = torch.tile(torch.eye(n_state), (n_batch, T, 1, 1))
>>> D = torch.tile(torch.zeros(n_state, n_ctrl), (n_batch, T, 1, 1))
>>> x = torch.randn(n_state)
>>> u = torch.randn(T, n_ctrl)
...
>>> class MyLTV(pp.module.LTV):
...     def __init__(self, A, B, C, D, T):
...         super().__init__(A, B, C, D)
...         self.T = T
...
...     @property
...     def A(self):
...         return self._A[...,self._t % self.T,:,:]
...
...     @property
...     def B(self):
...         return self._B[...,self._t % self.T,:,:]
...
...     @property
...     def C(self):
...         return self._C[...,self._t % self.T,:,:]
...
...     @property
...     def D(self):
...         return self._D[...,self._t % self.T,:,:]
...
>>> ltv = MyLTV(A, B, C, D, T)
>>> for t in range(T):
...     x, y = ltv(x, u[t])

One may also generate the system matrices with the time variable _t.

>>> n_batch, n_state, n_ctrl, T = 2, 4, 3, 5
>>> n_sc = n_state + n_ctrl
>>> x = torch.randn(n_state)
>>> u = torch.randn(T, n_ctrl)
...
>>> class MyLTV(pp.module.LTV):
...     def __init__(self, A, B, C, D, T):
...         super().__init__(A, B, C, D)
...         self.T = T
...
...     @property
...     def A(self):
...         return torch.eye(4, 4) * self._t.cos()
...
...     @property
...     def B(self):
...         return torch.eye(4, 3) * self._t.sin()
...
...     @property
...     def C(self):
...         return torch.eye(4, 4) * self._t.tan()
...
...     @property
...     def D(self):
...         return torch.eye(4, 3)
...
>>> ltv = MyLTV()
>>> for t in range(T):
...     x, y = ltv(x, u[t])

Note

More practical examples can be found at examples/module/dynamics.

set_refpoint(state=None, input=None, t=None)[source]

Function to set the reference point for linearization.

Parameters:
  • state (Tensor) – The reference state of the dynamical system. If None, the the most recent state is taken. Default: None.

  • input (Tensor) – The reference input to the dynamical system. If None, the the most recent input is taken. Default: None.

  • t (Tensor) – The reference time step of the dynamical system. If None, the the most recent timestamp is taken. Default: None.

Returns:

The self module.

Warning

For nonlinear systems, the users have to call this function before getting the linearized system.

Docs

Access documentation for PyPose

View Docs

Tutorials

Get started with tutorials and examples

View Tutorials

Get Started

Find resources and how to start using pypose

View Resources