Tube MPC design - holaza/mptplus GitHub Wiki

MPTplus enables, by default, the rigid Tube MPC design according to: Mayne et al., Automatica (2005): Robust model predictive control of constrained linear systems with bounded disturbances. The tube is constructed according to: S. V. Rakovic et al., IEEE Transactions on Automatic Control (2005): Invariant approximations of the minimal robust positively Invariant set.

Note: MPTplus enables also the implicit Tube MPC design according to: Rakovic, Automatica (2023): The implicit rigid tube model predictive control. The implicit formulation of Tube MPC design enables handling of the large-scale systems, see Implicit Tube MPC design.

Construction and evaluation of Tube MPC controller

Example on how to construct and evaluate Tube MPC controller:

Demo:

%% TUBE MPC DESIGN
% LTI system
model = ULTISystem('A', [1, 1; 0, 1], 'B', [0.5; 1], 'E', [1, 0; 0, 1]);
model.u.min = [-1];
model.u.max = [ 1];
model.x.min = [-200; -2]; 
model.x.max = [ 200;  2];
model.d.min = [-0.1; -0.1]; 
model.d.max = [ 0.1;  0.1];
% Penalty functions
model.x.penalty = QuadFunction(diag([1, 1]));
model.u.penalty = QuadFunction(diag([0.01]));
% Prediction horizon
N = 9;
option = {'soltype',1,'LQRstability',1}
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% TMPC evaluation
x0 = [ -5; -2 ]; % Initial condition
u_implicit = iMPC.evaluate(x0) % Implicit MPC evaluation
u_explicit = eMPC.evaluate(x0)  % Explicit MPC evaluation
[ u, feasible ] = iMPC.evaluate(x0) % Feasibility check
[ u, feasible ] = eMPC.evaluate(x0) % Feasibility check

Note: If the value of the parameter LQRstability is set to 0, then no terminal penalty and terminal set are automatically computed. The user is expected to set his/her own terminal penalty and terminal set or remain empty.

Warning: The current version of MPTplus always displays for explicit Tube MPC controller confusing information on the prediction horizon _N_=1, although the controller is constructed correctly for any value of N.

How to evaluate the closed-loop simulation of control

For the given uncertain LTI model and prediction horizon N, the closed-loop simulation of the Tube MPC controller is evaluated by:

% Closed-loop simulation
Nsim = 12; % Number of simulation steps
implicit_loop = ClosedLoop(iMPC, model)
explicit_loop = ClosedLoop(eMPC, model)
ClosedLoopData = iMPC.simulate(x0, Nsim) % Implicit Tube MPC
% ClosedLoopData = eMPC.simulate(x0, Nsim) % Explicit Tube MPC
figure(1),hold on, box on, grid on, xlabel('Control steps k'), ylabel('System states x(k)')
stairs([0,Nsim],[0;0],'k--')
stairs([0:Nsim],ClosedLoopData.X(1,:))
stairs([0:Nsim],ClosedLoopData.X(2,:))
figure(2),hold on, box on, grid on, xlabel('Control steps k'), ylabel('Control inputs u(k)')
stairs([0:Nsim-1],ClosedLoopData.U(1,:))

Figure: Closed-loop Tube MPC

