mpt

mptopt Global option handler for MPT.
mpt_init Initializes MPT toolbox for the first time after installation.
mptdoc Display documentation for Multi-Parametric Toolbox in Matlab help browser.

utils

modules

demos

Back to Top

utils

mpt_ineq2eq Detects inequality constraints which form equalities
mpt_scale_matrix Scales matrix row-wise and column-wise

@IterableBehavior

Back to Top

@IterableBehavior

foreach Applies a given function to each element of in an array of sets.
iterablebehavior Basic class which provides forEach method to iterate over an array.

Back to Top

modules

geometry

solvers

ui

Back to Top

geometry

unions

sets

functions

Back to Top

unions

@BinTreePolyUnion

@Union

@PolyUnion

Back to Top

@BinTreePolyUnion

toc Export of PWA/PWQ function to C-code

Back to Top

@Union

listfunctions Extract list of functions stored with the union.
union Represents a general union of convex sets in MPT
hasfunction Returns true if the union contains given function names.
contains Test if a point is contained inside the union of convex sets.
add Insert set to Union object.
display Overload display for Union class.
feval Evaluates a given function defined over a union of convex sets.
fplot Plot single function over the sets of the Union object.
vertcat Vertical concatenation for union objecs.
remove Remove set from Union object.
horzcat Horizontal concatenation for union objecs.
removefunction Remove function from all sets in the union based on the function name.
removeallfunctions Remove all functions that are associated to this union of convex sets.
getfunction Extract function handle from the union of convex sets.
copy Create a copy of an object derived from the Union class.
plot Plot the union of convex sets.

Back to Top

@PolyUnion

le Test if a union of polyhedra is contained inside another union.
outerapprox Computes outer bounding box for the union of polyhedra
isoverlapping Test if the union of polyhedra contains overlaps.
plus Minkowski addition for union of polyhedra
merge Greedy merging of polyhedra
join Merges arrays of polyunions to one polyunion object.
ge Test if a union of polyhedra contains another union.
minus Pontryagin/Minkowski difference for union of polyhedra
contains Test if a point is contained inside the union of polyhedra in the same dimension.
add Insert Polyhedron to PolyUnion object.
display Overload display for PolyUnion class.
eq Returns true if the set covered by unions of polyhedra U_1 is the same as the set covered by union U_2 and false otherwise.
feval Evaluates a given function defined over a union of polyhedra.
isbounded Test if the union is built from bounded polyhedra.
locatepoint Implementation of a graph search algorithm for a point location problem.
isfulldim Test if the union is built from full-dimensional polyhedra.
toc Export of PWA/PWQ function to C-code
fplot Plot function over the union of polyhedra.
isconnected Test if the union of polyhedra form a connected union.
polyunion Represents a union of polyhedra in the same dimension
convexhull Computes the convex hull for union of polyhedra
reduce Reduces the overlapping union to minimal number of sets.
removefunction Remove function from all Polyhedra in the union based on the function name.
removeallfunctions Remove all functions that are associated to this union of polyhedra.
getfunction Extract function from PolyUnion object.
isconvex Test if the union of polyhedra is convex.
copy Create a new copy of the PolyUnion object.
plot Plot the union of polyhedra.

Back to Top

sets

@ConvexSet

@YSet

@Polyhedron

Back to Top

@ConvexSet

addfunction Attach function to a convex set.
distance Computes the closest distance between the convex set and given point.
outerapprox Computes outer bounding box of the convex set.
separate Computes separating hyperplane between the set and given point.
listfunctions Shows functions attached to a convex set.
hasfunction Returns true if the set contains given function name.
convexset Represets a convex set in MPT
fliplr Revert the order of convex sets in the array.
feval Evaluates a function defined over a convex set or an array thereof.
isbounded Test if a convex set is bounded.
grid Grid the convex set.
fplot Plot a single function over a convex set or over an array of convex sets.
vertcat Vertical concatenation for convex set objecs.
isemptyset Test if a convex set is empty.
horzcat Horizontal concatenation for convex set objecs.
removefunction Remove function associated to a convex set based on the function name.
removeallfunctions Remove all functions that are associated to this set.
support Compute the support of the set in the specified direction.
getfunction Extract function handle from a convex set.
affinehull Computes affine hull of a convex set.
copy Create a copy of an object derived from the ConvexSet class.
plot Plot the convex set.

