Main Content

Specify Constraints for Nonlinear MPC

When you create a nonlinear MPC controller using an nlmpc object, you can define any of the following constraints:

  • Standard linear constraints on states, outputs, manipulated variables, and manipulated variable rates of change

  • Custom equality constraints, specified as linear or nonlinear functions of the prediction model system states and inputs

  • Custom inequality constraints, specified as linear or nonlinear functions of the prediction model system states and inputs

  • Passivity inequality constraints, specified as linear or nonlinear functions of the prediction model states and inputs

The controller optimizes its control moves to satisfy all of these constraints; that is, the custom constraints supplement the standard linear constraints.

To improve computational efficiency, you can also specify analytical Jacobians for your custom equality and inequality constraints.

By specifying custom equality or inequality constraints, you can, for example:

  • Require the plant to reach a target state at the end of the prediction horizon

  • Require cumulative resource consumption to stay within specified limits

If your plant is passive, enforcing controller passivity guarantees that the resulting closed loop system is stable. You can enforce controller passivity by specifying passivity constraints.

For a multistage MPC controller, each stage has its own constraints, and each constraint for a specific stage is function only of the decision variables and parameters at that stage. Passivity constraints are not supported for nlmpcMultistage objects.

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

Linear MPC controllers have properties for defining custom constraints on linear combinations of inputs and outputs, as discussed in Constraints on Linear Combinations of Inputs and Outputs. These properties are not available for nonlinear MPC controllers. Instead, you implement such constraints within your custom equality or inequality constraint functions.

Standard Linear Constraints

The following table shows the standard linear constraints supported by nonlinear MPC controllers. For each of these constraints, you can specify a single bound that applies across the entire prediction horizon, or you can vary each constraint over the prediction horizon. For more information on setting controller linear constraint properties, see nlmpc.

ConstraintController PropertyConstraint Softening
Lower bounds on state iStates(i).Min > -InfNot applicable. State bounds are always hard.
Upper bounds on state iStates(i).Max < InfNot applicable. State bounds are always hard.
Lower bounds on output variable iOutputVariables(i).Min > -Inf

OutputVariables(i).MinECR > 0

Default: 1 (soft)

Upper bounds on output variable iOutputVariables(i).Max < Inf

OutputVariables(i).MaxECR > 0

Default: 1 (soft)

Lower bounds on manipulated variable iManipulatedVariables(i).Min > -Inf

ManipulatedVariables(i).MinECR > 0

Default: 0 (hard)

Upper bounds on manipulated variable iManipulatedVariables(i).Max < Inf

ManipulatedVariables(i).MaxECR > 0

Default: 0 (hard)

Lower bounds on manipulated variable i rate of changeManipulatedVariables(i).RateMin > -Inf

ManipulatedVariables(i).RateMinECR > 0

Default: 0 (hard)

Lower bounds on manipulated variable i rate of changeManipulatedVariables(i).RateMax < Inf

ManipulatedVariables(i).RateMaxECR > 0

Default: 0 (hard)

Custom Constraints