%% FIGURE: Closed-loop Tube MPC
figure(1)
% System state x1
subplot(3,1,1), hold on, box on, grid on 
xlabel('Control steps k'), ylabel('System state x_1(k)'), title('Closed-loop Tube MPC')
stairs([0:Nsim],ClosedLoopData.X(1,:))
stairs([0,Nsim],[0;0],'k:')
legend('x_1','Location','SouthEast')
axis([0, Nsim, -7.5, 0.5])
% System state x2
subplot(3,1,2), hold on, box on, grid on 
xlabel('Control steps k'), ylabel('System state x_2(k)')
stairs([0:Nsim],ClosedLoopData.X(2,:))
stairs([0,Nsim],[model.x.min(2);model.x.min(2)],'k--')
stairs([0,Nsim],[model.x.max(2);model.x.max(2)],'k-.')
stairs([0,Nsim],[0;0],'k:')
legend('x_2','x_{2,min}','x_{2,max}','Location','Best')
axis([0, Nsim, model.x.min(2)-0.5, model.x.max(2)+0.5])
% Control inputs u
subplot(3,1,3), hold on, box on, grid on 
xlabel('Control steps k'), ylabel('Control inputs u(k)')
stairs([0:Nsim-1],ClosedLoopData.U(1,:))
stairs([0,Nsim-1],[model.u.min;model.u.min],'k--')
stairs([0,Nsim-1],[model.u.max;model.u.max],'k-.')
legend('u','u_{min}','u_{max}','Location','SouthWest')
axis([0, Nsim-1, model.u.min-0.1, model.u.max+0.1])

How to construct an explicit Tube MPC controller

For the given uncertain LTI model and prediction horizon N, enable/disable (potentially time-consuming) construction of the explicit Tube MPC controller by:

% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% TMPC evaluation
x0 = [-5; -2]; % Initial condition
u = eMPC.evaluate(x0)  % Explicit MPC evaluation

How to get the tube and the associated sets

For the given uncertain LTI model and prediction horizon N, get (approximated) minimum robust positive invariant set (the tube), sets of the conservative state and input constraints, and plot them (if applicable):

% TMPC controller construction
iMPC = TMPCController(model,N);
% Tube 
Tube = iMPC.TMPCparams.Tube
figure, Tube.plot()
% State constraints
Xconservative = iMPC.TMPCparams.Px_robust
figure, Xconservative.plot()
% Input constraints
Uconservative = iMPC.TMPCparams.Pu_robust
figure, Uconservative.plot()
% Disturbances
Wset = iMPC.TMPCparams.Pw
figure, Wset.plot()

Figure: Tube MPC design sets

%% FIGURE: Tube MPC design sets
figure(1)
% System states
subplot(2,2,1), hold on, box on, grid on 
xlabel('System state x_1'), ylabel('System state x_2'), title('System states X')
Xconservative.plot('Color',[0, 0.6, 0.6])
plot(0,0,'kx','MarkerSize',5) % origin
% Control input
subplot(2,2,2), hold on, box on, grid on 
xlabel('Control inputstate u'), ylabel('[--]'), title('Control input U')
Uconservative.plot('Color',[0, 0.6, 0.6])
plot(0,0,'kx','MarkerSize',5) % origin
% Disturbances
subplot(2,2,3), hold on, box on, grid on 
xlabel('Disturbance d_1'), ylabel('Disturbance d_2'), title('Disturbances')
Wset.plot('Color',[0, 0.6, 0.6])
plot(0,0,'kx','MarkerSize',5) % origin
% Tube
subplot(2,2,4), hold on, box on, grid on 
xlabel('System state x_1'), ylabel('System state x_2'), title('Tube')
Tube.plot('Color',[0, 0.6, 0.6])
plot(0,0,'kx','MarkerSize',5) % origin

How to get the internal feedback controller and the associated terminal penalty and terminal set

For the given uncertain LTI model and prediction horizon N, get the internal feedback (discrete-time LQ-optimal) controller, corresponding terminal penalty (Lyapunov) matrix, and the associated terminal set, and plot them (if applicable):

% TMPC controller construction
option = {'LQRstability',1, 'solType',1};
iMPC = TMPCController(model,N,option)
% K: u(0) = u_opt + K*( x(0) - x_opt )
K = iMPC.TMPCparams.K
% Terminal penalty: P > 0
P = iMPC.model.x.terminalPenalty.weight
% Terminal set: X_N
X_N = iMPC.model.x.terminalSet
figure, X_N.plot()

Figure: Closed-loop Tube MPC

