Controllers

class hilo_mpc.NMPC(model, id=None, name=None, plot_backend=None, use_sx=True, stats=False)[source]

Class for Nonlinear Model Predictive Control

check_consistency()
Returns:

create_path_variable(name='theta', u_pf_lb=0.0001, u_pf_ub=1, u_pf_ref=None, u_pf_weight=10, theta_guess=0, theta_lb=0, theta_ub=inf)[source]

Set the path following variable. This must be used for building SX expression of the path.

Parameters:
  • name (string) – name of the variable, default = ‘theta’

  • u_pf_lb (float) – lower bound on the path virtual input \(vel_{lb} \leq \dot{ \theta }\), default = 0.0001

  • u_pf_ub (float) – upper bound on the path virtual input \(vel_{ub} \geq \dot{ \theta }\), default = 1

  • u_pf_ref (float) – Reference for the path virtual input, default = None

  • u_pf_weight (float) – Weight for the path virtual input , default = 10

  • theta_guess

  • theta_lb

  • theta_ub

Returns:

casadi.SX

get_reference(time)[source]

Returns reference values at a given time. If works for path following, trajectory tracking and reference tracking problems. For the reference tracking problem it returns always a (constant) reference.

Parameters:

time

Returns:

get_time_variable()[source]

Useful for trajectory tacking

Returns:

is_setup()
Returns:

minimize_final_time(weight=1)[source]
Parameters:

weight

Returns:

optimize(x0, cp=None, tvp=None, v0=None, runs=0, fix_x0=True, **kwargs)[source]

Solves the MPC problem

Parameters:
  • x0 (list or casadi DM) – current system state

  • cp (list or casadi DM, optional) – constant system parameters (these will be assumed constant along the prediction horizon)

  • tvp (dict, optional) – time-varying system parameters (these can change during prediction horizon, entire parameter history must be passed in)

  • v0 (list or casadi DM, optional) – initial guess of the optimal vector

  • runs (int) – number of optimizations to run. If different from zero will run very optimization will perturb the initial guess v0 randomly. ACHTUNG: This could cause problems with the integrators or give something outside constraints. The output will be the solution with the minimum objective function (default 0)

  • fix_x0 (bool) – If True, the first state is fixed as the measured states. This is the classic MPC approach. If False, also the initial state is optimized.

Returns:

u_opt: first piece of optimal control sequence

plot_iterations(plot_states=False, **kwargs)

This plots the states and constraints for every mpc iteration. Useful to debug. At the moment it is working only with Bokeh. Warning: if the optimizer computes a large number of iterations the plots might take a bit of time to show up.

Parameters:
  • plot_states – if True, also the states are plotted

  • kwargs – If you pass ‘plot_last’ only the last iteration is plotted. This is to avoid very busy figures.

Returns:

plot_prediction(save_plot=False, plot_dir=None, name_file='mpc_prediction.html', show_plot=True, extras=None, extras_names=None, title=None, format_figure=None, **kwargs)[source]

Plots the MPC predicted values.

Parameters:
  • save_plot (bool) – if True plot will be saved under ‘plot_dir/name_file.html’ if they are declared, otherwise in current directory

  • plot_dir (str) – path to the folder where plots are saved (default = None)

  • name_file (str) – name of the file where plot will be saved (default = mpc_prediction.html)

  • show_plot (bool) – if True, shows plots (default = False)

  • extras (dict) – dictionary with values that will be plotted over the predictions if keys are equal to predicted states/inputs.

  • extras_names (list) – tags that will be attached to the extras in the legend

  • title (str) – title of the plots

  • format_figure (python function taking a bokeh figure object as an input) – python function that modifies the format of the figure

Returns:

reset_solution()
Returns:

return_prediction()[source]

Returns the mpc prediction.

Returns:

x_pred, u_pred, t_pred

set_box_constraints(x_ub=None, x_lb=None, u_ub=None, u_lb=None, y_ub=None, y_lb=None, z_ub=None, z_lb=None)[source]

Set box constraints to the model’s variables. These look like

\[x_{lb} \leq x \leq x_{ub}\]
Parameters:
  • x_ub (list, numpy array or CasADi DM array) – upper bound on states.

  • x_lb (list, numpy array or CasADi DM array) – lower bound on states

  • u_ub (list, numpy array or CasADi DM array) – upper bound on inputs

  • u_lb (list, numpy array or CasADi DM array) – lower bound on inputs

  • y_ub (list, numpy array or CasADi DM array) – upper bound on measurements

  • y_lb (list, numpy array or CasADi DM array) – lower bound on measurements

  • z_ub (list, numpy array or CasADi DM array) – upper bound on algebraic states

  • z_lb (list, numpy array or CasADi DM array) – lower bound on algebraic states

Returns:

set_compiler(method, compiler)
Parameters:
  • method

  • compiler

Returns:

