Main Content

mpc

Model predictive controller

Description

A model predictive controller uses linear plant, disturbance, and noise models to estimate the controller state and predict future plant outputs. Using the predicted plant outputs, the controller solves a quadratic programming optimization problem to determine control moves.

For more information on the structure of model predictive controllers, see MPC Prediction Models.

Creation

Description

mpcobj = mpc(plant) creates a model predictive controller object based on the discrete-time prediction model plant. The controller, mpcobj, inherits its control interval from plant.Ts, and its time unit from plant.TimeUnit. All other controller properties are default values. After you create the MPC controller, you can set its properties using dot notation.

If plant.Ts = -1, you must set the Ts property of the controller to a positive value before designing and simulating your controller.

mpcobj = mpc(plant,ts) creates a model predictive controller based on the specified plant model and sets the Ts property of the controller. If plant is:

  • A continuous-time model, then the controller discretizes the model for prediction using sample time ts

  • A discrete-time model with a specified sample time, the controller resamples the plant for prediction using sample time ts

  • A discrete-time model with an unspecified sample time (plant.Ts = –1), it inherits the sample time ts when used for predictions.

example

mpcobj = mpc(plant,ts,P,M,W,MV,OV,DV) specifies the following controller properties. If any of these values are omitted or empty, the default values apply.

  • P sets the PredictionHorizon property.

  • M sets the ControlHorizon property.

  • W sets the Weights property.

  • MV sets the ManipulatedVariables property.

  • OV sets the OutputVariables property.

  • DV sets the DisturbanceVariables property.

mpcobj = mpc(model) creates a model predictive controller object based on the specified prediction model set, which includes the plant, input disturbance, and measurement noise models along with the nominal conditions at which the models were obtained. When you do not specify a sample time, the plant model, model.Plant, must be a discrete-time model. This syntax sets the Model property of the controller.

mpcobj = mpc(model,ts) creates a model predictive controller based on the specified plant model and sets the Ts property of the controller to ts. If model.Plant is a discrete-time LTI model with an unspecified sample time (model.Plant.Ts = –1), it inherits the sample time ts when used for predictions.

mpcobj = mpc(model,ts,P,M,W,MV,OV,DV) specifies additional controller properties. If any of these values are omitted or empty, the default values apply.

Input Arguments

expand all

Plant prediction model, specified as either an LTI model or a linear System Identification Toolbox™ model. The specified plant corresponds to the Model.Plant property of the controller.

If you do not specify a sample time when creating your controller, plant must be a discrete-time model. For prediction, plant is discretized or resampled if needed using mpcobj.Ts as sample time. Delays, if present, are incorporated in the resulting discrete time model.

For more information on MPC prediction models, see MPC Prediction Models.

Note

Direct feedthrough from manipulated variables to any output in plant is not supported.

Example: tf(10,[1 10])

Prediction model, specified as a structure with the same format as the Model property of the controller. If you do not specify a sample time when creating your controller, model.Plant must be a discrete-time model.

For more information on MPC prediction models, see MPC Prediction Models.

Properties

expand all

Controller sample time, specified as a positive finite scalar. The controller uses a discrete-time model with sample time Ts for prediction. The time unit is inherited from plant.TimeUnit.

Example: mpcobj.Ts = 0.1

Prediction horizon steps, specified as a positive integer. The product of PredictionHorizon and Ts is the prediction time; that is, how far the controller looks into the future.

If you specify a prediction horizon that is not larger than the number of steps necessary to cover the longest delay among all the input-output channels, Nd = max(mpcobj.Model.Plant.IODelay(:))/mpcobj.Ts, then the software automatically increases the prediction horizon by floor(Nd).

Example: mpcobj.PredictionHorizon = 15