%% FIGURE: Terminal set
figure(1), hold on, box on, grid on 
xlabel('System state x_1'), ylabel('System state x_2'), title('Terminal set X_N')
X_N.plot('Color',[0, 0.6, 0.6]) % Terminal set
plot(0,0,'kx','MarkerSize',5) % origin

How to return the particular variables of the feedback control law

For given feedback control law: u(0) = u_opt + K*( x(0) - x_opt ) , switch between returning the compact control input u(0) and the vector of the particular variables u_opt and x_opt using the option solType - {0/1}. For the given uncertain LTI model and prediction horizon N, evaluate the vector of the particular variables u_opt and x_opt:

% Setup for expanded control input 
option = {'solType',0}
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% TMPC evaluation of expanded control input
x0 = [-5; -2]; % Initial condition
[ ux_implicit, feasible, implicit_openloop ] = iMPC.evaluate(x0) % Enriched output
[ ux_explicit, feasible, explicit_openloop ] = eMPC.evaluate(x0) % Enriched output

Evaluation of the compact control input u(0):

% Setup for compact control input 
option = {'solType',1}
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% TMPC evaluation of compact control input
x0 = [-5; -2]; % Initial condition
ux_implicit = iMPC.evaluate(x0) % Implicit MPC evaluation
ux_explicit = eMPC.evaluate(x0) % Explicit MPC evaluation

Closed-loop Tube MPC control using the particular variables of the feedback control law

Example on how to construct and evaluate Tube MPC controller using the particular variables of the feedback control law:

% Closed-loop simulation for solType == 0
% LTI system
model = ULTISystem('A', [1, 1; 0, 1], 'B', [0.5; 1], 'E', [1, 0; 0, 1]);
model.u.min = [-1];
model.u.max = [ 1];
model.x.min = [-200; -2]; 
model.x.max = [ 200;  2];
model.d.min = [-0.1; -0.1]; 
model.d.max = [ 0.1;  0.1];
% Penalty functions
model.x.penalty = QuadFunction(diag([1, 1]));
model.u.penalty = QuadFunction(diag([0.01]));
% Prediction horizon
N = 9;
% Include the LQR-based terminal penalty and set for compact control law
option = {'LQRstability',1, 'solType',0};
% Construct Tube MPC controller
iMPC_expanded = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC_expanded = iMPC_expanded.toExplicit
% TMPC evaluation
x0 = [ -5; -2 ]; % Initial condition
Nsim = 12; % Number of simulation steps
implicit_loop = ClosedLoop(iMPC_expanded, model)
% explicit_loop = ClosedLoop(eMPC_expanded, model) % TODO: DOES NOT WORK
ClosedLoopData = iMPC_expanded.simulate(x0, Nsim) % Implicit Tube MPC
% ClosedLoopData = eMPC_expanded.simulate(x0, Nsim) % Explicit Tube MPC
for k = 1 : Nsim, w(:,k) = iMPC_expanded.TMPCparams.Pw.randomPoint; end % Fixed sequence of disturbances
ClosedLoopData = iMPC_expanded.simulate(x0, Nsim, w) % Implicit Tube MPC
% ClosedLoopData = eMPC_expanded.simulate(x0, Nsim, w) % Explicit Tube MPC
figure(1),hold on, box on, grid on, xlabel('k'), ylabel('System states x(k)')
stairs([0:Nsim],ClosedLoopData.X(1,:))
stairs([0:Nsim],ClosedLoopData.X(2,:))
stairs([0,Nsim],[0;0],'k--')
figure(2),hold on, box on, grid on, xlabel('k'), ylabel('Control inputs u(k)')
stairs([0:Nsim-1],ClosedLoopData.U(1,:))

Figure: Closed-loop Tube MPC design sets