set_custom_constraints_function(fun=None, lb=None, ub=None, soft=False, max_violation=inf)
Set a custom function that will be added as last position in the nonlinear constraints vector:

lb <= fun <= ub

This must take the entire optimization vector z and the indices of states and inputs as

fun(v, x_ind, u_ind)

Parameters:
  • fun – python function

  • lb – lower bound

  • ub – upper bound

  • soft

  • max_violation

Returns:

set_initial_guess(x_guess=None, u_guess=None, z_guess=None)

Sets initial guess for the optimizer when no other information of the states or inputs are available. :param x_guess: optimal state guesss :type x_guess: list, numpy array, float or casADi DM array :param u_guess: optimal input guess :type u_guess: list, numpy array, float or casADi DM array :param z_guess: optimal algebraic states guess :type z_guess: list, numpy array, float or casADi DM array :return:

set_nlp_options(*args, **kwargs)

Sets the options that modify how the MPC problem is set

Parameters:
  • args

  • kwargs

Returns:

set_nlp_solver(solver)

Set the solver for the MPC. Possible options are For nonlinear programming problems (e.g. nonlinear MPC) - ‘ipopt’, ‘bonmin’, ‘knitro’, ‘snopt’, ‘worhp’, ‘scpgen’, ‘sqpmethod’, ‘blocksqp’, ‘AmplInterface’ for quadratic programmin problems (e.g. linear MPC) - ‘qpoases’, ‘cplex’, ‘gurobi’, ‘oopq’, ‘sqic’, ‘nlp For more info refer to the CasADi documentation https://web.casadi.org/docs/.

Parameters:

solver

Returns:

set_quadratic_stage_cost(states=None, cost_states=None, states_references=None, inputs=None, cost_inputs=None, inputs_references=None)[source]

More compact way to set the quadratic cost for the MPC. Mostly left for backwards compatibility. To use only for set-point-tracking problems.

Parameters:
  • states (list) – list of states name that will appear in the quadratic cost

  • cost_states (list, numpy array, or casADi DM array) – weights values that will be multiplied by the states

  • states_references (list) – list of reference values

  • inputs (list) – list of inputs names that will be multiplied by the states

  • cost_inputs (list, numpy array, or casADi DM array) – list of inputs weights that will be multiplied by the states

  • inputs_references (list) – list of inputs reference values

Returns:

set_quadratic_terminal_cost(states=None, cost=None, references=None)[source]

More compact way to set the quadratic cost for the MPC. Mostly left for backwards compatibility. To use only for set-point-tracking problems.

Parameters:
  • states (list) – list of states name that will appear in the quadratic cost

  • cost (list, numpy array or CasADi DM) – list of weights values that will be multiplied by the states

  • references – list of references values for the states

Returns:

set_sampling_interval(dt=None)
Parameters:

dt

Returns:

set_scaling(x_scaling=None, u_scaling=None, y_scaling=None)

Pass the scaling factors of states, inputs and outputs. This is important for system with where the optimization variable can have a large difference of order of magnitude. The scaling factors divide the respective variables.

Parameters:
  • x_scaling (list) – scaling factors for the states

  • u_scaling (list) – scaling of scaling factors for inputs

  • y_scaling (list) – scaling of scaling factors for outputs

Returns:

set_solver_opts(*args, **kwargs)

Sets the nonlinear programming settings. This can be a dictionary or key-valued arguments These correspond to the option of the used nlp solver, for example ipopt or bonmin :param args: :param kwargs: :return:

set_stage_constraints(stage_constraint=None, lb=None, ub=None, is_soft=False, max_violation=inf, weight=None, name='stage_constraint')

Allows to add a (nonlinear) stage constraint.

Parameters:
  • stage_constraint – SX expression. It has to contain variables of the model

  • lb – Vector or list float,integer or casadi.DM. Lower bound on the constraint

  • ub – Vector or list float,integer or casadi.DM. Upper bound on the constraint

  • is_soft – bool: if True soft constraints are used.

  • max_violation – (optional) Vector or list float,integer or casadi.DM. Maximum violation if constraint is soft. If None, there is no limit on the violation of the soft constraints

  • weight – (optional) matrix of appropriate dimension. If is_soft=True it will be used to weight the soft constraint in the objective function using a quadratic cost.

  • name

Returns:

set_terminal_constraints(terminal_constraint, name='terminal_constraint', lb=None, ub=None, is_soft=False, max_violation=inf, weight=None)[source]

Allows to add a (nonlinear) terminal constraint.

Parameters:
  • terminal_constraint (CasADi SX expression) – It has to contain variables of the model

  • lb (list of float, integer or casadi.DM.) – Lower bound on the constraint

  • ub (list of float, integer or casadi.DM.) – Upper bound on the constraint

  • is_soft (bool) – if True soft constraints are used (default False)

  • max_violation (list float,integer or casadi.DM) – (optional) Maximum violation if constraint is soft. Default: inf

  • weight (casadi.DM) – (optional) matrix of appropriate dimension. If is_soft=True it will be used to weight the soft constraint in the objective function using a quadratic cost.

