A basic MPC problem

The code generation described in this section basically consist of the following steps:

  1. write the system module with the MPC problem description,
  2. create a muaompc object out of that problem, and
  3. write the C-code from that object.

The MPC problem description

The simplest problem that can be setup with the ltidt module is an input constrained problem. The code for this example can be found inside the tutorial directory muaompc_root/muaompc/_ltidt/tutorial, where muaompc_root is the path to the root directory where muaompc sources were extracted.

The system description

We consider as system a DC-motor, which can be modeled as:

\ddot{y} = \frac{1}{T} (Ku - \dot{y})

where T is the time constant in seconds, and K is amplification factor. The continuous-time state-space representation \dot{x} = A_c x + B_c u is given by the following matrices:

A_c = \left[ \begin{matrix}
0 & 1 \\
0 & -\frac{1}{T} \\
\end{matrix} \right], \;\;
B_c = \left[ \begin{matrix}
0 \\ \frac{K}{T} \\
\end{matrix} \right]

with the state vector x = [x_1 \; x_2]^T, where x_1 and x_2 are the rotor position and angular speed, respectively. The input is the PWM voltage, which is the percentage of the full-scale voltage applied to the motor. It is therefore constrained to be between -100% and 100%. This constraint can be written as -100 \leq u \leq 100.

As the continuous-time system should be controlled by the MPC digital controller, a suitable discretization time must be chosen. A rule of thumb is to choose the discretization time as one-tenth of the system’s time constant. In this case, dt = \frac{T}{10}.

Note: to discretize a system, SciPy needs to be installed.

The controller parameters

The horizon length is specified as steps through the parameter N. In this case we choose the value N=10. The additional parameters for the controller are the weighting matrices. They are usually chosen via a tuning procedure. For this example, we set them to be identity matrices of appropriate size, i.e. Q = I \in \mathbb{R}^{2
\times 2}, and R = 1. Additionally we set P as "auto", which will compute it as a stabilizing matrix.

Note: to use the “auto” feature, Slycot needs to be installed.

The system module

We have now the required information to write the Python system module. The only requirements are that it should contain valid Python syntax, the name of the matrices should be as described in section The system module, and the file name should end with (the extension) .py. In your favorite text editor, type the following (note that in Python tabs and spaces at the beginning of a line do matter, see A short Python tutorial):

T = 0.1
K = 0.2
dt = T / 10
N = 10
# continuous time system
Ac = [[0, 1], [0, -1/T]]
Bc = [[0], [K/T]]
# input constraints
u_lb = [[-100]]
u_ub = [[100]]
# weighting matrices
Q = [[1, 0], [0, 1]]
R = [[1]]
P = "auto"

Save the file as sys_motor.py.

Generating the C-code

Now that we have written the sys_motor.py module, we proceed to create an mpc object. In the directory containing sys_motor.py, launch your Python interpreter and in it type:

import muaompc

mpc = muaompc.ltidt.setup_mpc_problem("sys_motor")
mpc.generate_c_files()

And that’s it! If everything went allright, you should now see inside current directory a new directory called cmpc. As an alternative to typing the above code, you can execute the file main_motor.py found in the tutorial directory, which contains exactly that code. The tutorial directory already contains the sys_motor.py example. In the next section, you will learn how to use the generated C code.

Tip

If the code generation was not succesful, try passing the verbose=True input parameter to the function setup_mpc_problem. It will print extra information about the code generation procedure. For example:

mpc = muaompc.ltidt.setup_mpc_problem("sys_motor", verbose=True)

Tip

By default, the generated code uses double precision float (64-bit) for all computations. You can specify a different numeric representation via the input parameter numeric of the function generate_c_files. For example, to use single precision (32-bit) floating point numbers type:

mpc.generate_c_files(numeric="float32")

Using the generated C-code

In the cmpc directory you will find all the automatically generated code for the current example. Included is also an example Makefile, which compiles the generated code into a library using the GNU Compiler Collection (gcc). Adapt the Makefile to your compiler if necessary.

