Creating MPC controllers

This section will explain in detail the generation of MPC controllers for a given MPC setup.

The MPC setup

The plant to be controlled is described by x^+ = A_d x + B_d u, where x \in \mathcal{C}_x \subseteq \mathbb{R}^n, and u \in \mathcal{C}_u \subset \mathbb{R}^m are the current state and input vector, respectively. The the state at the next sampling time is denoted by x^+. The discrete-time system and input matrices are denoted as A_d and B_d, respectively.

The MPC setup is as follows:

\underset{u}{\text{minimize}} & \;\; 
\frac{1}{2} \sum\limits_{j=0}^{N-1} ((x_j - x\_ref_j)^T Q (x_j - x\_ref_j) + \\
& (u_j - u\_ref_j)^T R (u_j - u\_ref_j)) + \\
& \frac{1}{2} (x_{N} - x\_ref_N)^{T} P (x_{N} - x\_ref_N) \\
\text{subject to} 
& \;\; x_{j+1}=A_d x_j + B_d u_j, \;\; j = 0, \cdots, N-1 \\
& \;\; u\_lb \leq u_j \leq u\_ub, \;\; j = 0, \cdots, N-1   \\
& \;\; e\_lb \leq K_{x} x_j + K_{u} u_j \leq e\_ub, \;\; j  = 0, \cdots, N-1 \\
& \;\; f\_lb \leq F x_N \leq f\_ub \\
& \;\; x_0 = x \\

where the integer N \geq 2 is the prediction horizon. The symmetric matrices Q, R, and P are the state, input, and final state weighting matrices, respectively. The inputs are constrained by a box set, defined by the lower and upper bound u\_lb and u\_ub, respectively. Furthermore, the state and input vectors are also constrained (mixed constraints), using K_{x} and K_{u}, and delimited by the lower and upper bounds e\_lb and e\_ub \in
\mathbb{R}^q, respectively. Additionally, the terminal state needs to satisfy some constraints defined by f\_lb, f\_ub \in \mathbb{R}^r, and the matrix F.

The sequences x\_ref and u\_ref denote the state and input references, respectively. They are specified online. By default, the reference is the origin.

The system module

The matrices describing the MPC setup are read from the system module. It basically contains the matrices that describe the MPC setup.

  • The system matrices can be given either in discrete or continuous time.

    • In the first case, they must be called Ac and Bc, respectively (in this case SciPy is required).
    • In the discrete-time case, they must be called Ad and Bd, respectively.
    • The zero-order hold discretization time should be specified as dt in both cases.
  • The state and input weighting matrices Q and R must be called Q and R, respectively.

  • The terminal weight matrix P is called P. It can be declared as "auto", in which case it will be computed as a stabilizing matrix (the Python package Slycot is required).

  • The lower and upper input constraints bounds u\_lb, u\_ub are called u_lb and u_ub, respectively.

  • The MPC horizon length N represents steps (not time) and is an integer greater than one called N.

Additionally, for a state constrained problem, the following are required:

  • Mixed constraints

    • The lower and upper mixed constraints bounds e\_lb, e\_ub \in \mathbb{R}^{q} should be called e_lb, and e_ub, respectively.
    • K_x, must be called Kx.
    • K_u, is optional and is called Ku. If not specified (or None), it is set to a zero matrix of appropriate size.

If any of e_lb, e_ub, or Kx is not specified (or None), then the MPC setup is considered to be without state constraints.

  • Terminal state constraints are optional:

    • The terminal state bounds f\_lb, f\_ub \in \mathbb{R}^{q}, are called f_lb, and f_ub, respectively.
    • F, the terminal state constraint matrix, must be called F.
    • If any of F, f_lb, or f_ub is not specified (or None), each of them is set to Kx, e_lb, and e_ub, respectively.
  • The penalty parameter \mu of the augmented Lagrangian method is optional. If specified, it must be called mu, and must be a positive real number. If not specified (or None), it is computed automatically (recommended).

All matrices are accepted as Python lists of lists, or as numpy arrays, or numpy matrices. The system module can also be written as a MATLAB mat file containing the required matrices using the names above.

For example, an input-constrained second-order continuous-time LTI system could be described by the following system.py Python module:

Ac = [[0, 1], [-1, -1]]
Bc = [[0], [1]]
dt = 0.5
N = 10
Q = [[1, 0], [0, 1]]
R = [[1]]
P = Q
u_lb = [[-10]]
u_ub = [[10]]

Creating a Python MPC object

The following function creates the MPC object for the system module. This function belongs to the ltidt module.

ltidt.setup_mpc_problem(system_name, verbose=False)

Create an MPC object from a given system module.

Parameters:
  • system_name (a string or a Python module) –

    a string with the name of a Python module containing the system description, e.g. for a system.py, system_name="system", or system_name="system.py". It can also be the name of a MATLAB mat file. In that case, the file name must end with the extension .mat, e.g. for a system.mat the parameter is given as system_name="system.mat"

    Alternatively, a Python module can be given as input. For example, if you import system, then system_name=system.

  • verbose (bool) – if True, print on-screen information about the problem.
Returns:

an instance of the appropriate MPC class according to the given system module.

For example, assuming system1.py and system2.mat both contain exactly the same MPC setup, we can write:

import muaompc
mpcx = muaompc.ltidt.setup_mpc_problem("system1")  # short way
mpcy = muaompc.ltidt.setup_mpc_problem("system1.py", verbose=True)
mpcz = muaompc.ltidt.setup_mpc_problem("system2.mat")  # MATLAB way
# The three objects, mpcx, mpcy, and mpcz contain the same information

Additionally, you can quickly create setups that differ only slighlty between them:

from muaompc.ltidt import setup_mpc_problem
import system

system.N = 10  # set horizon length to 10 steps
mpcx = setup_mpc_problem(system)  # system is a module, not a string
system.N = 5  # same setup but with a shorter horizon
mpcy = setup_mpc_problem(system)  #  mpcx is not the same as mpcy

Generating the C code

The following function is available for all MPC objects, and generates C-code from the MPC object data.

_MPCBase.generate_c_files(numeric='float64', fracbits=None, matlab=False, singledir=False)

Write, in the current path, C code for the current MPC problem.

Parameters:
  • numeric (string) –

    indicates the numeric representation of the C variables, valid strings are:

    • "float64": double precision floating point (64 bits)
    • "float32": single precision floating point (32 bits)
    • "accum": fixed-point data type of the C extension to support embedded processors (signed 32 bits). Your compiler must support the extension.
    • "fip": (EXPERIMENTAL) fixed-point (signed 32 bits).
  • fracbits (integer or None) – an integer greater than 0 that indicates the number of fractional bits of fixed-point representation. (EXPERIMENTAL) Only required if numeric is “fip”.
  • matlab (bool) – if True, generate code for MATLAB/Simulink interfaces.
  • singledir (bool) – if True, all generated code is saved in a single directory. Useful for example for Arduino microcontrollers.

For example, assuming that system.py contains a valid MPC setup, and we want to generate code appropriate for a microcontroller to be programmed via Simulink:

import muaompc
mpc = muaompc.ltidt.setup_mpc_problem("system")
mpc.generate_c_files(numeric="float32", matlab=True)
# you will find the generated C code in the current directory

The next section will show you how to use the generated code.