Control horizon, specified as one of the following:

  • Positive integer, m, between 1 and p, inclusive, where p is equal to PredictionHorizon. In this case, the controller computes m free control moves occurring at times k through k+m-1, and holds the controller output constant for the remaining prediction horizon steps from k+m through k+p-1. Here, k is the current control interval.

  • Vector of positive integers [m1, m2, …], specifying the lengths of blocking intervals. By default the controller computes M blocks of free moves, where M is the number of blocking intervals. The first free move applies to times k through k+m1-1, the second free move applies from time k+m1 through k+m1+m2-1, and so on. Using block moves can improve the robustness of your controller. The sum of the values in ControlHorizon must match the prediction horizon p. If you specify a vector whose sum is:

    • Less than the prediction horizon, then the controller adds a blocking interval. The length of this interval is such that the sum of the interval lengths is p. For example, if p=10 and you specify a control horizon of ControlHorizon=[1 2 3], then the controller uses four intervals with lengths [1 2 3 4].

    • Greater than the prediction horizon, then the intervals are truncated until the sum of the interval lengths is equal to p. For example, if p=10 and you specify a control horizon of ControlHorizon= [1 2 3 6 7], then the controller uses four intervals with lengths [1 2 3 4].

    For more information on manipulated variable blocking, see Manipulated Variable Blocking.

Example: mpcobj.ControlHorizon = 3

Prediction model and nominal conditions, specified as a structure with the following fields. For more information on the MPC prediction model, see MPC Prediction Models and Controller State Estimation.

Plant prediction model, specified as either an LTI model or a linear System Identification Toolbox model.

Note

Direct feedthrough from manipulated variables to any output in plant is not supported.

Example: mpcobj.Model.Plant = ss(-1,1,1,0)

Model describing expected unmeasured disturbances, specified as an LTI model. This model is required only when the plant has unmeasured disturbances. You can set this disturbance model directly using dot notation or using the setindist function.

By default, input disturbances are expected to be integrated white noise. To model the signal, an integrator with dimensionless unity gain is added for each unmeasured input disturbance, unless the addition causes the controller to lose state observability. In that case, the disturbance is expected to be white noise, and so, a dimensionless unity gain is added to that channel instead.

Example: mpcobj.Model.Disturbance = tf(5,[1 5])

Model describing expected output measurement noise, specified as an LTI model.

By default, measurement noise is expected to be white noise with unit variance. To model the signal, a dimensionless unity gain is added for each measured channel.

Example: mpcobj.Model.Noise = zpk(0,-1,1)

Nominal operating point at which plant model is linearized, specified as a structure with the following fields.

FieldDescriptionDefault
X

Plant state at operating point, specified as a column vector with length equal to the number of states in Model.Plant.

zero vector
U

Plant input at operating point, including manipulated variables and measured and unmeasured disturbances, specified as a column vector with length equal to the number of inputs in Model.Plant.

zero vector
Y

Plant output at operating point, including measured and unmeasured outputs, specified as a column vector with length equal to the number of outputs in Model.Plant.

zero vector
DX

For continuous-time models, DX is the state derivative at operating point: DX=f(X,U). For discrete-time models, DX=x(k+1)-x(k)=f(X,U)-X. Specify DX as a column vector with length equal to the number of states in Model.Plant.

zero vector

Manipulated Variable (MV) information, bounds, and scale factors, specified as a structure array with Nmv elements, where Nmv is the number of manipulated variables. To access this property, you can use the alias MV instead of ManipulatedVariables.

Note

Rates refer to the difference Δu(k)=u(k)-u(k-1). Constraints and weights based on derivatives du/dt of continuous-time input signals must be properly reformulated for the discrete-time difference Δu(k), using the approximation du/dt ≅ Δu(k)/Ts.

Each structure element has the following fields.

Lower bound for a given manipulated variable, specified as a scalar or vector. By default, this lower bound is -Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).Min = -5

Upper bound for a given manipulated variable, specified as a scalar or vector. By default, this upper bound is Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).Max = 5

Softness of the lower bound for a given manipulated variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative scalar or vector. By default, MV lower bounds are hard constraints.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR value over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR value is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).MinECR = 0.01

Softness of the upper bound for a given manipulated variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative scalar or vector. By default, MV upper bounds are hard constraints.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR value over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR value is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).MaxECR = 0.01

