Workflow of ParNMPC
Preparation
- Choose a compiler that supports code generation with OpenMP by
mex -setup
. - Edit
Timer.m
to specify your own timer function.
NMPC Problem Formulation
Example
./NMPC_Problem_Definition.m
-
Formulate an OCP using Class
OptimalControlProblem
% Create an OptimalControlProblem object OCP = OptimalControlProblem(dim.u,... % inputs dim dim.x,... % states dim dim.p,... % parameters dim N); % num of discretization grids % Give names to x, u, p (optional) [~] = OCP.setStateName(~); [~] = OCP.setInputName(~); [~] = OCP.setParameterName(~); % Set the prediction horizon T OCP.setT(~); % Set the dynamic function f OCP.setf(~); % Set the matrix M (optional for, e.g., Lagrange model) OCP.setM(~); % Set the equality constraint function C (optional) OCP.setC(~); % Set the cost function L OCP.setL(~); % Set the polytopic constraint G (optional) OCP.setG(~); % Generate necessary files OCP.codeGen();
-
Configure the solver using Class
NMPCSolver
% Create a NMPCSolver object nmpcSolver = NMPCSolver(OCP); % Configurate the Hessian approximation method nmpcSolver.setHessianApproximation(~); % Configurate the descent regularization parameter (optional) nmpcSolver.setDescentRegularization(~); % Generate necessary files nmpcSolver.codeGen();
-
Solve the very first OCP offline to provide an accurate initial guess
% Set the initial state x0 = [~]; % Set the parameters p = [~]; % Create an initial guess solutionInitGuess = [~]; % Solve the optimal control problem for given values of x0 and p % with barrier parameter rho solution = NMPC_SolveOffline(x0,p,solutionInitGuess,rho,maxIter); % Save to file for Simu_Matlab.m save GEN_initData.mat dim x0 p N % Set initial guess global ParNMPCGlobalVariable ParNMPCGlobalVariable.solutionInitGuess = solution;
-
Define the controlled plant using Class
DynamicSystem
(optional for simulation)% Create a DynamicSystem object plant = DynamicSystem(dim.u,dim.x,dim.p); % Give names to x, u, p (optional) [~] = plant.setStateName(~); [~] = plant.setInputName(~); [~] = plant.setParameterName(~); % Set the dynamic function f plant.setf(~); % Set the matrix M (optional for, e.g., Lagrange model) plant.setM(~); % Generate necessary files plant.codeGen();
Configuration Table:
Configurable discretization method | Configurable Hessian approximation method | |
---|---|---|
M enabled |
'Euler' |
'GaussNewton' |
M disabled |
All | All |
Closed-loop Simulation
In order to do the closed-loop simulation for the problem defined above, two functions are provided:
-
NMPC_Solve
: function of the NMPC solver. See Interfaces > Functions > NMPC_Solve. -
SIM_Plant_RK4
: one-step simulation of the controlled plant based on the 4-th order Runge-Kutta method. See Interfaces > Functions > SIM_Plant_RK4.
Code Generation and Deployment
MATLAB
Here, assume your closed-loop simulation is performed in Simu_Matlab.m
.
Example
./Simu_Matlab.m
Code generation
Example
./Simu_Matlab_Codegen.m
An executable file that performs the closed-loop simulation will be generated automatically.
Simulink
Here, assume your closed-loop simulation is performed in Simulink. You can call the generated C/C++ solver function NMPC_Solve
directly to compute the optimal input.
Code generation
Example
./Simu_Simulink_Setup.m
-
Define and configurate options for NMPC_Solve:
options = createOptions();
-
Generate code:
NMPC_Solve_CodeGen(~,~,options);
Deployment
Example
./Simu_Simulink.slx
This example shows how to call the generated C interface in Simulink using the coder.cevel
function within a MATLAB Function
block.
You can also call the C/C++ interface using S-function.
-
Open the Simulation Target pane in the Simulink Editor: Simulation > Model Configuration Parameters > Simulation Target.
-
Add
#include "NMPC_Solve.h"
to Insert custom C code in generated: Header file. -
Add
NMPC_Solve_initialize();
to Insert custom C code in generated: Initialize function. -
Add
NMPC_Solve_terminate();
to Insert custom C code in generated: Terminate function. -
Add the following directory to Additional Build Information: Include directories:
./codegen/~/NMPC_Solve
-
Add
NMPC_Solve.lib
(NMPC_Solve.so
in linux) to Additional Build Information: Libraries. -
Call the generated C function in a
MATLAB Function
block in Simulink:output = createOutput(); solution = createNonemptySolution(); coder.ceval('NMPC_Solve',... x0,... p,... % (optional) coder.wref(solution),... coder.wref(output));
Note
Alternatively, steps 1-6 can be done using the following commands.
Simu_Simulink set_param('Simu_Simulink', 'SimCustomHeaderCode', '#include "NMPC_Solve.h"') set_param('Simu_Simulink', 'SimCustomInitializer', 'NMPC_Solve_initialize();') set_param('Simu_Simulink', 'SimCustomTerminator', 'NMPC_Solve_terminate();') set_param('Simu_Simulink', 'SimUserLibraries', 'NMPC_Solve.lib') set_param('Simu_Simulink', 'SimUserIncludeDirs', './codegen/~/NMPC_Solve')
Accelerating Simulation using MEX-function
-
Code generation
Example
./Simu_Simulink_Setup.m
Following the code generation for Simulink procedure, MEX-function can be generated by modifying the generation target to
mex
:NMPC_Solve_CodeGen('mex','C',options);
-
Deployment
Example
./Simu_Matlab.m
Modify
NMPC_Solve
toNMPC_Solve_mex
to call the generatedmex
function and run.MEX-function is typically slower than C code. However, it can speed up your simulation to check the closed-loop response.