Back to Top

@YSet

contains Test if the point is contained inside convex set YSet.
display Overload display for YSet class.
yset Representation of a convex set using YALMIP constraints.
project Compute the projection of the point onto this set.
shoot Compute the maximal value of a multiplier in the desired direction.
extreme Compute an extreme point of this set in the given direction.

Back to Top

@Polyhedron

invaffinemap Compute the inverse affine map of the Polyhedron.
distance Compute the distance between the given point/polyhedron and this polyhedron.
le Test if a polyhedron is contained inside polyhedron.
intersect Intersect two polyhedra.
outerapprox Computes outer bounding hypercube of a polyhedron.
b Get b vector from equality description of the Polyhedron.
normalize Normalizes polyhedron in H-representation.
uminus Unitary minus for a polyhedron.
separate Separate a point/polyhedron from another polyhedron.
lt Test if a polyhedron is contained inside polyhedron.
ae Get Ae matrix from equality description of the Polyhedron.
computehrep Compute H-representation of a polyhedron.
volume Compute the volume of the polyhedron.
plus Add a Polyhedron and a vector or Polyhedron.
mldivide Set difference between polyhedra
facetinteriorpoints Compute points that lie on each of the facet of the Polyhedron.
getfacet Extract facet of the polyhedron specified by the inequality index.
affinemap Compute the affine map of the Polyhedron.
minvrep Compute an irredundant V-representation of a polyhedron.
ne Test if a polyhedron is not equal to another polyhedron.
be Get be vector from equality description of the Polyhedron.
meshgrid Generate X-Y grid for 2D bounded polyhedra.
ge Test if a polyhedron is contained inside polyhedron.
minus Subtract a Polyhedron or a vector from a Polyhedron.
ispointed Test if a polyhedron is pointed or not
minhrep Compute an irredundant H-representation of a polyhedron.
isneighbor Test if a polyhedron touches another polyhedron along a given facet.
contains Test if a polyhedron/point is contained inside polyhedron.
isadjacent Test if a polyhedron shares a facet with another polyhedron.
projection Compute the projection of the Polyhedron.
isfullspace Test if a polyhedron represents the whole space \mathbb{R}^n.
display Overload display for Polyhedron class.
a Get A matrix from inequality description of the Polyhedron.
gt Test if a polyhedron is contained inside polyhedron.
eq Returns true if the set covered by polyhedra P is the same as the set covered by S and false otherwise.
project Project a point onto the given polyhedron.
incidencemap Compute the incidence map of this polyhedron.
isbounded Test if a polyhedron is bounded.
mtimes Multiply two polyhedra, or a polyhedron with a matrix or scalar.
computevrep Compute V-representation of a polyhedron.
isfulldim Test if a polyhedron has a non-empty interior.
shoot Maximize along a given ray within the polyhedron.
fplot Plot single function over the polyhedron or array of polyhedra.
polyhedron Create a Polyhedron object.
isemptyset Test if a polyhedron has a non-empty interior.
interiorpoint Compute a point in the relative interior of the Polyhedron.
chebycenter Compute the Chebyshev centre of the Polyhedron.
slice Slice the polyhedron through given dimensions at specified values.
extreme Compute extremal point of a polyhedron in a given direction.
homogenize Compute the homogenization of the given Polyhedron.
affinehull Compute the affine hull of the Polyhedron.
triangulate Triangulation of a polyhedron.
uplus Unitary plus for a polyhedron.
isinside Test if a point is contained inside polyhedron in H-representation.
plot Plot the polyhedron.

Back to Top

functions

@InfNormFunction

@Function

@OneNormFunction

@AffFunction

@NormFunction

@QuadFunction

Back to Top

@InfNormFunction

infnormfunction Class representing inf-norm function.