Lower bound for the rate of change of a given manipulated variable, specified as a nonpositive scalar or vector. The MV rate of change is defined as MV(k) - MV(k-1), where k is the current time. By default, this lower bound is -Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).RateMin = -2

Upper bound for the rate of change of a given manipulated variable, specified as a nonnegative scalar or vector. The MV rate of change is defined as MV(k) - MV(k-1), where k is the current time. By default, this lower bound is Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(1).RateMax = 2

Softness of the lower bound for the rate of change of a given manipulated variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative finite scalar or vector. By default, MV rate of change lower bounds are hard constraints.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR values over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR values are used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(2).RateMinECR = 0.01

Softness of the upper bound for the rate of change of a given manipulated variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative finite scalar or vector. By default, MV rate of change upper bounds are hard constraints.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR values over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR values are used for the remaining steps of the prediction horizon.

Example: mpcobj.ManipulatedVariables(2).RateMaxECR = 0.01

Targets for a given manipulated variable, specified as a scalar, vector, or as 'nominal' (default). When Target is 'nominal', then the manipulated variable targets correspond to mpcobj.Model.Nominal.U.

To use the same target across the prediction horizon, specify a scalar value.

To vary the target over the prediction horizon from time k to time k+p-1, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final value is used for the remaining steps of the prediction horizon.

You might want to set target values for some manipulated variables, along with corresponding nonzero cost function weights, for economic or operational reasons, whenever you have more manipulated variables than plant outputs. For more information, see Design MPC Controller for Nonsquare Plants and Setting Targets for Manipulated Variables.

Example: mpcobj.ManipulatedVariables(2).Target = [0.3 0.2]

Name of a given manipulated variable, specified as a string or character vector. This is a read-only property. To modify the names of manipulated variables, use mpcobj.Model.Plant.InputName.

Example: mpcobj.ManipulatedVariables(2).Name

Units of a given manipulated variable, specified as a string or character vector. This is a read-only property. To modify the units of manipulated variables, use mpcobj.Model.Plant.InputUnit.

Example: mpcobj.ManipulatedVariables(2).Units

Scale factor of a given manipulated variable, specified as a positive finite scalar. Specifying the proper scale factor can improve numerical conditioning for optimization. In general, use the amplitude of the operating range of the manipulated variable. For more information, see Specify Scale Factors.

Example: mpcobj.ManipulatedVariables(1).ScaleFactor = 10

Type of a given manipulated variable, specified as:

  • 'continuous' — This indicates that the manipulated variable is continuous.

  • 'binary' — This restricts the manipulated variable to be either 0 or 1.

  • 'integer' — This restricts the manipulated variable to be an integer.

  • A vector containing all the possible values — This restricts the manipulated variable to the specified values, for example mpcobj.MV(1).Type = [-1,0,0.5,1,2];.

By default, the type is set to 'continuous'.

For more information, see Finite Control Set MPC.

Example: mpcobj.ManipulatedVariables(1).Type = 'binary'

Output variable (OV) information, bounds, and scale factors, specified as a structure array with Ny elements, where Ny is the number of output variables. To access this property, you can use the alias OV instead of OutputVariables.

Each structure element has the following fields.

Lower bound for a given output variable, specified as a scalar or vector. By default, this lower bound is -Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k+1 to time k+p, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.OutputVariables(1).Min = -10

Upper bound for a given output variable, specified as a scalar or vector. By default, this upper bound is Inf.

To use the same bound across the prediction horizon, specify a scalar value.

To vary the bound over the prediction horizon from time k+1 to time k+p, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final bound is used for the remaining steps of the prediction horizon.

Example: mpcobj.OutputVariables(1).Max = 10

Softness of the lower bound for a given output variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative finite scalar or vector. By default, OV upper bounds are soft constraints.

To avoid creating an infeasible optimization problem at run time, it is best practice to use soft OV bounds.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR value over the prediction horizon from time k+1 to time k+p, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR value is used for the remaining steps of the prediction horizon.

Example: mpcobj.OutputVariables(1).MinECR = 5

Softness of the upper bound for a given output variable. A larger equal concern for relaxation (ECR) value indicates a softer constraint, specified as a nonnegative finite scalar or vector. By default, OV lower bounds are soft constraints.

To avoid creating an infeasible optimization problem at run time, it is best practice to use soft OV bounds.

To use the same ECR value across the prediction horizon, specify a scalar value.

To vary the ECR value over the prediction horizon from time k+1 to time k+p, specify a vector of up to p values. Here, k is the current time and p is the prediction horizon. If you specify fewer than p values, the final ECR value is used for the remaining steps of the prediction horizon.

Example: mpcobj.OutputVariables(1).MaxECR = 10

Name of a given output variable, specified as a string or character vector. This is a read-only property. To modify the names of output variables, use mpcobj.Model.Plant.OutputName

Example: mpcobj.OutputVariables(2).Name

Units of a given output variable, specified as a string or character vector. This is a read-only property. To modify the names of output variables, use mpcobj.Model.Plant.OutputUnit.

Example: mpcobj.OutputVariables(2).Units

Scale factor of a given output variable, specified as a positive finite scalar. Specifying the proper scale factor can improve numerical conditioning for optimization. In general, use the operating range of the output variable. For more information, see Specify Scale Factors.

Example: mpcobj.OutputVariables(1).ScaleFactor = 20

Disturbance variable (DV) information and scale factors, specified as a structure array with Nd elements, where Nd is the total number of measured and unmeasured disturbance inputs. The order of the disturbance signals within DisturbanceVariables is the following: the first Nmd entries relate to measured input disturbances, the last Nud entries relate to unmeasured input disturbances.

To access this property, you can use the alias DV instead of DisturbanceVariables.

Each structure element has the following fields.

DV name, specified as a string or character vector. This is a read-only property. To modify the names of disturbance variables, use mpcobj.Plant.Inputname.

Example: mpcobj.DisturbanceVariables(1).Name

OV units, specified as a string or character vector. This is a read-only property. To modify the units of disturbance variables, use mpcobj.Model.Plant.InputUnit.

Example: mpcobj.DisturbanceVariables(1).Units

DV scale factor, specified as a positive finite scalar. Specifying the proper scale factor can improve numerical conditioning for optimization. For more information, see Specify Scale Factors.

Example: mpcobj.DisturbanceVariables(1).ScaleFactor = 15

Standard cost function tuning weights, specified as a structure. The controller applies these weights to the scaled variables. Therefore, the tuning weights are dimensionless values.

The format of OutputWeights must match the format of the Weights.OutputVariables property of the controller object. For example, you cannot specify constant weights across the prediction horizon in the controller object, and then specify time-varying weights using mpcmoveopt.

Weights has the following fields. The values of these fields depend on whether you use the standard or alternative cost function. For more information on these cost functions, see Optimization Problem.

Manipulated variable tuning weights, which penalize deviations from MV targets, specified as a row vector or array of nonnegative values. The default weight for all manipulated variables is 0.

To use the same weights across the prediction horizon, specify a row vector of length Nmv, where Nmv is the number of manipulated variables.

To vary the tuning weights over the prediction horizon from time k to time k+p-1, specify an array with Nmv columns and up to p rows. Here, k is the current time and p is the prediction horizon. Each row contains the manipulated variable tuning weights for one prediction horizon step. If you specify fewer than p rows, the weights in the final row are used for the remaining steps of the prediction horizon.

If you use the alternative cost function, specify Weights.ManipulatedVariables as a cell array that contains the Nmv-by-Nmv Ru matrix. For example, mpcobj.Weights.ManipulatedVariables = {Ru}. Ru must be a positive semidefinite matrix. Varying the Ru matrix across the prediction horizon Is not supported. For more information, see Alternative Cost Function.

Example: mpcobj.Weights.ManipulatedVariables = [0.1 0.2]

