Workflow of ParNMPC

Preparation

  1. Choose a compiler that supports code generation with OpenMP by mex -setup.
  2. Edit Timer.m to specify your own timer function.

NMPC Problem Formulation

Example

./NMPC_Problem_Definition.m

  1. 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();
    

  2. 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();
    

  3. 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;
    

  4. 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:

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.

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

  1. Define and configurate options for NMPC_Solve:

    options = createOptions();
    

  2. 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.

  1. Open the Simulation Target pane in the Simulink Editor: Simulation > Model Configuration Parameters > Simulation Target.

  2. Add #include "NMPC_Solve.h" to Insert custom C code in generated: Header file.

  3. Add NMPC_Solve_initialize(); to Insert custom C code in generated: Initialize function.

  4. Add NMPC_Solve_terminate(); to Insert custom C code in generated: Terminate function.

  5. Add the following directory to Additional Build Information: Include directories:

    ./codegen/~/NMPC_Solve
    

  6. Add NMPC_Solve.lib (NMPC_Solve.so in linux) to Additional Build Information: Libraries.

  7. 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

  1. 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);
    

  2. Deployment

    Example

    ./Simu_Matlab.m

    Modify NMPC_Solve to NMPC_Solve_mex to call the generated mex function and run.

    MEX-function is typically slower than C code. However, it can speed up your simulation to check the closed-loop response.