You can specify custom equality and inequality constraints for a nonlinear MPC controller. To configure your nonlinear MPC controller to use custom equality or inequality constraints, set its Optimization.CustomEqConFcn or Optimization.CustomIneqConFcn respectively. To do so, specify the custom functions as 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

    Optimization.CustomEqConFcn = "myEqConFunction";
    Optimization.CustomIneqConFcn = "myIneqConFunction";
  • Handle to a function in the current working folder or on the MATLAB path

    Optimization.CustomEqConFcn = @myEqConFunction;
    Optimization.CustomIneqConFcn = @myIneqConFunction;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Optimization.CustomEqConFcn = ...
        @(X,U,data,params) myEqConFunction(X,U,data,params);
    Optimization.CustomIneqConFcn = ...
        @(X,U,e,data,params) myIneqConFunction(X,U,e,data,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 constraint functions must have one of the following signatures.

  • If your controller does not use optional parameters:

    function ceq = myEqConFunction(X,U,data)
    function cineq = myIneqConFunction(X,U,e,data)
  • If your controller uses parameters. Here, params is a comma-separated list of parameters:

    function ceq = myEqConFunction(X,U,data,params)
    function cineq = myIneqConFunction(X,U,e,data,params)

This table describes the inputs and outputs of these functions, 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.

  • Nceq is the number of equality constraints.

  • Ncineq is the number of inequality constraints.

  • p is the prediction horizon.

  • k is the current time.

ArgumentInput/OutputDescription
XInputState trajectory from time k to time k+p, specified as a (p+1)-by-Nx array. The first row of X contains the current state values, which means that the solver does not use the values in X(1,:) as decision variables during optimization.
UInputInput trajectory from time k to time k+p, specified as a (p+1)-by-Nu array. The final row of U is always a duplicate of the preceding row; that is, U(end,:) = U(end-1,:). Therefore, the values in the final row of U are not independent decision variables during optimization.
eInput

Slack variable for constraint softening, specified as a positive scalar. Since all equality constraints are hard, this input argument applies to only the inequality constraint function.

dataInput

Additional signals, specified as a structure with the following fields:

FieldDescription
TsPrediction model sample time, as defined in the Ts property of the controller
CurrentStatesCurrent prediction model states, as specified in the x input argument of nlmpcmove
LastMVMV moves used in previous control, as specified in the lastmv input argument of nlmpcmove interval
ReferencesReference values for plant outputs, as specified in the ref input argument of nlmpcmove
MVTargetManipulated variable targets, as specified in the MVTarget property of an nlmpcmoveopt object
PredictionHorizonPrediction horizon, as defined in the PredictionHorizon property of the controller
NumOfStatesNumber of states, as defined in the Dimensions.NumberOfStates property of the controller
NumOfOutputsNumber of outputs, as defined in the Dimensions.NumberOfOutputs property of the controller
NumOfInputsNumber of inputs, as defined in the Dimensions.NumberOfInputs property of the controller
MVIndexManipulated variables indices, as defined in the Dimensions.MVIndex property of the controller
MDIndexMeasured disturbance indices, as defined in the Dimensions.MDIndex property of the controller
UDIndexUnmeasured disturbance indices, as defined in the Dimensions.UDIndex property of the controller
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. For example, if the state function uses only parameter p1, the constraint functions use only parameter p2, and the cost function uses only parameter p3, then all three parameters are passed to all of these functions.

If your model uses optional parameters, you must specify the number of parameters using Model.NumberOfParameters. At simulation time, you then pass these parameters to the Nonlinear MPC Controller block (in Simulink®) or to a simulation function such as nlmpcmove (in MATLAB).

ceqOutputComputed equality constraint values, returned as a column vector of length Nceq. An equality constraint is satisfied when the corresponding output is 0.
cineqOutputComputed inequality constraint values, returned as a column vector of length Ncineq. An inequality constraint is satisfied when the corresponding output is less than or equal to 0.

To use output variable values in your constraint functions, you must first derive them from the state and input arguments using the prediction model output function, as specified in the Model.OutputFcn property of the controller. For example, to compute the output trajectory Y from time k to time k+p, use:

p = data.PredictionHorizon;
for i=1:p+1
    Y(i,:) = myOutputFunction(X(i,:)',U(i,:)',params)';
end

For more information on the prediction model output function, see Specify Prediction Model for Nonlinear MPC.

In general:

  • All equality constraints are hard.

  • To define soft inequality constraints, use the slack variable input argument, e. For more information on constraint softening in MPC, see Constraint Softening.

  • Equality constraints should be continuous and have continuous first derivatives with respect to the decision variables.

You can define custom constraints that apply across the entire prediction horizon. For example, suppose that you want to satisfy the following inequality constraints across the prediction horizon, where u1 is the first manipulated variable:

2x123x2100u1250

To define the constraint values across the prediction horizon, use:

p = data.PredictionHorizon;
U1 = U(1:p,data.MVIndex(1));
X1 = X(2:p+1,1);
X2 = X(2:p+1,2);

cineq = [2*X1.^2 - 3*X2 - 10;
         U1.^2 - 5];

Applying these two constraints across p prediction horizon steps produces a column vector with 2*p inequality constraints. These inequality constraints are satisfied when the corresponding element of cineq is less than or equal to zero.

Alternatively, you can define constraints that apply at specific prediction horizon steps. For example, suppose that you want the states of a third-order plant to be:

x1=5x2=3x3=0

To specify these state values as constraints on only the final prediction horizon step, use:

ceq = [X(p+1,1) - 5;
       X(p+1,2) + 3;
       X(p+1,3)];

These equality constraints are satisfied when the corresponding element of ceq is equal to zero.

For relatively simple constraints, you can specify the constraint function using an anonymous function handle. For example, to specify an anonymous function that implements the equality constraints, use:

Optimization.CustomEqConFcn = @(X,U,data) [X(p+1,1) - 5; X(p+1,2) + 3; X(p+1,3)];

Custom Constraint Jacobians

To improve computational efficiency, it is best practice to specify analytical Jacobians for your custom constraint functions. If you do not specify Jacobians, the controller computes the Jacobians using numerical perturbation.

To specify a Jacobian for your equality or inequality constraint functions, set the respective Jacobian.CustomEqConFcn or Jacobian.CustomIneqConFcn 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.CustomEqConFcn = "myEqConJacobian";
    Jacobian.CustomIneqConFcn = "myIneqConJacobian";
  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path

    Jacobian.CustomEqConFcn = @myEqConJacobian;
    Jacobian.CustomIneqConFcn = @myIneqConJacobian;

    For more information on local functions, see Local Functions.

  • Anonymous function

    Jacobian.CustomEqConFcn = @(X,U,data,params) myEqConJacobian(X,U,data,params);
    Jacobian.CustomInqConFcn = @(X,U,e,data,params) myIneqConJacobian(X,U,e,data,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 constraint Jacobian functions must have one of the following signatures.

  • If your controller does not use optional parameters:

    function [Geq,Gmv] = myEqConJacobian(X,U,data)
    function [Geq,Gmv,Ge] = myIneqConJacobian(X,U,e,data)
  • If your controller uses parameters. Here, params is a comma-separated list of parameters:

    function [Geq,Gmv] = myEqConJacobian(X,U,data,params)
    function [Geq,Gmv,Ge] = myIneqConJacobian(X,U,e,data,params)

The input arguments of the constraint Jacobian functions are the same as the inputs of their respective custom constraint functions. This table describes the outputs of the Jacobian functions, where:

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

  • Nmv is the number of manipulated variables.

  • Nc is the number of constraints (either equality or inequality constraints, depending on the constraint function).

  • p is the prediction horizon.

ArgumentDescription
GJacobian of the equality or inequality constraints with respect to the state trajectories, returned as a p-by-Nx-by-Nc array, where G(i,j,l)=c(l)/X(i+1,j). Compute G based on X from the second row to row p+1, ignoring the first row.
Gmv

Jacobian of the equality or inequality constraints with respect to the manipulated variable trajectories, returned as a p-by-Nmv-by-Nc array, where Gmv(i,j,l)=c(l)/U(i,MV(j)) and MV(j) is the jth MV index in data.MVIndex.

Since the controller forces U(p+1,:) to equal U(p,:), if your constraints use U(p+1,:), you must include the impact of both U(p,:) and U(p+1,:) in the Jacobian for U(p,:).

GeJacobian of the inequality constraints with respect to the slack variable, e, returned as a row vector of length Nc, where Ge(l)=c(l)/e

To use output variable Jacobians in your constraint Jacobian functions, you must first derive them from the state and input arguments using the Jacobian of the prediction model output function, as specified in the Jacobian.OutputFcn property of the controller. For example, to compute the output variable Jacobians Yjacob from time k to time k+p, use:

p = data.PredictionHorizon;
for i=1:p+1
    Y(i,:) = myOutputFunction(X(i,:)',U(i,:)',params)';
end
for i=1:p+1
    Yjacob(i,:) = myOutputJacobian(X(i,:)',U(i,:)',params)';
end

Since prediction model output functions do not support direct feedthrough from inputs to outputs, the output function Jacobian contains partial derivatives with respect to only the states in X. For more information on the output function Jacobian, see Specify Prediction Model for Nonlinear MPC.

To find the Jacobians, compute the partial derivatives of the constraint functions with respect to the state trajectories, manipulated variable trajectories, and slack variable. For example, suppose that your constraint function is as follows, where u1 is the first manipulated variable.

2x123x2100u1250

To compute the Jacobian with respect to the state trajectories, use:

Nx = data.NumOfStates;
Nc = 2*p;
G = zeros(p,Nx,Nc);
G(1:p,2,1:p) = diag(2*X1 - 3);

To compute the Jacobian with respect to the manipulated variable trajectories, use:

Nmv = length(data.MVIndex);
Gmv = zeros(p,Nmv,Nc);
Gmv(1:p,1,p+1:2*p) = diag(2*u(1:p,data.MVIndex(1)));

In this case, the derivative with respect to the slack variable is Ge = zeros(20,1).

Note

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

Passivity Constraints

You can specify passivity inequality constraints for a general nonlinear MPC controller (multistage MPC controllers do not support passivity constraints). To use passivity constraints, set these properties of your nlmpc object as follows:

  • Passivity.EnforceConstrainttrue

  • Passivity.OutputPassivityIndex — A desired nonnegative scalar

  • Passivity.InputPassivityIndex — A desired nonnegative scalar

  • Passivity.OutputFcn — Name of the desired passivity output function yp(x,u)

  • Passivity.InputFcn — Name of the desired passivity input function up(x,u)

When your nonlinear MPC controller is configured to use passivity constraints, at each step the optimization algorithm tries to enforce the inequality constraint:

yp(x,u)Tup(x,u)+νyyp(x,u)Typ(x,u)+νuup(x,u)Tup(x,u)0.

Here, νy is the output passivity index, νu is the input passivity index, up(x,u) is the passivity input function, and yp(x,u) is the passivity output function. The variables x and u are the current state and input of the prediction model.

A dynamical system is said to be passive with respect to the input-output pair up and yp if there is a continuously differentiable positive definite function V(x), usually called storage function, such that V˙(x)up(x,u)Typ(x,u). Indeed, you can often find a valid storage function for your plant first, and then derive the passivity input-output function pair from it.

In general, for physical systems, you can use the total energy of the system as a storage function. Similarly to the problem of finding a Lyapunov function, you can look for terms in the system dynamics that represent potential or kinetic energy, and use them to construct a candidate storage function that is positive definite and radially unbounded. For more general nonlinear systems, you may need to use techniques based on sum-of-squares optimization or neural networks.

Assuming that the plant is already passive with respect to the input-output pair up and yp, if the controller is able to enforce the inequality constraint, then (under mild conditions) the resulting closed loop system tends to dissipate energy over time, and therefore has a stable equilibrium. For more information on passivity in the context of linear systems, see About Passivity and Passivity Indices. For examples of enforcing passivity constraints in simulation, see Passivity Enforcement for Control Design (Simulink Control Design).

To improve computational efficiency, you can specify analytical Jacobians for your passivity constraint functions. To do so, specify the Passivity.OutputJacobianFcn and Passivity.InputJacobianFcn properties.

You can specify the passivity functions and their Jacobians as 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.

  • Handle to a local function, or a function defined in the current working folder or on the MATLAB path. For more information on local functions, see Local Functions.

  • Anonymous function. 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.

The passivity functions and their Jacobians must accept as first and second input arguments the current state and input of the prediction model, respectively. After the first two input arguments, you can also pass an optional comma separated list of parameters (for example p1,p2,p3) that might be needed by the function you specify.

If any of your functions use optional parameters, you must specify the number of parameters using Model.NumberOfParameters. At run time, in Simulink, you then pass these parameters to the Nonlinear MPC Controller block. In MATLAB, you pass the parameters to a simulation function (such as nlmpcmove, using an nlmpcmoveopt option set object).

The function specified in Passivity.OutputJacobianFcn (if any) must return as a first output argument the Jacobian matrix of the output passivity function with respect to the current state (an Nyp-by-Nx matrix) and as a second output argument the Jacobian matrix of the output passivity function with respect to the manipulated variables (an Nyp by Nmv matrix).

Similarly, the function specified in Passivity.InputJacobianFcn (if any) must return as a first output argument the Jacobian of the input passivity function with respect to the current state (an Nup-by-Nx matrix) and as a second output argument the Jacobian of the input passivity function with respect to the manipulated variables (an Nup by Nmv matrix).

Here, Nx is the number of state variables of the prediction model, Nmv is the number of manipulated variables, Nyp is the number of outputs of the passivity output function, and Nup is the number of outputs of the passivity input function.

For more detail, see the Passivity property of nlmpc. For examples, see Control Quadruple-Tank Using Passivity-Based Nonlinear MPC and Control Robot Manipulator Using Passivity-Based Nonlinear MPC.

See Also

Functions

Objects

Blocks

Related Examples

More About