Manipulated variable rate tuning weights, which penalize large changes in control moves, specified as a row vector or array of nonnegative values. The default weight for all manipulated variable rates is 0.1.

To use the same weights across the prediction horizon, specify a row vector of length Nmv, where Nmv is the number of manipulated variables.

To vary the tuning weights over the prediction horizon from time k to time k+p-1, specify an array with Nmv columns and up to p rows. Here, k is the current time and p is the prediction horizon. Each row contains the manipulated variable rate tuning weights for one prediction horizon step. If you specify fewer than p rows, the weights in the final row are used for the remaining steps of the prediction horizon.

Note

It is best practice to use nonzero manipulated variable rate weights. If all manipulated variable rate weights are strictly positive, the resulting QP problem is strictly convex. If some weights are zero, the QP Hessian could be positive semidefinite. To keep the QP problem strictly convex, when the condition number of the Hessian matrix KΔU is larger than 1012, the quantity 10*sqrt(eps) is added to each diagonal term. See Cost Function.

If you use the alternative cost function, specify Weights.ManipulatedVariablesRate as a cell array that contains the Nmv-by-Nmv RΔu matrix. For example, mpcobj.Weights.ManipulatedVariablesRate = {Rdu}. RΔu must be a positive semidefinite matrix. Varying the RΔu matrix across the prediction horizon Is not supported. For more information, see Alternative Cost Function.

Example: mpcobj.Weights.ManipulatedVariablesRate = [0.1 0.1]

Output variable tuning weights, which penalize deviation from output references, specified as a row vector or array of nonnegative values. The default weight for all output variables is 1.

To use the same weights across the prediction horizon, specify a row vector of length Ny, where Ny is the number of output variables.

To vary the tuning weights over the prediction horizon from time k+1 to time k+p, specify an array with Ny columns and up to p rows. Here, k is the current time and p is the prediction horizon. Each row contains the output variable tuning weights for one prediction horizon step. If you specify fewer than p rows, the weights in the final row are used for the remaining steps of the prediction horizon.

If you use the alternative cost function, specify Weights.OutputVariables as a cell array that contains the Ny-by-Ny Q matrix. For example, mpcobj.Weights.OutputVariables = {Q}. Q must be a positive semidefinite matrix. Varying the Q matrix across the prediction horizon Is not supported. For more information, see Alternative Cost Function.

Example: mpcobj.Weights.OutputVariables = [1 1]

Slack variable tuning weight, specified as a positive scalar. Increase or decrease the equal concern for relaxation (ECR) weight to make all soft constraints harder or softer, respectively.

Example: mpcobj.Weights.ECR = 1e4

QP optimization parameters, specified as a structure with the following fields. The first four fields, Algorithm, ActiveSetOptions, InteriorPointOptions and MixedIntegerOptions, are related to the built in solvers. If you chose to use a custom solver for simulation (by setting CustomSolver to true) these four fields are ignored for simulation. Likewise, if you chose to use a custom solver for code generation (by setting CustomSolverCodeGen to true) these four fields are ignored for code generation.

For more information on the supported QP solvers, see QP Solvers.

QP solver algorithm, specified as one of the following:

  • 'active-set' — Solve the QP problem using the KWIK active-set algorithm.

  • 'interior-point' — Solve the QP problem using a primal-dual interior-point algorithm with Mehrotra predictor-corrector.

For applications that require solving QP problems, you can also access the active-set and interior-point algorithms using the mpcActiveSetSolver and mpcInteriorPointSolver functions, respectively.

Example: mpcobj.Optimizer.Algorithm = 'interior-point'

Active-set QP solver settings, specified as a structure. These settings apply only when Algorithm is 'active-set', and the type property of all manipulated variables is 'continuous'.

You can specify the following active-set optimizer settings.

