Main Content

Specify Prediction Model for Nonlinear MPC

The prediction model of a nonlinear MPC controller consists of the following user-defined functions:

  • State function — Predicts how the plant states evolve over time

  • Output function — Calculates plant outputs in terms of state and input variables

You can specify either a continuous-time or a discrete-time prediction model.

Before simulating your controller, it is best practice to validate your custom functions, including the state function, output function, and their Jacobians using the validateFcns command.

For an example on how to use a neural state-space model identified from data as a prediction model for a multistage nonlinear MPC problem, see Control House Heating System Using Nonlinear Model Predictive Control With Neural State-Space Prediction Model.

State Function

You can specify either a continuous-time or a discrete-time state function. For a:

  • Continuous-time prediction model, the state function is the state derivative function.

    dx/dt=f(x,u)

  • Discrete-time prediction model, the state function is the state update function.

    x(k+1)=f(x(k),u(k))

Since a nonlinear MPC controller is a discrete-time controller, if your state function is continuous-time, the controller automatically discretizes the model using the implicit trapezoidal rule. This method can handle moderately stiff models, and its prediction accuracy depends on the controller sample time; that is, a large sample time can potentially lead to inaccurate prediction.

If the default discretization method does not provide satisfactory prediction for your application, you can specify your own discrete-time prediction model that uses a different method. To do so, you can integrate a continuous-time state function from the given initial condition, xk, to the next state, xk+1. When doing so numerically, avoid approaches that require iterations, such as some variable-step-size methods, because these methods introduce numerical noise that degrades solver performance. An explicit multistep Euler method with sufficiently small step size is often the best method to try first. For an example, see Swing-Up Control of a Pendulum Using Nonlinear Model Predictive Control.

You can specify your state function in one of the following ways.

  • Name of a function in the current working folder or on the MATLAB® path, specified as a string or character vector

    Model.StateFcn = "myStateFunction";
  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path

    Model.StateFcn = @myStateFunction;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Model.StateFcn = @(x,u,params) myStateFunction(x,u,params)

    For more information on anonymous functions, see Anonymous Functions.

Note

Only functions defined in a separate file in the current folder or on the MATLAB path are supported for C/C++ code generation. Therefore, specifying state, output, cost, or constraint functions (or their Jacobians) as local or anonymous functions is not recommended.

Your state function must have one of the following signatures.

  • If your controller does not use optional parameters:

    function z = myStateFunction(x,u)
  • If your controller uses parameters. Here, params is a comma-separated list of parameters:

    function z = myStateFunction(x,u,params)

This table describes the inputs and outputs of this function, where:

  • Nx is the number of states and is equal to the Dimensions.NumberOfStates property of the controller.

  • Nu is the number of inputs, including all manipulated variables, measured disturbances, and unmeasured disturbances, and is equal to the Dimensions.NumberOfInputs property of the controller.

ArgumentInput/OutputDescription
xInputCurrent states, specified as a column vector of length Nx.
uInputCurrent inputs, specified as a column vector of length Nu.
paramsInput

Optional parameters, specified as a comma-separated list (for example p1,p2,p3). The same parameters are passed to the prediction model, custom cost function, and custom constraint functions of the controller.

If your model uses optional parameters, you must specify the number of parameters using the Model.NumberOfParameters property of the controller.

zOutputState function output, returned as a column vector of length Nx. For a continuous-time prediction model, z contains the state derivatives, dx/dt, and for discrete-time prediction models, z contains the next states, x(k+1).

As an example of a state function, consider the continuous-time model with the following state equations:

x˙1=x4x˙2=x5x˙3=x6x˙4=(u1u2+u3u4)cos(x3)x˙5=(u1u2+u3u4)sin(x3)x˙6=0.2(u1u2u3+u4)

You can specify the state function as follows:

z = zeros(6,1);
z(1) = x(4);
z(2) = x(5);
z(3) = x(6);
z(4) = (u(1) - u(2) + u(3) - u(4))*cos(x(3));
z(5) = (u(1) - u(2) + u(3) - u(4))*sin(x(3));
z(6) = 0.2*(u(1) - u(2) - u(3) + u(4));

State Function Jacobians

To improve computational efficiency, it is best practice to specify an analytical Jacobian for your state function. If you do not specify a Jacobian, the controller computes the Jacobian using numerical perturbation. To specify a Jacobian for your state function, set the Jacobian.StateFcn property of the controller to one of the following.

  • Name of a function in the current working folder or on the MATLAB path, specified as a string or character vector

    Jacobian.StateFcn = "myStateJacobian";
  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path

    Jacobian.StateFcn = @myStateJacobian;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Jacobian.StateFcn = @(x,u,params) myStateJacobian(x,u,params)

    For more information on anonymous functions, see Anonymous Functions.