%% FIGURE: Closed-loop Tube MPC design sets
figure(1), hold on, box on, title('Closed-loop Tube MPC'), xlabel('x_1'), ylabel('x_2')
plot(ClosedLoopData.Xnominal(1,:),ClosedLoopData.Xnominal(2,:),'kx:','LineWidth', 2, 'MarkerSize', 6)
plot(ClosedLoopData.X(1,:),ClosedLoopData.X(2,:),'k*--','LineWidth', 2, 'MarkerSize', 6)
plot( iMPC_expanded.model.x.terminalSet, 'Color',[0, 0.6, 0.6] )
for k = 2 : size(ClosedLoopData.Xnominal,2)
    plot( iMPC_expanded.TMPCparams.Tube + [ ClosedLoopData.Xnominal(:,k) ], 'Color',[0, 0.8, 0.6] )
end
plot(ClosedLoopData.Xnominal(1,:),ClosedLoopData.Xnominal(2,:),'kx:','LineWidth', 2, 'MarkerSize', 6)
plot(ClosedLoopData.X(1,:),ClosedLoopData.X(2,:),'k*--','LineWidth', 2, 'MarkerSize', 6)
legend('nominal states','uncertain states','terminal set','tube')

How to plot the partition, PWA feedback law, and PWQ cost function of the explicit Tube MPC controller

For the given uncertain LTI model and prediction horizon N, plot, if applicable, the partition (explicit solution map/domain of the optimization problem), PWA feedback law, and PWQ cost function of the explicit Tube MPC controller run:

% Control law setup
option = {'solType',1};   % enable/comment for compact control input 
% option = {'solType',0}; % enable/comment for expanded control input 
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% Show figures
figure, eMPC.partition.plot()
figure, eMPC.feedback.fplot()
figure, eMPC.cost.fplot()

Figure: Closed-loop Tube MPC

%% FIGURE: Explicit partition 
figure(1), hold on, box on, grid on
% eMPC.partition.plot('Color',[0, 0.6, 0.6])
xlabel('System state x_1'), ylabel('System state x_2'), title('Explicit partition')
plot(0,0,'kx','MarkerSize',5) % origin
eMPC.partition.plot('Color',[0, 0.6, 0.6])

Figure: Closed-loop Tube MPC

%% FIGURE: Explicit feedback law
figure(2), hold on, box on, grid on
xlabel('System state x_1'), ylabel('System state x_2')
zlabel('Control action u'), title('Feedback law')
plot(0,0,'kx','MarkerSize',5) % origin
eMPC.feedback.fplot('Color',[0, 0.6, 0.6])

Figure: Closed-loop Tube MPC

%% FIGURE: Cost function
figure(3), hold on, box on, grid on
xlabel('System state x_1'), ylabel('System state x_2')
zlabel('Cost J'), title('Cost function')
eMPC.cost.fplot('Color',[0, 0.6, 0.6])

Note, the returned output feedback differs in the case of the compact (u) and in the case of the expanded vector of the control inputs (u_opt,x_opt) determined by the value of option solType - {0/1}. The returned partition does not differ in the case of the compact (u) and in the case of the expanded vector of the control inputs (u_opt,x_opt) determined by the value of option solType - {0/1}.

Warning: the PWQ cost function is always computed (and plotted) subject to the original decision variables of the optimization problem (i.e., the expanded control inputs: u_opt, x_opt) regardless of the setting of the parameter solType.

How to simplify constructed explicit Tube MPC controller without optimality loss

The constructed explicit Tube MPC controller can be reduced without optimality loss using the Optimal region merging (ORM) method and the Separation-based method. For the given uncertain LTI model and prediction horizon N, apply the Optimal region merging method running:

% Setup for explicit compact control input 
option = {'solType',1}
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% Complexity reduction by Optimal region merging method
eMPCsimple = eMPC.simplify('orm')
% Number of critical regions
Nr_original = eMPC.nr
Nr_reduced = eMPCsimple.nr