Maximum number of iterations allowed when computing the QP solution, specified as one of the following:

  • 'default' — The MPC controller automatically computes the maximum number of QP solver iterations as 4(nc+nv), where:

    • nc is the total number of constraints across the prediction horizon.

    • nv is the total number of optimization variables across the control horizon.

    The default MaxIterations value has a lower bound of 120.

  • Positive integer — The QP solver stops after the specified number of iterations. If the solver fails to converge in the final iteration, the controller:

    • Freezes the controller movement if UseSuboptimalSolution is false.

    • Applies the suboptimal solution reached after the final iteration if UseSuboptimalSolution is true.

Note

The default MaxIterations value can be very large for some controller configurations, such as those with large prediction and control horizons. When simulating such controllers, if the QP solver cannot find a feasible solution, the simulation can appear to stop responding, since the solver continues searching for a solution until the number of iterations reach MaxIterations.

Example: mpcobj.Optimizer.ActiveSetOptions.MaxIterations = 2000

Tolerance used to verify that inequality constraints are satisfied by the optimal solution, specified as a positive scalar. A larger ConstraintTolerance value allows for larger constraint violations.

Example: mpcobj.Optimizer.ActiveSetOptions.ConstraintTolerance = 1e-5

Option indicating whether to warm start each QP solver iteration by passing in a list of active inequalities from the previous iteration, specified as a logical value. Inequalities are active when their equal portion is true.

Example: mpcobj.Optimizer.ActiveSetOptions.UseWarmStart = true

Interior-point QP solver settings, specified as a structure. These settings apply only when Algorithm is 'interior-point', and the type property of all manipulated variables is 'continuous'.

You can specify the following interior-point optimizer settings.

Maximum number of iterations allowed when computing the QP solution, specified as a positive integer. The QP solver stops after the specified number of iterations. If the solver fails to converge in the final iteration, the controller:

  • Freezes the controller movement if UseSuboptimalSolution is false.

  • Applies the suboptimal solution reached after the final iteration if UseSuboptimalSolution is true.

Example: mpcobj.Optimizer.InteriorPointOptions.MaxIterations = 30

Tolerance used to verify that equality and inequality constraints are satisfied by the optimal solution, specified as a positive scalar. A larger ConstraintTolerance value allows for larger constraint violations.

Example: mpcobj.Optimizer.InteriorPointOptions.ConstraintTolerance = 1e-5

Termination tolerance for first-order optimality (KKT dual residual), specified as a positive scalar.

Example: mpcobj.Optimizer.InteriorPointOptions.OptimalityTolerance = 1e-5

Termination tolerance for first-order optimality (KKT average complementarity residual), specified as a positive scalar. Increasing this value improves robustness, while decreasing this value increases accuracy.

Example: mpcobj.Optimizer.InteriorPointOptions.ComplementarityTolerance = 1e-6

Termination tolerance for decision variables, specified as a positive scalar.

Example: mpcobj.Optimizer.InteriorPointOptions.StepTolerance = 1e-7

Mixed-integer QP solver settings, specified as a structure. This setting apply when any manipulated variable has a type property which is not 'continuous'. In this case, a built it mixed-integer KWIK algorithm that implements a branch and bound method is used.

You can specify the following mixed-integer QP optimizer settings.

Maximum number of iterations allowed when computing the mixed-integer QP solution, specified as a positive integer. The mixed-integer QP solver stops after the specified number of iterations. If the solver fails to converge in the final iteration, the controller:

  • Freezes the controller movement if UseSuboptimalSolution is false.

  • Applies the suboptimal solution reached after the final iteration if UseSuboptimalSolution is true.

Example: mpcobj.Optimizer.MixedIntegerOptions.MaxIterations = 500

Tolerance used to verify that equality and inequality constraints are satisfied by the optimal solution, specified as a positive scalar. A larger ConstraintTolerance value allows for larger constraint violations.

Example: mpcobj.Optimizer.MixedIntegerOptions.ConstraintTolerance = 1e-5

Tolerance used to verify that constraints in the discrete manipulated variables are satisfied by the optimal solution, specified as a positive scalar. A larger DiscreteConstraintTolerance value allows for larger constraint violations.

Example: mpcobj.Optimizer.MixedIntegerOptions.DiscreteConstraintTolerance = 1e-5