Back to Top

@Function

sethandle Assign function handle to existing Function object
isemptyfunction Test if the object of the Function class contains a function handle.
display Overload display for Function class.
vertcat Vertical concatenation for Function class.
horzcat Horizontal concatenation for Function class.
function Function representation for MPT

Back to Top

@OneNormFunction

onenormfunction Class representing 1-norm function.

Back to Top

@AffFunction

afffunction Representation of affine functions in the form F*x + g
display Overload display for AffFunction class.

Back to Top

@NormFunction

normfunction Class representing 1- or infinity-norm function.

Back to Top

@QuadFunction

display Overload display for QuadFunction class.
quadfunction Representation of quadratic functions in the form x'*H*x + F*x + g

Back to Top

solvers

mpt_call_cdd A gateway function to CDD solver (without errorchecks)
mpt_call_gurobi A gateway function to GUROBI solver (without errorchecks)
mpt_call_nag A gateway function to the NAG Toolbox LP and QP solvers
mpt_call_lcp A gateway function to LCP solver (without errorchecks)
mpt_call_mpqp A gateway function to MPQP solver (without errorchecks)
mpt_call_clp A gateway function to CLP solver (without errorchecks)
mpt_call_qpoases A gateway function to QPoases solver (without errorchecks)
mpt_solve A gateway function to solve non-parametric optimization problems (without errorchecks)
mpt_call_mplp A gateway function to MPLP solver (without errorchecks)
mpt_call_plcp A gateway function to PLCP solver (without errorchecks)
mpt_call_qpspline A gateway function to QPspline solver (without errorchecks)
mpt_call_linprog A gateway function to LINPROG solver (without errorchecks)
mpt_call_sedumi A gateway function to SEDUMI solver (without errorchecks)
mpt_call_glpk A gateway function to GLPK solver (without errorchecks)
mpt_detect_solvers Searches for installed solvers on the path.
mpt_plcp Parametric linear complementarity solver (PLCP) (without errorchecks)
mpt_call_qpc A gateway function to QPC solver (without errorchecks)
mpt_solvers_options Global option settings for solvers.
mpt_call_cplex A gateway function to CPLEX solver (without errorchecks)
mpt_solvemp A gateway function to solve parametric optimization problems (without errorchecks)
mpt_call_quadprog A gateway function to QUADPROG solver (without errorchecks)

@Opt

Back to Top

@Opt

qp2lcp Transforms LP/QP/MPLP/MPQP to LPC/PLCP
eliminateequations Reduce LP/QP/MPLP/MPQP by removing equality constraints
opt Interface for solving optimization problems
display Overload display for Opt class.
solve The main routine for solving optimization problems
feasibleset Computes the feasible set of a given parametric problem.
copy Creates a copy of the optimization problem given as Opt object.

Back to Top

ui

mpt_import Converts sysStruct and probStruct into an MPT3 prediction model

@MinTimeController

@MPCController

utils

@SystemSignal

@AbstractSystem

@LTISystem

@PWASystem

@EMPCController

@MLDSystem

@AbstractController

@ClosedLoop

@EMinTimeController

Back to Top

@MinTimeController

mintimecontroller Implicit minimum-time MPC controller
evaluate Returns the optimal control action

Back to Top

@MPCController

fromyalmip Converts a custom YALMIP setup to a controller
toexplicit Computes the explicit solution to the MPC optimization problem
evaluate Returns the optimal control action
mpccontroller MPC controller with on-line optimization
toyalmip Converts an MPC problem into YALMIP's constraints and objective

Back to Top

utils

mpt_mpsol2pu Converts a parametric solution generated by solvemp to a PolyUnion object

Back to Top

@SystemSignal