We now proceed to make use of the generated code. Let’s create a main_motor.c in the current directory (i.e. one level above the cmpc directory). The first thing to include is the header file of the library, which is found under cmpc/include/mpc.h. Before we continue, there are a few things to note first. The mpc.h header makes available to the programmer some helpful constants, for example: MPC_STATES is the number of states, MPC_INPUTS is the number of inputs (all the available constants are found in cmpc/include/mpc_const.h). This helps us easily define all variables with the appropriate size. Additionally, cmpc/include/mpc_base.h includes the type definition real_t, which is the type for all numeric operations of the algorithm. It is then easy to switch the numerical type of the entire algorithm (for example, from single precision floating-point to double precision). For this example, it is by default set to double precision floating point (64-bit). With this in mind, we can declare a state vector as real_t x[MPC_STATES]; inside our main function.

We need to have access to some of the algorithm’s variables, for example the MPC system input and the algorithm settings. This is done through the fields of the struct mpc_ctl structure (declared in mpc_base.h). An instance of this structure has been automatically defined and named ctl. To access it in our program, we need to declare it inside our main function as extern struct mpc_ctl ctl;.

The next step is to configure the algorithm. In this case, we have an input constrained case. The only parameter to configure is the number of iterations of the algorithm. For this simple case, let’s set it to 10 iterations, by setting ctl.conf->in_iter = 10; (See section Basics of tuning for details).

Let us assume that the current state is x = [0.1 \; -0.5]^T. We can finally solve our MPC problem for this state by calling mpc_ctl_solve_problem(&ctl, x);. The solution is stored in an array of size MPC_HOR_INPUTS (the horizon length times the number of inputs) pointed by ctl.u_opt. We can get access to its first element using array notation, e.g. ctl.u_opt[0]. The complete example code looks like:

#include <stdio.h>  /* printf */
#include "cmpc/include/mpc.h"  /* the auto-generated code */

/* This file is a test of the C routines of the ALM+FGM MPC
 * algorithm. The same routines can be used in real systems.
 */
int main(void)
{
  real_t x[MPC_STATES];  /* current state of the system */
  extern struct mpc_ctl ctl;  /* already defined */

  ctl.conf->in_iter = 10;  /* number of iterations */

  /* The current state */
  x[0] = 0.1;
  x[1] = -0.5;

  /* Solve MPC problem and print the first element of input sequence */
  mpc_ctl_solve_problem(&ctl, x);  /* solve the MPC problem */
  printf("u[0] = %f \n", ctl.u_opt[0]);
  printf("\n SUCCESS! \n");

  return 0;
}

In the tutorial directory you will find, among others, a main_motor.c file with the code above, together with a Makefile. Compile the code by typing make motor (you might need to modify the provided Makefile or create your own). If compilation was successful, you should see a new executable file called motor. If you run it, the word SUCCESS! should be visible at the end of the text displayed in the console.

Warning

Everytime you auto generate the C files, the whole cmpc directory is deleted. For precaution, DO NOT save in this directory any important file.

Testing with Python

The Python interface presents the user with almost the same functionality as the generated code. However, Python’s simpler syntax and powerful scientific libraries makes it an excellent platform for prototyping.

Let’s compare it to the pure C implementation. Just like in the C tutorial, change to the tutorial directory, launch your Python interpreter, and in it type:

import muaompc
import numpy as np

mpc = muaompc.ltidt.setup_mpc_problem("sys_motor")

The mpc object contains many methods and data structures that will help you test your controller before implementing it in C. We’ve already learned about the method generate_c_files. The Python interface to the MPC controller will be set up automatically when you access the ctl attribute of your mpc object, without the need to compile anything. Thus, we can do exactly the same as in the C-code above with a simpler Python syntax. Continue typing in the Python interpreter the following:

ctl = mpc.ctl
ctl.conf.in_iter = 10
x = np.matrix([[0.1], [-0.5]])
ctl.solve_problem(x)
print(ctl.u_opt[0])
print("SUCCESS!")

Compare with the C code above.