Note

Only functions defined in a separate file in the current folder or on the MATLAB path are supported for C/C++ code generation. Therefore, specifying state, output, cost, or constraint functions (or their Jacobians) as local or anonymous functions is not recommended.

Your state Jacobian function must have one of the following signatures.

  • If your controller does not use optional parameters:

    function [A,Bmv] = myStateJacobian(x,u)
  • If your controller uses parameters. Here params is a comma-separated list of parameters:

    function [A,Bmv] = myStateJacobian(x,u,params)

The input arguments of the state Jacobian function are the same as the inputs of the state function. This table describes the outputs of the Jacobian function, where:

  • Nx is the number of states and is equal to the Dimensions.NumberOfStates property of the controller

  • Nu is the number of inputs, including all manipulated variables, measured disturbances, and unmeasured disturbances, and is equal to the Dimensions.NumberOfInputs property of the controller

ArgumentDescription
AJacobian of the state function output, z, with respect to x, returned as an Nx-by-Nx array, where A(i,j)=z(i)/x(j).
BmvJacobian of the state function output with respect to the manipulated variables, specified as an Nx-by-Nmv array, where Bmv(i,j)=z(i)/u(MV(j)) and MV(j) is the jth MV index in the Dimensions.MVIndex controller property. Bmv contains the gradients with respect to only the manipulated variables in u, since the measured and unmeasured disturbances are not decision variables.

Consider again, the state function with the following state equations:

x˙1=x4x˙2=x5x˙3=x6x˙4=(u1u2+u3u4)cos(x3)x˙5=(u1u2+u3u4)sin(x3)x˙6=0.2(u1u2u3+u4)

To find the Jacobians, compute the partial derivatives of the state equations with respect to the states and manipulated variables, assuming that all four inputs are manipulated variables.

A = zeros(6,6);
A(1,4) = 1;
A(2,5) = 1;
A(3,6) = 1;
A(4,3) = -(u(1) - u(2) + u(3) - u(4))*sin(x(3));
A(5,3) =  (u(1) - u(2) + u(3) - u(4))*cos(x(3));
B = zeros(6,4);
B(4,:) = cos(x(3))*[1 -1 1 -1];
B(5,:) = sin(x(3))*[1 -1 1 -1];
B(6,:) = 0.2*[1 -1 -1 1];

Note

For multistage nonlinear MPC, you can automatically generate a state Jacobian function using generateJacobianFunction.

Output Function

The output function of your prediction model relates the states and inputs at the current control interval to the outputs. If the number of states and outputs of the prediction model are the same, you can omit OutputFcn, which implies that all states are measurable; that is, each output corresponds to one state.

Note

OutputFcn cannot have direct feedthrough from any manipulated variable to any output at any time; in other words, nonlinear MPC always assumes Dmv = 0.

You can specify your output function in one of the following ways.

  • Name of a function in the current working folder or on the MATLAB path, specified as a string or character vector

    Model.OutputFcn = "myOutputFunction";
  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path

    Model.OutputFcn = @myOutputFunction;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Model.OutputFcn = @(x,u,params) myOutputFunction(x,u,params)

    For more information on anonymous functions, see Anonymous Functions.

Note

Only functions defined in a separate file in the current folder or on the MATLAB path are supported for C/C++ code generation. Therefore, specifying state, output, cost, or constraint functions (or their Jacobians) as local or anonymous functions is not recommended.

Your output function must have one of the following signatures.

  • If your controller does not use optional parameters:

    function y = myOutputFunction(x,u)
  • If your controller uses parameters. Here, params is a comma-separated list of parameters:

    function y = myOutputFunction(x,u,params)

This table describes the inputs and outputs of this function, where:

  • Nx is the number of states and is equal to the Dimensions.NumberOfStates property of the controller.

  • Nu is the number of inputs, including all manipulated variables, measured disturbances, and unmeasured disturbances, and is equal to the Dimensions.NumberOfInputs of the controller.

  • NY is the number of outputs and is equal to the Dimensions.NumberOfOutputs property of the controller.

ArgumentInput/OutputDescription
xInputCurrent states, specified as a column vector of length Nx.
uInputCurrent inputs, specified as a column vector of length Nu.
paramsInput

Optional parameters, specified as a comma-separated list (for example p1,p2,p3). The same parameters are passed to the prediction model, custom cost function, and custom constraint functions of the controller.

If your model uses optional parameters, you must specify the number of parameters using Model.NumberOfParameters.

yOutputCurrent outputs, returned as a column vector of length Ny.

As an example of an output function, consider the following output equations. Recall, that your output function cannot have direct feedthrough from any manipulated variable to any output at any time.