filter_deltamin Lower bound on the increment of a signal
filter_min Lower bound on a signal
filter_deltapenalty Penalizes the increment of a signal
filter_terminalpenalty Penalizes the final predicted state in the MPC problem
systemsignal Class representing variables of a dynamical system
filter_deltamax Upper bound on the increment of a signal
filter_binary Constraints variable to be binary (0/1)
filter_penalty Penalizes the signal in the MPC cost function
filter_softmax Soft upper bound constraint
filter_max Upper bound on a signal
filter_terminalset Adds a polyhedral constraint on the final predicted state
filter_block Adds a move blocking constraint
filter_softmin Soft lower bound constraint
filter_setconstraint Adds a polyhedral constraint
filter_reference Penalizes difference of a signal from a given reference level

Back to Top

@AbstractSystem

output Returns value of the output variables
initialize Sets the internal state of the system
update Updates the internal state using the state-update equation
simulate Simulates evolution of the system
getstates Returns the internal state of the system

Back to Top

@LTISystem

output Returns value of the output variables
initialize Sets the internal state of the system
setdomain Sets the domain of an LTI system
lqrgain Linear-quadratic regulator design for LTI systems
invariantset Computation of invariant sets for linear systems
reachableset Computes forward or backwards reachable sets
update Updates the internal state using the state-update equation
ltisystem Represents linear time-invariant systems
simulate Simulates evolution of the system
lqrset Computes an invariant subset of an LQR controller
getstates Returns the internal state of the system
lqrpenalty Linear-quadratic regulator design for LTI systems

Back to Top

@PWASystem

output Returns value of the output variables
initialize Sets the internal state of the system
invariantset Computation of invariant sets for PWA systems
reachableset Computes forward or backwards reachable sets
update Updates the internal state using the state-update equation
simulate Simulates evolution of the system
tolti Converts the i-th mode of a PWA system to an LTI system
getstates Returns the internal state of the system
pwasystem Represents discrete-time piecewise affine systems

Back to Top

@EMPCController

empccontroller Explicit MPC controller
exporttoc Export the explicit controller to C-code
evaluate Returns the optimal control action

Back to Top

@MLDSystem

output Returns value of the output variables
initialize Sets the internal state of the system
update Updates the internal state using the state-update equation
simulate Simulates evolution of the system
topwa Converts the MLD model into an equivalent PWA form
mldsystem Represents mixed logical dynamical systems
getstates Returns the internal state of the system

Back to Top

@AbstractController

fromyalmip Converts a custom YALMIP setup to a controller
toyalmip Converts an MPC problem into YALMIP's constraints and objective

Back to Top

@ClosedLoop

invariantset Computes the invariant subset of the closed-loop system
tosystem Converts the closed-loop object to an autonomous dynamical system
closedloop Create a closed-loop system.
simulate Simulates the closed-loop system.

Back to Top

@EMinTimeController

emintimecontroller Explicit minimum-time MPC controller
evaluate Returns the optimal control action

Back to Top

demos

mpt_demo_functions1 Demonstration of functions associated to sets
mpt_demo_deployment_onlinempc Application of online MPC controller with the help of Simulink interface
mpt_demo_deployment_explicitmpctracking Application of tracking explicit MPC controller with the help of Simulink interface
mpt_demo_lti2 Demonstrates online MPC for LTI system
mpt_demo_functions2 Demonstration of functions over unions of polyhedra
mpt_demo_lti4 Construction of explicit controller for LTI system
mpt_demo_sets2 Construction and basic properties of sets created in Yalmip
mpt_demo_lti5 Demostration of problem formulation using additional properties.
mpt_demo_opt1 Demonstration for using Opt interface
mpt_demo_sets1 Demonstrates construction and basic properties of the Polyhedron object
mpt_demo_pwa1 Demonstration for modeling PWA systems
mpt_demo_lti3 Demonstrates simulation of the closed-loop system
mpt_demo_deployment_explicitmpc Application of explicit MPC controller with the help of Simulink interface
mpt_demo_unions1 Demo that illustrates working with unions of convex sets
mpt_demo_lti1 Simulation of LTISystem
mpt_demo2 Tour through visualization capabilities of the toolbox
mpt_demo1 Demonstration of basic usage of the geometric library
mpt_demo_unions2 Demo that illustrates working with unions of polyhedra
mpt_demo_sets3 Demo that illustrates operations on polyhedra

Back to Top