Option to round the solution at the root node, specified as a boolean. When RoundingAtRootNode=1, the solver rounds the solution of the relaxed QP problem solved at the root node of the search tree, so that discrete constraints are satisfied. Then, an additional QP is solved with respect to the remaining (continuous) variables. If such a QP has a feasible solution, the corresponding cost is used as a valid upper-bound on the optimal solution of the original mixed-integer problem. Having such an upper-bound may eliminate entire subtrees in the rest of the execution of the solver and accelerate the solution of the following QP relaxations. Unless the number of iterations MaxIterations is small, it is worth setting RoundingAtRootNode=1. Otherwise, setting RoundingAtRootNode=0 avoids solving the additional QP.

Example: mpcobj.Optimizer.MixedIntegerOptions.RoundingAtRootNode = true

This is the maximum number of pending QP relaxations that can be stored. It determines the memory allocated to store all pending QP relaxations, which is proportional to (2*m+3*Nd)*MaxPendingNodes, where m is the number of inequality constraints, and Nd is the number of discrete variables. If the number of pending relaxations exceeds MaxPendingNodes then the solver is stopped with status code -3, -4 or -5.

Example: mpcobj.Optimizer.MixedIntegerOptions.MaxPendingNodes = 2000

Minimum value allowed for output constraint equal concern for relaxation (ECR) values, specified as a nonnegative scalar. A value of 0 indicates that hard output constraints are allowed. If either of the OutputVariables.MinECR or OutputVariables.MaxECR properties of an MPC controller are less than MinOutputECR, a warning is displayed and the value is raised to MinOutputECR during computation.

Example: mpcobj.Optimizer.MinOutputECR = 1e-10

Option indicating whether a suboptimal solution is acceptable, specified as a logical value. When the QP solver reaches the maximum number of iterations without finding a solution (the exit Option is 0), the controller:

  • Freezes the MV values if UseSuboptimalSolution is false

  • Applies the suboptimal solution found by the solver after the final iteration if UseSuboptimalSolution is true

To specify the maximum number of iterations, depending on the value of Algorithm, use either ActiveSetOptions.MaxIterations or InteriorPointOptions.MaxIterations.

Example: mpcobj.Optimizer.UseSuboptimalSolution = true

Option indicating whether to use a custom QP solver for simulation, specified as a logical value. If CustomSolver is true, the user must provide an mpcCustomSolver function on the MATLAB® path.

This custom solver is not used for code generation. To generate code for a controller with a custom solver, use CustomSolverCodeGen.

If CustomSolver is true, the controller does not require the custom solver to honor the settings in either ActiveSetOptions or InteriorPointOptions.

You can also use the function setCustomSolver to automatically configure mpcobj to use the active-set algorithm of quadprog (Optimization Toolbox) as a custom QP solver for both simulation and code generation.

For more information on using a custom QP solver see, QP Solvers.

Example: mpcobj.Optimizer.CustomSolver = true

Option indicating whether to use a custom QP solver for code generation, specified as a logical value. If CustomSolverCodeGen is true, the user must provide an mpcCustomSolverCodeGen function on the MATLAB path.

This custom solver is not used for simulation. To simulate a controller with a custom solver, use CustomSolver.

You can also use the function setCustomSolver to automatically configure mpcobj to use the active-set algorithm of quadprog (Optimization Toolbox) as a custom QP solver for both simulation and code generation.

For more information on using a custom QP solver see, QP Solvers.

Example: mpcobj.Optimizer.CustomSolverCodeGen = true

User notes associated with the MPC controller, specified as a cell array of character vectors.

Example: mpcobj.Notes = {'Longitudinal Controller'; 'Version 2.1'}

User data associated with the MPC controller, specified as any MATLAB data, such as a cell array or structure.