Returns:

set_time_varying_parameters(names=None, values=None)

Sets the time-varying parameters values for then MPC. Time varying parameters are model parameters that change in time. Hence, when predicting the system dynamics, their value must be supplied to the model at the every sampling time.

Parameters:
  • names (list of strings) – list of strings with time varying parameter names

  • values (dict (optional)) – values of the time varying parameters. You need to pass at least a number of values as long as the prediction horizon. Note: if the prediction goes after the last supplied value, the values will be repeated!

Returns:

None

setup(options=None, solver_options=None)[source]

Sets up the corresponding optimization problem (OP) of the MPC. This must be run before attempting to solve the MPC.

Parameters:
  • options (dict) – Options for MPC. See documentation.

  • solver_options (dict) – Dictionary with options for the optimizer. These options are solver specific. Refer to the CasADi Documentation https://web.casadi.org/python-api/#nlp

Returns:

None

property compiler
Returns:

property control_horizon
Returns:

property current_time
Returns:

property display
Returns:

property horizon
Returns:

property id

Identifier of the object

Returns:

Identifier of the object

Return type:

str

property initial_time
Returns:

property n_iterations
Returns:

property n_of_path_vars

Number of path variables used for path following

Returns:

property n_tvp
Returns:

property obj_fun
Returns:

Objective function (MX)

property obj_function_stage_cost
Returns:

property prediction_horizon
Returns:

property sampling_interval
Returns:

property solution
Returns:

property time_var
Returns:

property type
Returns:

property u_lb
Returns:

property u_ub
Returns:

property x_lb
Returns:

property x_ub
Returns:

class hilo_mpc.LMPC(model, id=None, name=None, plot_backend='bokeh', use_sx=True)[source]
optimize(x0, tvp=None, cp=None)[source]
Parameters:
  • x0

  • tvp

  • cp

Returns:

return_prediction()[source]

Returns the mpc prediction.

Returns:

x_pred, u_pred, t_pred

set_custom_constraints_function(fun=None, lb=None, ub=None, soft=False, max_violation=inf)[source]
Set a custom function that will be added as last position in the nonlinear constraints vector:

lb <= fun <= ub

This must take the entire optimization vector z and the indices of states and inputs as

fun(v, x_ind, u_ind)

Parameters:
  • fun – python function

  • lb – lower bound

  • ub – upper bound

  • soft

  • max_violation

Returns:

set_initial_guess(x_guess=None, u_guess=None, z_guess=None)[source]

Sets initial guess for the optimizer when no other information of the states or inputs are available. :param x_guess: optimal state guesss :type x_guess: list, numpy array, float or casADi DM array :param u_guess: optimal input guess :type u_guess: list, numpy array, float or casADi DM array :param z_guess: optimal algebraic states guess :type z_guess: list, numpy array, float or casADi DM array :return:

set_stage_constraints(stage_constraint=None, lb=None, ub=None, is_soft=False, max_violation=inf, weight=None, name='stage_constraint')[source]

Allows to add a (nonlinear) stage constraint.

Parameters:
  • stage_constraint – SX expression. It has to contain variables of the model

  • lb – Vector or list float,integer or casadi.DM. Lower bound on the constraint

  • ub – Vector or list float,integer or casadi.DM. Upper bound on the constraint

  • is_soft – bool: if True soft constraints are used.

  • max_violation – (optional) Vector or list float,integer or casadi.DM. Maximum violation if constraint is soft. If None, there is no limit on the violation of the soft constraints

  • weight – (optional) matrix of appropriate dimension. If is_soft=True it will be used to weight the soft constraint in the objective function using a quadratic cost.

  • name

Returns:

setup(options=None, solver_options={}, solver='qpoases')[source]
Parameters:
  • options

  • solver_options

:param : :return:

property prediction_horizon
Returns:

class hilo_mpc.PID(n_set_points=1, id=None, name=None, k_p=None, t_i=None, t_d=None, proportional_on_process_value=False, derivative_on_process_value=False, plot_backend=None)[source]

Class for PID controller

Parameters:
  • n_set_points (int) –

  • id (str, optional) –

  • name (str, optional) –

  • k_p

  • t_i

  • t_d

  • proportional_on_process_value (bool) –

  • derivative_on_process_value (bool) –

  • plot_backend (str, optional) –

call(*args, **kwargs)[source]
Parameters:
  • args

  • kwargs

Returns:

setup(**kwargs)[source]
Parameters:

kwargs

Returns:

property derivative_gain
Returns:

property derivative_time
Returns:

property integral_gain
Returns:

property integral_time
Returns:

property k_d
Returns:

property k_i
Returns:

property k_p
Returns:

property proportional_gain
Returns:

property s_p
Returns:

property set_point
Returns:

property t_d
Returns:

property t_i
Returns: