MPC Algorithm#
Introduction#
Model Predictive Control (MPC) is a control method that solves an optimization problem during each control cycle to determine an optimal control sequence based on a given vehicle model. The calculated sequence of control inputs is used to control the system.
In simpler terms, an MPC controller calculates a series of control inputs that optimize the state and output trajectories to achieve the desired behavior. The key characteristics of an MPC control system can be summarized as follows:
- Prediction of Future Trajectories: MPC computes a control sequence by predicting the future state and output trajectories. The first control input is applied to the system, and this process repeats in a receding horizon manner at each control cycle.
- Handling of Constraints: MPC is capable of handling constraints on the state and input variables during the optimization phase. This ensures that the system operates within specified limits.
- Handling of Complex Dynamics: MPC algorithms can handle complex dynamics, whether they are linear or nonlinear in nature.
The choice between a linear or nonlinear model or constraint equation depends on the specific formulation of the MPC problem. If any nonlinear expressions are present in the motion equation or constraints, the optimization problem becomes nonlinear. In the following sections, we provide a step-by-step explanation of how linear and nonlinear optimization problems are solved within the MPC framework. Note that in this documentation, we utilize the linearization method to accommodate the nonlinear model.
Linear MPC formulation#
Formulate as an optimization problem#
This section provides an explanation of MPC specifically for linear systems. In the following section, it also demonstrates the formulation of a vehicle path following problem as an application.
In the linear MPC formulation, all motion and constraint expressions are linear. For the path following problem, let's assume that the system's motion can be described by a set of equations, denoted as (1). The state evolution and measurements are presented in a discrete state space format, where matrices
Equation (1) represents the state-space equation, where
It's worth noting that another advantage of MPC is its ability to effectively handle the disturbance term
The state transition and measurement equations in (1) are iterative, moving from time
For simplicity, let's assume the initial state is
To begin, we can compute the state
Then, when
When
If
Putting all of them together with (2) to (5) yields the following matrix equation;
In this case, the measurements (outputs) become;
We can combine equations (6) and (7) into the following form:
This form is similar to the original state-space equations (1), but it introduces new matrices: the state transition matrix
Now that
The next step is to define a cost function. The cost function generally uses the following quadratic form;
where
This cost function is the same as that of the LQR controller. The first term of
Note: in some cases,
As the resulting trajectory output is now
Substituting equation (8) into equation (9) and tidying up the equation for
This equation is a quadratic form of
The coefficient matrix of the quadratic term of
Apply to vehicle path-following problem (nonlinear problem)#
Because the path-following problem with a kinematic vehicle model is nonlinear, we cannot directly use the linear MPC methods described in the preceding section. There are several ways to deal with a nonlinearity such as using the nonlinear optimization solver. Here, the linearization is applied to the nonlinear vehicle model along the reference trajectory, and consequently, the nonlinear model is converted into a linear time-varying model.
For a nonlinear kinematic vehicle model, the discrete-time update equations are as follows:
The vehicle reference is the center of the rear axle and all states are measured at this point. The states, parameters, and control variables are shown in the following table.
Symbol | Represent |
---|---|
Vehicle speed measured at the center of rear axle | |
Yaw (heading angle) in global coordinate system | |
Vehicle steering angle | |
Vehicle target steering angle | |
Vehicle wheelbase (distance between the rear and front axles) | |
Time constant for the first order steering dynamics |
We assume in this example that the MPC only generates the steering control, and the trajectory generator gives the vehicle speed along the trajectory.
The kinematic vehicle model discrete update equations contain trigonometric functions; sin and cos, and the vehicle coordinates
We make small angle assumptions for the following derivations of linear equations. Given the nonlinear dynamics and omitting the longitudinal coordinate
Where
There are three expressions in the update equations that are subject to linear approximation: the lateral deviation (or lateral coordinate)
In the path tracking problem, the curvature of the trajectory
When the vehicle is turning a path, its steer angle
Substituting this equation into equation (12), and approximate
Using this,
Finally, the linearized time-varying model equation becomes;
This equation has the same form as equation (1) of the linear MPC assumption, but the matrices
Comparing equation (1),
Using this equation, write down the update equation likewise (2) ~ (6)
As it has the same form as equation (6), convex optimization is applicable for as much as the model in the former section.
The cost functions and constraints#
In this section, we give the details on how to set up the cost function and constraint conditions.
The cost function#
Weight for error and input#
MPC states and control weights appear in the cost function in a similar way as LQR (9). In the vehicle path following the problem described above, if C is the unit matrix, the output
As an example, let's determine the weight matrix
The first term in the cost function (9) with
This shows that
Weight for non-diagonal term#
MPC can handle the non-diagonal term in its calculation (as long as the resulting matrix is positive definite).
For instance, write
Expanding the first term of the evaluation function using
The value of
Since the weight matrix can be added linearly, the final weight can be set as
Furthermore, MPC optimizes over a period of time, the time-varying weight can be considered in the optimization.
Constraints#
Input constraint#
The main advantage of MPC controllers is the capability to deal with any state or input constraints. The constraints can be expressed as box constraints, such as "the tire angle must be within ±30 degrees", and can be put in the following form;
The constraints must be linear and convex in the linear MPC applications.
Constraints on the derivative of the input#
We can also put constraints on the input deviations. As the derivative of steering angle is
We discretize
Along the prediction or control horizon, i.e for setting
and aligning the inequality signs
We can obtain a matrix expression for the resulting constraint equation in the form of
Thus, putting this inequality to fit the form above, the constraints against