MPCSettings#

class MPCSettings(t_step=None, n_horizon=None, n_robust=0, open_loop=False, use_terminal_bounds=False, state_discretization='collocation', collocation_type='radau', collocation_deg=2, collocation_ni=1, nl_cons_check_colloc_points=False, nl_cons_single_slack=False, cons_check_colloc_points=True, store_full_solution=False, store_lagr_multiplier=True, store_solver_stats=<factory>, nlpsol_opts=<factory>)[source]#

Bases: ControllerSettings

Settings for do_mpc.controller.MPC. The do_mpc.controller.MPC automatically creates an instance of type MPCSettings and adds it to its class attributes.

Example to change settings:

mpc.settings.n_horizon = 20

Note

Settings cannot be updated after calling do_mpc.controller.MPC.setup().

Parameters:
  • t_step (float) –

  • n_horizon (int) –

  • n_robust (int) –

  • open_loop (bool) –

  • use_terminal_bounds (bool) –

  • state_discretization (str) –

  • collocation_type (str) –

  • collocation_deg (int) –

  • collocation_ni (int) –

  • nl_cons_check_colloc_points (bool) –

  • nl_cons_single_slack (bool) –

  • cons_check_colloc_points (bool) –

  • store_full_solution (bool) –

  • store_lagr_multiplier (bool) –

  • store_solver_stats (List[str]) –

  • nlpsol_opts (Dict) –

Methods#

check_for_mandatory_settings#

check_for_mandatory_settings(self)#

Method to assert the necessary settings required to design do_mpc.controller.MPC

set_linear_solver#

set_linear_solver(self, solver_name='MA27')#

Method to set the linear solver to MA27.

This method enables to set the linear solver to MA27. This change in many cases will drastically boost the speed of do-mpc.

Example:

mpc.settings.set_linear_solver(solver_name = "MA27")
Parameters:

solver_name (str) – Specify the linear solver name

supress_ipopt_output#

supress_ipopt_output(self)#

Method to supress the ipopt solver output.

This method set the revelvant settings in the ipopt solver in order to supress the output log.

Attributes#

collocation_deg#

MPCSettings.collocation_deg: int = 2#

Choose the collocation degree for continuous models with collocation as state discretization.

collocation_ni#

MPCSettings.collocation_ni: int = 1#

For orthogonal collocation choose the number of finite elements for the states within a time-step (and during constant control input).

Can be used to avoid high-order polynomials.

collocation_type#

MPCSettings.collocation_type: str = 'radau'#

Choose the collocation type for continuous models with collocation as state discretization.

Note

Currently only 'radau' is available.

cons_check_colloc_points#

MPCSettings.cons_check_colloc_points: bool = True#

For orthogonal collocation choose whether the linear bounds set with do_mpc.controller.MPC.bounds are evaluated once per finite Element or for each collocation point.

n_horizon#

MPCSettings.n_horizon: int = None#

Prediction horizon of the optimal control problem.

Parameter must be set by user

n_robust#

MPCSettings.n_robust: int = 0#

Robust horizon for robust scenario-tree MPC.

Note

Optimization problem grows exponentially with n_robust.

nl_cons_check_colloc_points#

MPCSettings.nl_cons_check_colloc_points: bool = False#

For orthogonal collocation choose whether the nonlinear bounds set with do_mpc.controller.MPC.set_nl_cons() are evaluated once per finite Element or for each collocation point.

nl_cons_single_slack#

MPCSettings.nl_cons_single_slack: bool = False#

If True, soft-constraints set with do_mpc.controller.MPC.set_nl_cons() introduce only a single slack variable for the entire horizon.

open_loop#

MPCSettings.open_loop: bool = False#

Setting for scenario-tree MPC.

Note

If the parameter is False, for each timestep AND scenario an individual control input is computed. If set to True, the same control input is used for each scenario.

state_discretization#

MPCSettings.state_discretization: str = 'collocation'#

Choose the state discretization for continuous models.

Note

Currently only 'collocation' is available. Defaults to 'collocation'. Has no effect if model is created in discrete type.

store_full_solution#

MPCSettings.store_full_solution: bool = False#

Choose whether to store the full solution of the optimization problem.

This is required for animating the predictions in post processing. However, it drastically increases the required storage.

store_lagr_multiplier#

MPCSettings.store_lagr_multiplier: bool = True#

Choose whether to store the lagrange multipliers of the optimization problem.

Note

Increases the required storage.

t_step#

MPCSettings.t_step: float = None#

Timestep of the controller

use_terminal_bounds#

MPCSettings.use_terminal_bounds: bool = False#

Choose if terminal bounds for the states are used.

Set terminal bounds with do_mpc.controller.MPC.terminal_bounds.

store_solver_stats#

MPCSettings.store_solver_stats: List[str]#

Choose which solver statistics to store.

Must be a list of valid statistics. This attribute is an object of type list.

nlpsol_opts#

MPCSettings.nlpsol_opts: Dict#

Dictionary with options for the CasADi solver call nlpsol with plugin ipopt.

All options are listed here.