y1=x1y2=x2+0.2x3y3=x3x4

You can specify the output function as follows:

y = zeros(6,1);
y(1) = x(1);
y(2) = x(2)+0.2*x(3);
y(3) = x(3)*x(4);

Output Function Jacobians

To improve computational efficiency, it is best practice to specify an analytical Jacobian for your output function. If you do not specify a Jacobian, the controller computes the Jacobian using numerical perturbation. To specify a Jacobian for your output function, set the Jacobian.OutputFcn property of the controller to one of the following.

  • Name of a function in the current working folder or on the MATLAB path, specified as a string or character vector

    Jacobian.OutputFcn = "myOutputJacobian";
  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path

    Jacobian.OutputFcn = @myOutputJacobian;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Jacobian.OutputFcn = @(x,u,params) myOutputJacobian(x,u,params)

    For more information on anonymous functions, see Anonymous Functions.

Note

Only functions defined in a separate file in the current folder or on the MATLAB path are supported for C/C++ code generation. Therefore, specifying state, output, cost, or constraint functions (or their Jacobians) as local or anonymous functions is not recommended.

Your output Jacobian function must have one of the following signatures.

  • If your controller does not use optional parameters:

    function C = myOutputJacobian(x,u)
  • If your controller uses parameters. Here, params is a comma-separated list of parameters:

    function C = myOutputJacobian(x,u,params)

The input arguments of the output Jacobian function are the same as the inputs of the output function. This table describes the output of the Jacobian function. Since the output function cannot have direct feedthrough from any manipulated variable to any output, the output Jacobian function returns only the gradients of the output function with respect to the model states.

ArgumentDescription
CJacobian of the output function, returned as an Ny-by-Nx array, where C(i,j)=y(i)/x(j).

Consider again, the model with the following output equations:

y1=x1y2=x2+0.2x3y3=x3x4

To find the Jacobians, compute the partial derivatives of the output equations with respect to the states. Since the output function cannot have direct feedthrough from any manipulated variable to any output at any time, you do not compute the Jacobian with respect to the manipulated variables.

C = zeros(3,4);
C(1,1) = 1;
C(2,2) = 1;
C(2,3) = 0.2;
C(3,3) = x(4);
C(3,4) = x(3);

Specify Optional Model Parameters

You can specify optional parameters for your nonlinear MPC prediction model, cost function, and custom constraints. To do so, pass a comma-separated list of parameter arguments to your custom functions (for example p1,p2,p3). These parameters must be numerical values. Also, you must specify the number of model parameters using the Model.NumberOfParameters property of the controller.

The same parameters are passed to the prediction model, custom cost function, custom constraint functions, and their respective Jacobians. For example, even if the state function uses only parameter p1, the constraint functions use only parameter p2, and the cost function uses only parameter p3, you must still define three parameters. All of these parameters are passed into all of these functions, and you must choose the correct parameter to use in each function.

For an example that specifies the sample time of a discrete-time state function as a parameter, see Swing-Up Control of a Pendulum Using Nonlinear Model Predictive Control.

Augment Prediction Model with Unmeasured Disturbances

You can augment your prediction model to include unmeasured disturbances. For example, if your plant does not have an integrator and you want to reject a certain unmeasured disturbance, augment your plan with a disturbance model. Doing so allows the external state estimator to detect the disturbance and thus give the nonlinear MPC controller enough information to reject it.

During simulation, the controller passes a zero to each unmeasured disturbance input channel, since the signals are unmeasured and assumed to be zero-mean by default.

To augment your prediction model, you must designate one or more input signals as unmeasured disturbances when creating a controller using nlmpc. For example, create a controller where the first two inputs are manipulated variables and the third input is an unmeasured disturbance (UD).

nlobj = nlmpc(nx,ny,'MV',[1 2],'UD',3);

Specify the unmeasured disturbance model in the state and output functions of your prediction model. This unmeasured disturbance model can be any arbitrary model that accurately captures the effect of the disturbance on your plant. For example:

  • If you expect a step-like UD at a plant output, then specify the UD model as an integrator in your state function, and add the integrator state to the plant output in your output function.

  • If you expect a ramp-like UD at a plant input, then specify the UD model as an integrator and add the integrator output to the input signal in your state function.

Any states that you add when specifying the unmeasured disturbance model are included in the prediction model state vector. The values in these unmeasured disturbance model states reflect the disturbance behavior during simulation. This state vector corresponds to the x input argument of your state function and the X input argument to your custom cost and constraint functions.

For an example that augments the prediction model for random step-like output disturbances, see Nonlinear Model Predictive Control of an Exothermic Chemical Reactor.

See Also

Functions

Objects

Related Examples

More About