MPC#
- class MPC(model, settings=None)[source]#
Bases:
Optimizer
,IteratedVariables
Model predictive controller.
New in version >v4.5.1: New interface to settings. The class has a property called
settings
which accesses an instance ofMPCSettings
(please see this documentation for a list of available settings). Settings are now chosen as:mpc.settings.n_horizon = 20
Previously, settings were passed to
set_param()
. This method is still available and wraps the new interface. The new method has important advantages:The
mpc.settings
attribute can be printed to see the current configuration.Context help is available in most IDEs (e.g. VS Code) to see the available _settings, the type and a description.
The
MPCSettings
class has convenient methods, such asMPCSettings.supress_ipopt_output()
to silence the solver.
For general information on model predictive control, please read our background article .
The MPC controller extends the
do_mpc.optimizer.Optimizer
base class (which is also used for thedo_mpc.estimator.MHE
estimator).Use this class to configure and run the MPC controller based on a previously configured
do_mpc.model.Model
instance.Configuration and setup:
Configuring and setting up the MPC controller involves the following steps:
Configure the MPC controller with
MPCSettings
. The MPC instance has the attributesettings
which is an instance ofMPCSettings
.Set the objective of the control problem with
set_objective()
andset_rterm()
Set upper and lower bounds with
bounds
(optional).Set further (non-linear) constraints with
set_nl_cons()
(optional).Use the low-level API (
get_p_template()
andset_p_fun()
) or high level API (set_uncertainty_values()
) to create scenarios for robust MPC (optional).Use
get_tvp_template()
andset_tvp_fun()
to create a method to obtain new time-varying parameters at each iteration.To finalize the class configuration there are two routes. The default approach is to call
setup()
. For deep customization use the combination ofprepare_nlp()
andcreate_nlp()
. See graph below for an illustration of the process.
- Parameters:
model (
Union
[Model
,LinearModel
]) – Model_settings – Settings for the MPC controller. See
MPCSettings
for details.
Warning
Before running the controller, make sure to supply a valid initial guess for all optimized variables (states, algebraic states and inputs). Simply set the initial values of
x0
,z0
andu0
and then callset_initial_guess()
.To take full control over the initial guess, modify the values of
opt_x_num
.During runtime call
make_step()
with the current state \(x\) to obtain the optimal control input \(u\).- Parameters:
settings (
Optional
[MPCSettings
]) –
Methods#
compile_nlp#
- compile_nlp(self, overwrite=False, cname='nlp.c', libname='nlp.so', compiler_command=None)#
Compile the NLP. This may accelerate the optimization. As compilation is time consuming, the default option is to NOT overwrite (
overwrite=False
) an existing compilation. If an existing compilation with the namelibname
is found, it is used. This can be dangerous, if the NLP has changed (user tweaked the cost function, the model etc.).Warning
This feature is experimental and currently only supported on Linux and MacOS.
What happens here?
The NLP is written to a C-file (
cname
)The C-File (
cname
) is compiled. The custom compiler uses:
gcc -fPIC -shared -O1 {cname} -o {libname}
The compiled library is linked to the NLP. This overwrites the original NLP. Options from the previous NLP (e.g. linear solver) are kept.
self.S = nlpsol('solver_compiled', 'ipopt', f'{libname}', self.nlpsol_opts)
- Parameters:
overwrite (
bool
) – If True, the existing compiled NLP will be overwritten.cname (
str
) – Name of the C file that will be exported.libname (
str
) – Name of the shared library that will be created after compilation.compiler_command (
str
) – Command to use for compiling. If None, the default compiler command will be used. Please make sure to use matching strings forlibname
when supplying your custom compiler command.
- Return type:
None
copy_struct#
- copy_struct(self, original_struct)#
Create a copy of a given CasADi struct. This method is called during initialization to copy the struct containing the system inputs
u
. The copied structure is an identical copy of the input structure and is used inset_rterm()
as a symbolic variable for past inputs.- Parameters:
original_struct – A CasADi struct (either SXStruct or MXStruct).
- Returns:
A new CasADi struct with the same structure and entry names as the original.
create_nlp#
- create_nlp(self)#
Create the optimization problem. Typically, this method is called internally from
setup()
.Users should only call this method if they intend to modify the objective with
nlp_obj
, the constraints withnlp_cons
,nlp_cons_lb
andnlp_cons_ub
.To finish the setup process, users MUST call
create_nlp()
afterwards.Note
Do NOT call
setup()
if you intend to go the manual route withprepare_nlp()
andcreate_nlp()
.Note
Only AFTER calling
prepare_nlp()
the previously mentionned attributesnlp_obj
,nlp_cons
,nlp_cons_lb
,nlp_cons_ub
become available.- Returns:
None
– None
get_p_template#
- get_p_template(self, n_combinations)#
Obtain output template for
set_p_fun()
.Low level API method to set user defined scenarios for robust multi-stage MPC by defining an arbitrary number of combinations for the parameters defined in the model. For more details on robust multi-stage MPC please read our background article
The method returns a structured object which is initialized with all zeros. Use this object to define values of the parameters for an arbitrary number of scenarios (defined by
n_combinations
).This structure (with numerical values) should be used as the output of the
p_fun
function which is set to the class withset_p_fun()
.Use the combination of
get_p_template()
andset_p_template()
as a more adaptable alternative toset_uncertainty_values()
.Note
We advice less experienced users to use
set_uncertainty_values()
as an alterntive way to configure the scenario-tree for robust multi-stage MPC.Example:
# in model definition: alpha = model.set_variable(var_type='_p', var_name='alpha') beta = model.set_variable(var_type='_p', var_name='beta') ... # in MPC configuration: n_combinations = 3 p_template = MPC.get_p_template(n_combinations) p_template['_p',0] = np.array([1,1]) p_template['_p',1] = np.array([0.9, 1.1]) p_template['_p',2] = np.array([1.1, 0.9]) def p_fun(t_now): return p_template MPC.set_p_fun(p_fun)
Note the nominal case is now: alpha = 1, beta = 1 which is determined by the order in the arrays above (first element is nominal).
- Parameters:
n_combinations (
int
) – Define the number of combinations for the uncertain parameters for robust MPC.- Return type:
None
get_tvp_template#
- get_tvp_template(self)#
Obtain output template for
set_tvp_fun()
.The method returns a structured object with
n_horizon+1
elements, and a set of time-varying parameters (as defined indo_mpc.model.Model
) for each of these instances. The structure is initialized with all zeros. Use this object to define values of the time-varying parameters.This structure (with numerical values) should be used as the output of the
tvp_fun
function which is set to the class withset_tvp_fun()
. Use the combination ofget_tvp_template()
andset_tvp_fun()
.Example:
# in model definition: alpha = model.set_variable(var_type='_tvp', var_name='alpha') beta = model.set_variable(var_type='_tvp', var_name='beta') ... # in optimizer configuration: tvp_temp_1 = optimizer.get_tvp_template() tvp_temp_1['_tvp', :] = np.array([1,1]) tvp_temp_2 = optimizer.get_tvp_template() tvp_temp_2['_tvp', :] = np.array([0,0]) def tvp_fun(t_now): if t_now<10: return tvp_temp_1 else: tvp_temp_2 optimizer.set_tvp_fun(tvp_fun)
- Returns:
Union
[SXStruct
,MXStruct
] – Casadi SX or MX structure
make_step#
- make_step(self, x0)#
Main method of the class during runtime. This method is called at each timestep and returns the control input for the current initial state
x0
.The method prepares the MHE by setting the current parameters, calls
solve()
and updates thedo_mpc.data.Data
object.- Parameters:
x0 (
Union
[ndarray
,DM
]) – Current state of the system.- Returns:
ndarray
– u0
prepare_nlp#
- prepare_nlp(self)#
Prepare the optimization problem. Typically, this method is called internally from
setup()
.Users should only call this method if they intend to modify the objective with
nlp_obj
, the constraints withnlp_cons
,nlp_cons_lb
andnlp_cons_ub
.To finish the setup process, users MUST call
create_nlp()
afterwards.Note
Do NOT call
setup()
if you intend to go the manual route withprepare_nlp()
andcreate_nlp()
.Note
Only AFTER calling
prepare_nlp()
the previously mentionned attributesnlp_obj
,nlp_cons
,nlp_cons_lb
,nlp_cons_ub
become available.- Returns:
None
– None
reset_history#
- reset_history(self)#
Reset the history of the optimizer. All data from the
do_mpc.data.Data
instance is removed.- Return type:
None
set_initial_guess#
- set_initial_guess(self)#
Initial guess for optimization variables. Uses the current class attributes
x0
,z0
andu0
to create the initial guess. The initial guess is simply the initial values for all \(k=0,\dots,N\) instances of \(x_k\), \(u_k\) and \(z_k\). :rtype:None
Note
The initial guess is fully customizable by directly setting values on the class attribute:
opt_x_num
.
set_nl_cons#
- set_nl_cons(self, expr_name, expr, ub=inf, soft_constraint=False, penalty_term_cons=1, maximum_violation=inf)#
Introduce new constraint to the class. Further constraints are optional. Expressions must be formulated with respect to
_x
,_u
,_z
,_tvp
,_p
. They are implemented as:\[m(x,u,z,p_{\text{tv}}, p) \leq m_{\text{ub}}\]Setting the flag
soft_constraint=True
will introduce slack variables \(\epsilon\), such that:\[\begin{split}m(x,u,z,p_{\text{tv}}, p)-\epsilon &\leq m_{\text{ub}},\\ 0 &\leq \epsilon \leq \epsilon_{\text{max}},\end{split}\]Slack variables are added to the cost function and multiplied with the supplied penalty term. This formulation makes constraints soft, meaning that a certain violation is tolerated and does not lead to infeasibility. Typically, high values for the penalty are suggested to avoid significant violation of the constraints.
- Parameters:
expr_name (
str
) – Arbitrary name for the given expression. Names are used for key word indexing.expr (
Union
[SX
,MX
]) – CasADi SX or MX function depending on_x
,_u
,_z
,_tvp
,_p
.ub (
float
) – Upper boundsoft_constraint (
bool
) – Flag to enable soft constraintpenalty_term_cons (
int
) – Penalty term constantmaximum_violation (
float
) – Maximum violation
- Raises:
assertion – expr_name must be str
assertion – expr must be a casadi SX or MX type
- Returns:
Union
[SX
,MX
] – Returns the newly created expression. Expression can be used e.g. for the RHS.
set_objective#
- set_objective(self, mterm=None, lterm=None)#
Sets the objective of the optimal control problem (OCP). We introduce the following cost function:
\[J(x,u,z) = \sum_{k=0}^{N}\left(\underbrace{l(x_k,z_k,u_k,p_k,p_{\text{tv},k})}_{\text{lagrange term}} + \underbrace{\Delta u_k^T R \Delta u_k}_{\text{r-term}}\right) + \underbrace{m(x_{N+1})}_{\text{meyer term}}\]which is applied to the discrete-time model AND the discretized continuous-time model. For discretization we use orthogonal collocation on finite elements . The cost function is evaluated only on the first collocation point of each interval.
set_objective()
is used to set the \(l(x_k,z_k,u_k,p_k,p_{\text{tv},k})\) (lterm
) and \(m(x_{N+1})\) (mterm
), whereN
is the prediction horizon. Please seeset_rterm()
for the penalization of the control inputs.- Parameters:
lterm (
Union
[SX
,MX
]) – Stage cost - scalar symbolic expression with respect to_x
,_u
,_z
,_tvp
,_p
mterm (
Union
[SX
,MX
]) – Terminal cost - scalar symbolic expression with respect to_x
and_p
- Raises:
assertion – mterm must have
shape=(1,1)
(scalar expression)assertion – lterm must have
shape=(1,1)
(scalar expression)
- Return type:
None
set_p_fun#
- set_p_fun(self, p_fun)#
Set function which returns parameters. The
p_fun
is called at each optimization step to get the current values of the (uncertain) parameters.This is the low-level API method to set user defined scenarios for robust multi-stage MPC by defining an arbitrary number of combinations for the parameters defined in the model. For more details on robust multi-stage MPC please read our background article .
The method takes as input a function, which MUST return a structured object, based on the defined parameters and the number of combinations. The defined function has time as a single input.
Obtain this structured object first, by calling
get_p_template()
.Use the combination of
get_p_template()
andset_p_fun()
as a more adaptable alternative toset_uncertainty_values()
.Note
We advice less experienced users to use
set_uncertainty_values()
as an alterntive way to configure the scenario-tree for robust multi-stage MPC.Example:
# in model definition: alpha = model.set_variable(var_type='_p', var_name='alpha') beta = model.set_variable(var_type='_p', var_name='beta') ... # in MPC configuration: n_combinations = 3 p_template = MPC.get_p_template(n_combinations) p_template['_p',0] = np.array([1,1]) p_template['_p',1] = np.array([0.9, 1.1]) p_template['_p',2] = np.array([1.1, 0.9]) def p_fun(t_now): return p_template MPC.set_p_fun(p_fun)
Note the nominal case is now:
alpha = 1
,beta = 1
which is determined by the order in the arrays above (first element is nominal).- Parameters:
p_fun (
Callable
[[float
],Union
[SXStruct
,MXStruct
]]) – Function which returns a structure with numerical values. Must be the same structure as obtained fromget_p_template()
. Function must have a single input (time).- Return type:
None
set_param#
- set_param(self, **kwargs)#
Set the parameters of the
MPC
class. Parameters must be passed as pairs of valid keywords and respective argument. :rtype:None
Deprecated since version >v4.5.1: This function will be deprecated in the future
Note
A comprehensive list of all available parameters can be found in
do_mpc.controller.MPCSettings
For example:
mpc._settings.n_horizon = 20
The old interface, as shown in the example below, can still be accessed until further notice.
mpc.set_param(n_horizon = 20)
Note
The only required parameters are
n_horizon
andt_step
. All other parameters are optional.Note
We highly suggest to change the linear solver for IPOPT from mumps to MA27. Any available linear solver can be set using
do_mpc.controller.MPCSettings.set_linear_solver()
. For more details, please check thedo_mpc.controller.MPCSettings
.Note
The output of IPOPT can be suppressed
do_mpc.controller.MPCSettings.supress_ipopt_output()
. For more details, please check thedo_mpc.controller.MPCSettings
.
set_rterm#
- set_rterm(self, rterm=None, **kwargs)#
Set the penality factor for the inputs. Call this function with keyword argument refering to the input names in
model
and the penalty factor as the respective value.We define for \(i \in \mathbb{I}\), where \(\mathbb{I}\) is the set of inputs and all \(k=0,\dots, N\) where \(N\) denotes the horizon:
\[\Delta u_{k,i} = u_{k,i} - u_{k-1,i}\]and add:
\[\sum_{k=0}^N \sum_{i \in \mathbb{I}} r_{i}\Delta u_{k,i}^2,\]the weighted squared cost to the MPC objective function.
Example:
# in model definition: Q_heat = model.set_variable(var_type='_u', var_name='Q_heat') F_flow = model.set_variable(var_type='_u', var_name='F_flow') ... # in MPC configuration: MPC.set_rterm(Q_heat = 10) MPC.set_rterm(F_flow = 10) # or alternatively: MPC.set_rterm(Q_heat = 10, F_flow = 10)
In the above example we set \(r_{Q_{\text{heat}}}=10\) and \(r_{F_{\text{flow}}}=10\).
Note
As of version 4.6.3, set_rterm can be called with a user-defined penalty that overrides the default quadratic penalty term. Note that the inputs of the previous calculation step are stored in the mpc class and cannot be called from the model, see example.
u_prev
is generated automatically when theMPC
class is initialized.- Parameters:
rterm (
Union
[SX
,MX
]) – Penalty term on input change - scalar symbolic expression with respect to_x
,_u
,_u_prev
,_u_prev
,_tvp
,_p
- Return type:
None
Example:
# in model definition: Q_heat = model.set_variable(var_type='_u', var_name='Q_heat') F_flow = model.set_variable(var_type='_u', var_name='F_flow') ... # in MPC configuration: rterm = (model.u['Q_heat'] - mpc.u_prev['Q_heat'])**2 + (model.u['F_flow'] - mpc.u_prev['F_flow'])**2 MPC.set_rterm(rterm)
Note
For \(k=0\) we obtain \(u_{-1}\) from the previous solution.
set_tvp_fun#
- set_tvp_fun(self, tvp_fun)#
Set function which returns time-varying parameters.
The
tvp_fun
is called at each optimization step to get the current prediction of the time-varying parameters. The supplied function must be callable with the current time as the only input. Furthermore, the function must return a CasADi structured object which is based on the horizon and on the model definition. The structure can be obtained withget_tvp_template()
.Example:
# in model definition: alpha = model.set_variable(var_type='_tvp', var_name='alpha') beta = model.set_variable(var_type='_tvp', var_name='beta') ... # in optimizer configuration: tvp_temp_1 = optimizer.get_tvp_template() tvp_temp_1['_tvp', :] = np.array([1,1]) tvp_temp_2 = optimizer.get_tvp_template() tvp_temp_2['_tvp', :] = np.array([0,0]) def tvp_fun(t_now): if t_now<10: return tvp_temp_1 else: tvp_temp_2 optimizer.set_tvp_fun(tvp_fun)
Note
The method
set_tvp_fun()
. must be called prior to setup IF time-varying parameters are defined in the model. It is not required to call the method if no time-varying parameters are defined.- Parameters:
tvp_fun (
Callable
[[float
],Union
[SXStruct
,MXStruct
]]) – Function that returns the predicted tvp values at each timestep. Must have single input (float) and return astructure3.DMStruct
(obtained withget_tvp_template()
).- Return type:
None
set_uncertainty_values#
- set_uncertainty_values(self, **kwargs)#
Define scenarios for the uncertain parameters. High-level API method to conveniently set all possible scenarios for multistage MPC. For more details on robust multi-stage MPC please read our background article .
Pass a number of keyword arguments, where each keyword refers to a user defined parameter name from the model definition. The value for each parameter must be an array (or list), with an arbitrary number of possible values for this parameter. The first element is the nominal case.
Example:
# in model definition: alpha = model.set_variable(var_type='_p', var_name='alpha') beta = model.set_variable(var_type='_p', var_name='beta') gamma = model.set_variable(var_type='_p', var_name='gamma') ... # in MPC configuration: alpha_var = np.array([1., 0.9, 1.1]) beta_var = np.array([1., 1.05]) MPC.set_uncertainty_values( alpha = alpha_var, beta = beta_var )
Note
Parameters that are not imporant for the MPC controller (e.g. MHE tuning matrices) can be ignored with the new interface (see
gamma
in the example above).Note the nominal case is now:
alpha = 1
,beta = 1
which is determined by the order in the arrays above (first element is nominal).- Parameters:
kwargs – Arbitrary number of keyword arguments.
- Return type:
None
setup#
- setup(self)#
Setup the MPC class. Internally, this method will create the MPC optimization problem under consideration of the supplied dynamic model and the given
MPC
class instance configuration.The
setup()
method can be called again after changing the configuration (e.g. adapting bounds) and will simply overwrite the previous optimization problem. :rtype:None
Note
After this call, the
solve()
andmake_step()
method is applicable.Warning
The
setup()
method may take a while depending on the size of your MPC problem. Note that especially for robust multi-stage MPC with a long robust horizon and many possible combinations of the uncertain parameters very large problems will arise.For more details on robust multi-stage MPC please read our background article .
solve#
- solve(self)#
Solves the optmization problem.
The current problem is defined by the parameters in the
opt_p_num
CasADi structured Data.Typically,
opt_p_num
is prepared for the current iteration in themake_step()
method. It is, however, valid and possible to directly set paramters inopt_p_num
before callingsolve()
.The method updates the
opt_p_num
andopt_x_num
attributes of the class. By resettingopt_x_num
to the current solution, the method implicitly enables warmstarting the optimizer for the next iteration, since this vector is always used as the initial guess. :rtype:None
Warning
The method is part of the public API but it is generally not advised to use it. Instead we recommend to call
make_step()
at each iterations, which acts as a wrapper forsolve()
.- Raises:
asssertion – Optimizer was not setup yet.
Attributes#
bounds#
- MPC.bounds#
Query and set bounds of the optimization variables. The
bounds()
method is an indexed property, meaning getting and setting this property requires an index and calls this function. The power index (elements are separated by commas) must contain atleast the following elements:order
index name
valid options
1
bound type
lower
andupper
2
variable type
_x
,_u
and_z
(and_p_est
for MHE)3
variable name
Names defined in
do_mpc.model.Model
.Further indices are possible (but not neccessary) when the referenced variable is a vector or matrix.
Example:
# Set with: optimizer.bounds['lower','_x', 'phi_1'] = -2*np.pi optimizer.bounds['upper','_x', 'phi_1'] = 2*np.pi # Query with: optimizer.bounds['lower','_x', 'phi_1']
lb_opt_x#
- MPC.lb_opt_x#
Query and modify the lower bounds of all optimization variables
opt_x
. This is a more advanced method of setting bounds on optimization variables of the MPC/MHE problem. Users with less experience are advised to usebounds
instead.The attribute returns a nested structure that can be indexed using powerindexing. Please refer to
opt_x
for more details.Note
The attribute automatically considers the scaling variables when setting the bounds. See
scaling
for more details.Note
Modifications must be done after calling
prepare_nlp()
orsetup()
respectively.
nlp_cons#
- MPC.nlp_cons#
Query and modify (symbolically) the NLP constraints. Use the variables in
opt_x
andopt_p
.Prior to calling
create_nlp()
this attribute returns a list of symbolic constraints. After callingcreate_nlp()
this attribute returns the concatenation of this list and the attribute cannot be altered anymore.It is advised to append to the current list of
nlp_cons
:mpc.prepare_nlp() # Create new constraint: Input at timestep 0 and 1 must be identical. extra_cons = mpc.opt_x['_u', 0, 0]-mpc.opt_x['_u',1, 0] mpc.nlp_cons.append( extra_cons ) # Create appropriate upper and lower bound (here they are both 0 to create an equality constraint) mpc.nlp_cons_lb.append(np.zeros(extra_cons.shape)) mpc.nlp_cons_ub.append(np.zeros(extra_cons.shape)) mpc.create_nlp()
See the documentation of
opt_x
andopt_p
on how to query these attributes.Warning
This is a VERY low level feature and should be used with extreme caution. It is easy to break the code.
Be especially careful NOT to accidentially overwrite the default objective.
Note
Modifications must be done after calling
prepare_nlp()
and before callingcreate_nlp()
nlp_cons_lb#
- MPC.nlp_cons_lb#
Query and modify the lower bounds of the
nlp_cons
.Prior to calling
create_nlp()
this attribute returns a list of lower bounds matching the list of constraints obtained withnlp_cons
. After callingcreate_nlp()
this attribute returns the concatenation of this list.Values for lower (and upper) bounds MUST be added when adding new constraints to
nlp_cons
.Warning
This is a VERY low level feature and should be used with extreme caution. It is easy to break the code.
Note
Modifications must be done after calling
prepare_nlp()
nlp_cons_ub#
- MPC.nlp_cons_ub#
Query and modify the upper bounds of the
nlp_cons
.Prior to calling
create_nlp()
this attribute returns a list of upper bounds matching the list of constraints obtained withnlp_cons
. After callingcreate_nlp()
this attribute returns the concatenation of this list.Values for upper (and lower) bounds MUST be added when adding new constraints to
nlp_cons
.Warning
This is a VERY low level feature and should be used with extreme caution. It is easy to break the code.
Note
Modifications must be done after calling
prepare_nlp()
nlp_obj#
- MPC.nlp_obj#
Query and modify (symbolically) the NLP objective function. Use the variables in
opt_x
andopt_p
.It is advised to add to the current objective, e.g.:
mpc.prepare_nlp() # Modify the objective mpc.nlp_obj += sum1(vertcat(*mpc.opt_x['_x', -1, 0])**2) # Finish creating the NLP mpc.create_nlp()
See the documentation of
opt_x
andopt_p
on how to query these attributes.Warning
This is a VERY low level feature and should be used with extreme caution. It is easy to break the code.
Be especially careful NOT to accidentially overwrite the default objective.
Note
Modifications must be done after calling
prepare_nlp()
and before callingcreate_nlp()
opt_p#
- MPC.opt_p#
Full structure of (symbolic) MPC parameters.
The attribute is a CasADi numeric structure with nested power indices. It can be indexed as follows:
# initial state: opt_p['_x0', _x_name] # uncertain scenario parameters opt_p['_p', scenario, _p_name] # time-varying parameters: opt_p['_tvp', time_step, _tvp_name] # input at time k-1: opt_p['_u_prev', time_step, scenario]
The names refer to those given in the
do_mpc.model.Model
configuration. Further indices are possible, if the variables are itself vectors or matrices.Warning
Do not tweak or overwrite this attribute unless you known what you are doing.
Note
The attribute is populated when calling
setup()
orprepare_nlp()
opt_p_num#
- MPC.opt_p_num#
Full MPC parameter vector.
This attribute is used when calling the MPC solver to pass all required parameters, including
initial state
uncertain scenario parameters
time-varying parameters
previous input sequence
do-mpc handles setting these parameters automatically in the
make_step()
method. However, you can set these values manually and directly callsolve()
.The attribute is a CasADi numeric structure with nested power indices. It can be indexed as follows:
# initial state: opt_p_num['_x0', _x_name] # uncertain scenario parameters opt_p_num['_p', scenario, _p_name] # time-varying parameters: opt_p_num['_tvp', time_step, _tvp_name] # input at time k-1: opt_p_num['_u_prev', time_step, scenario]
The names refer to those given in the
do_mpc.model.Model
configuration. Further indices are possible, if the variables are itself vectors or matrices.Warning
Do not tweak or overwrite this attribute unless you known what you are doing.
Note
The attribute is populated when calling
setup()
opt_x#
- MPC.opt_x#
Full structure of (symbolic) MPC optimization variables.
The attribute is a CasADi symbolic structure with nested power indices. It can be indexed as follows:
# dynamic states: opt_x['_x', time_step, scenario, collocation_point, _x_name] # algebraic states: opt_x['_z', time_step, scenario, collocation_point, _z_name] # inputs: opt_x['_u', time_step, scenario, _u_name] # slack variables for soft constraints: opt_x['_eps', time_step, scenario, _nl_cons_name]
The names refer to those given in the
do_mpc.model.Model
configuration. Further indices are possible, if the variables are itself vectors or matrices.The attribute can be used to alter the objective function or constraints of the NLP.
How to query?
Querying the structure is more complicated than it seems at first look because of the scenario-tree used for robust MPC. To obtain all collocation points for the finite element at time-step \(k\) and scenario \(b\) use:
horzcat(*[mpc.opt_x['_x',k,b,-1]]+mpc.opt_x['_x',k+1,b,:-1])
Due to the multi-stage formulation at any given time \(k\) we can have multiple future scenarios. However, there is only exactly one scenario that lead to the current node in the tree. Thus the collocation points associated to the finite element \(k\) lie in the past.
The concept is illustrated in the figure below:
Note
The attribute
opt_x
carries the scaled values of all variables.Note
The attribute is populated when calling
setup()
orprepare_nlp()
opt_x_num#
- MPC.opt_x_num#
Full MPC solution and initial guess.
This is the core attribute of the MPC class. It is used as the initial guess when solving the optimization problem and then overwritten with the current solution.
The attribute is a CasADi numeric structure with nested power indices. It can be indexed as follows:
# dynamic states: opt_x_num['_x', time_step, scenario, collocation_point, _x_name] # algebraic states: opt_x_num['_z', time_step, scenario, collocation_point, _z_name] # inputs: opt_x_num['_u', time_step, scenario, _u_name] # slack variables for soft constraints: opt_x_num['_eps', time_step, scenario, _nl_cons_name]
The names refer to those given in the
do_mpc.model.Model
configuration. Further indices are possible, if the variables are itself vectors or matrices.The attribute can be used to manually set a custom initial guess or for debugging purposes.
How to query?
Querying the structure is more complicated than it seems at first look because of the scenario-tree used for robust MPC. To obtain all collocation points for the finite element at time-step \(k\) and scenario \(b\) use:
horzcat(*[mpc.opt_x_num['_x',k,b,-1]]+mpc.opt_x_num['_x',k+1,b,:-1])
Due to the multi-stage formulation at any given time \(k\) we can have multiple future scenarios. However, there is only exactly one scenario that lead to the current node in the tree. Thus the collocation points associated to the finite element \(k\) lie in the past.
The concept is illustrated in the figure below:
Note
The attribute
opt_x_num
carries the scaled values of all variables. Seeopt_x_num_unscaled
for the unscaled values (these are not used as the initial guess).Warning
Do not tweak or overwrite this attribute unless you known what you are doing.
Note
The attribute is populated when calling
setup()
scaling#
- MPC.scaling#
Query and set scaling of the optimization variables. The
Optimizer.scaling()
method is an indexed property, meaning getting and setting this property requires an index and calls this function. The power index (elements are seperated by comas) must contain atleast the following elements:order
index name
valid options
1
variable type
_x
,_u
and_z
(and_p_est
for MHE)2
variable name
Names defined in
do_mpc.model.Model
.Further indices are possible (but not neccessary) when the referenced variable is a vector or matrix.
Example:
# Set with: optimizer.scaling['_x', 'phi_1'] = 2 optimizer.scaling['_x', 'phi_2'] = 2 # Query with: optimizer.scaling['_x', 'phi_1']
Scaling factors \(a\) affect the MHE / MPC optimization problem. The optimization variables are scaled variables:
\[\bar\phi = \frac{\phi}{a_{\phi}} \quad \forall \phi \in [x, u, z, p_{\text{est}}]\]Scaled variables are used to formulate the bounds \(\bar\phi_{lb} \leq \bar\phi_{ub}\) and for the evaluation of the ODE. For the objective function and the nonlinear constraints the unscaled variables are used. The algebraic equations are also not scaled.
Note
Scaling the optimization problem is suggested when states and / or inputs take on values which differ by orders of magnitude.
settings#
- MPC.settings#
All necessary parameters of the mpc formulation.
This is a core attribute of the MPC class. It is used to set and change parameters when setting up the controller by accessing an instance of
MPCSettings
.Example to change settings:
MPC.settings.n_horizon = 15
Note
Settings cannot be updated after calling
do_mpc.controller.MPC.setup()
.For a detailed list of all available parameters see
MPCSettings
.
t0#
- MPC.t0#
Current time marker of the class. Use this property to set of query the time.
Set with
int
,float
,numpy.ndarray
orcasadi.DM
type.
terminal_bounds#
- MPC.terminal_bounds#
Query and set the terminal bounds for the states. The
terminal_bounds()
method is an indexed property, meaning getting and setting this property requires an index and calls this function. The power index (elements are seperated by commas) must contain at least the following elements:order
index name
valid options
1
bound type
lower
andupper
2
variable name
Names defined in
do_mpc.model.Model
.Further indices are possible (but not neccessary) when the referenced variable is a vector or matrix.
Example:
# Set with: optimizer.terminal_bounds['lower', 'phi_1'] = -2*np.pi optimizer.terminal_bounds['upper', 'phi_1'] = 2*np.pi # Query with: optimizer.terminal_bounds['lower', 'phi_1']
u0#
- MPC.u0#
Initial input and current iterate. This is the numerical structure holding the information about the current input in the class. The property can be indexed according to the model definition.
Example:
model = do_mpc.model.Model('continuous') model.set_variable('_u','heating', shape=(4,1)) ... mhe = do_mpc.estimator.MHE(model) # or mpc = do_mpc.estimator.MPC(model) # Get or set current value of variable: mpc.u0['heating', 0] # 0th element of variable mpc.u0['heating'] # all elements of variable mpc.u0['heating', 0:2] # 0th and 1st element
Useful CasADi symbolic structure methods:
.shape
.keys()
.labels()
ub_opt_x#
- MPC.ub_opt_x#
Query and modify the lower bounds of all optimization variables
opt_x
. This is a more advanced method of setting bounds on optimization variables of the MPC/MHE problem. Users with less experience are advised to usebounds
instead.The attribute returns a nested structure that can be indexed using powerindexing. Please refer to
opt_x
for more details.Note
The attribute automatically considers the scaling variables when setting the bounds. See
scaling
for more details.Note
Modifications must be done after calling
prepare_nlp()
orsetup()
respectively.
x0#
- MPC.x0#
Initial state and current iterate. This is the numerical structure holding the information about the current states in the class. The property can be indexed according to the model definition.
Example:
model = do_mpc.model.Model('continuous') model.set_variable('_x','temperature', shape=(4,1)) ... mhe = do_mpc.estimator.MHE(model) # or mpc = do_mpc.estimator.MPC(model) # Get or set current value of variable: mpc.x0['temperature', 0] # 0th element of variable mpc.x0['temperature'] # all elements of variable mpc.x0['temperature', 0:2] # 0th and 1st element
Useful CasADi symbolic structure methods:
.shape
.keys()
.labels()
z0#
- MPC.z0#
Initial algebraic state and current iterate. This is the numerical structure holding the information about the current algebraic states in the class. The property can be indexed according to the model definition.
Example:
model = do_mpc.model.Model('continuous') model.set_variable('_z','temperature', shape=(4,1)) ... mhe = do_mpc.estimator.MHE(model) # or mpc = do_mpc.estimator.MPC(model) # Get or set current value of variable: mpc.z0['temperature', 0] # 0th element of variable mpc.z0['temperature'] # all elements of variable mpc.z0['temperature', 0:2] # 0th and 1st element
Useful CasADi symbolic structure methods:
.shape
.keys()
.labels()