The separation-based method targets to reduce the complexity by removing all critical regions that lead to saturated control laws. Next, a separation filter is constructed to identify optimal control actions above the removed critical regions. For the given uncertain LTI model and prediction horizon N, apply the Separation-based method by running:

% Setup for explicit compact control input 
option = {'solType',1}
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit
% Complexity reduction using a Separation-based method
eMPCsimple = eMPC.simplify('separation')
% Number of critical regions
Nr_original = eMPC.nr
Nr_reduced = eMPCsimple.nr

Note: check LowCom on how works the functions orm and simplify, or read more at IEEEXPLORE.

How to change the advanced settings of the tube construction

For the given uncertain LTI model and prediction horizon N, adopt the advanced settings of the tube construction using the parameters: Tube_tol - allowed tolerance for the convergence (default = 1e-4), Tube_MaxIter - maximal number of iterations (default = 1e3) by running:

% Setup for advanced configuration of the Tube construction
option = {'Tube_tol',1e-3, 'Tube_MaxIter', 100}
% TMPC controller construction
iMPC = TMPCController(model,N,option)
% Show Tube
Tube = iMPC.TMPCparams.Tube
figure, Tube.plot()

Example on how to construct and evaluate Tube MPC controller with delta-u constraints:

It is also possible to include so-called delta-u constraints, i.e., the constraints bounding the limits on a rate of control actions. This can be implemented by activating the deltaMin and deltaMax filters:

model = ULTISystem('A', [1, 1; 0, 1], 'B', [0.5; 1], 'E', [1, 0; 0, 1]);
model.d.min = [-0.1; -0.1]; 
model.d.max = [ 0.1;  0.1];
model.x.min = [-200; -2]; 
model.x.max = [ 200;  2];
model.u.min = [-1];
model.u.max = [ 1];
model.u.with('deltaMin');
model.u.with('deltaMax');
model.u.deltaMin = -.5;
model.u.deltaMax = .5;
% Penalty functions
model.x.penalty = QuadFunction(diag([1, 1]));
model.u.penalty = QuadFunction(diag([0.01]));
% Prediction horizon
N = 2;
option = {'solType',1,'LQRstability',1};   % enable/comment for compact control input 
% option = {'solType',0,'LQRstability',1}; % enable/comment for expanded control input 
iMPC = TMPCController(model,N,option);
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit;
% TMPC evaluation
x0 = [1; -1];
u_prev = 0;
[u, feasible] = iMPC.evaluate(x0,'u.previous', u_prev) % Feasibility check
[u, feasible] = eMPC.evaluate(x0,'u.previous', u_prev) % Feasibility check

Example on how to show indexed partition:

It is also possible to depict the indices of individual critical regions (for more details see: help depictIndices):

Demo:

model = ULTISystem('A', [1, 1; 0, 1], 'B', [0.5; 1], 'E', [1, 0; 0, 1]);
model.u.min = [-1];
model.u.max = [ 1];
model.x.min = [-200; -2]; 
model.x.max = [ 200;  2];
model.d.min = [-0.1; -0.1]; 
model.d.max = [ 0.1;  0.1];
% Penalty functions
model.x.penalty = QuadFunction(diag([1, 1]));
model.u.penalty = QuadFunction(diag([0.01]));
% Prediction horizon
N = 2;
option = {'soltype',1,'LQRstability',1};
iMPC = TMPCController(model,N,option);
% Explicit TMPC controller construction
eMPC = iMPC.toExplicit;
% Depict indices
figure, eMPC.indexPartition
figure, hold on, eMPC.partition.plot, depictIndices(eMPC, [1 : 10 : 150])
figure, eMPC.partition.plot, depictIndices(eMPC, [1,50,100,120], gcf)
figure, hold on
eMPC.partition.Set(1).plot, eMPC.partition.Set(3).plot, eMPC.partition.Set(5).plot
depictIndices(eMPC, [1,3,5], gcf)