Example: mpcobj.UserData = {'Parameters',0.2,[3 4]'}

This property is read-only.

Controller creation date and time, specified as a vector with the following elements:

  • History(1) — Year

  • History(2) — Month

  • History(3) — Day

  • History(4) — Hours

  • History(5) — Minutes

  • History(6) — Seconds

Use datestr(mpcobj.History) to display the controller creation date as a character vector.

Example: mpcobj.History = datevec(now)

Object Functions

buildMEXBuild MEX file that solves an MPC control problem
cloffsetCompute closed-loop DC gain from output disturbances to measured outputs assuming constraints are inactive at steady state
compareCompare two MPC objects
generateExplicitMPCConvert implicit MPC controller to explicit MPC controller
generatePlotParametersParameters for plotSection
generateExplicitOptionsOptimization options for explicit MPC generation
generateExplicitRangeBounds on explicit MPC control law parameters
getGet property values from MPC object
getCodeGenerationDataCreate data structures for mpcmoveCodeGeneration
getEstimatorObtain Kalman gains and model for estimator design
getconstraintObtain mixed input/output constraints from model predictive controller
getindistRetrieve unmeasured input disturbance model
getnameRetrieve I/O signal names from MPC plant model
getoutdistRetrieve unmeasured output disturbance model
mpcmoveCompute optimal control action and update controller states
mpcmoveAdaptiveCompute optimal control with prediction model updating
plotPlot responses generated by MPC simulations
reviewExamine MPC controller for design errors and stability problems at run time
sensitivityCalculate the value of a performance metric and its sensitivity to the diagonal weights of an MPC controller
setSet or modify MPC object properties
setCustomSolverConfigures an MPC object to use the QP solver from Optimization Toolbox as a custom solver
setEstimatorModify a model predictive controller’s state estimator
setconstraintSet mixed input/output constraints for model predictive controller
setindistModify unmeasured input disturbance model
setnameSet I/O signal names in MPC plant model
setoutdistModify unmeasured output disturbance model
setterminalTerminal weights and constraints
simSimulate an MPC controller in closed loop with a linear plant
sizeSize and order of MPC Controller
ssConvert unconstrained MPC controller to state-space linear system form
tfConvert unconstrained MPC controller to linear transfer function form
trimCompute steady-state value of MPC controller plant model state for given inputs and outputs

Examples

collapse all

Create a plant model with the transfer function (s+1)/(s2+2s).

Plant = tf([1 1],[1 2 0]);

The plant is SISO, so its input must be a manipulated variable and its output must be measured. In general, it is good practice to designate all plant signal types using either the setmpcsignals command, or the LTI InputGroup and OutputGroup properties.

Specify a sample time for the controller.

Ts = 0.1;

Define bounds on the manipulated variable, u, such that -1u1.

MV = struct(Min=-1,Max=1);

MV contains only the upper and lower bounds on the manipulated variable. In general, you can specify additional MV properties. When you do not specify other properties, their default values apply.

Specify a 20-interval prediction horizon and a 3-interval control horizon.

p = 20;
m = 3;

Create an MPC controller using the specified values. The fifth input argument is empty, so default tuning weights apply.

mpcobj = mpc(Plant,Ts,p,m,[],MV);
-->"Weights.ManipulatedVariables" is empty. Assuming default 0.00000.
-->"Weights.ManipulatedVariablesRate" is empty. Assuming default 0.10000.
-->"Weights.OutputVariables" is empty. Assuming default 1.00000.

Algorithms

To minimize computational overhead, model predictive controller creation occurs in two phases. The first happens at creation when you use the mpc function, or when you change a controller property. Creation includes basic validity and consistency checks, such as signal dimensions and nonnegativity of weights.

The second phase is initialization, which occurs when you use the object for the first time in a simulation or analytical procedure. Initialization computes all constant properties required for efficient numerical performance, such as matrices defining the optimal control problem and state estimator gains. Additional, diagnostic checks occur during initialization, such as verification that the controller states are observable.

By default, both phases display informative messages in the command window. You can turn these messages on or off using the mpcverbosity function.

Alternative Functionality

You can also create model predictive controllers using the MPC Designer app.

Version History

Introduced before R2006a

expand all