Python Interface

acados_template is a Python package that can be used to specify optimal control problems from Python and to generate self-contained C code to solve them using acados. The pip package is based on templated code (C files, Header files and Makefiles), which are rendered from Python using the templating engine Tera. The genereated C code can be compiled into a self-contained C library that can be deployed on an embedded system.

Optimal Control Problem description

The Python interface relies on the same problem formulation as the MATLAB interface see here.

Installation

  1. Compile and install acados by following the CMake installation instructions.

  2. Optional: Recommended. Create a Python virtual environment using virtualenv.

    virtualenv env --python=/usr/bin/python3.7
    # Source the environment
    source env/bin/activate
    

    Note: There are known path issues with more high level virtual environment managers. Such as conda, miniconda, Pycharm. It is not recommended to use them. However, if you need to do so and have issues, please have a look in the acados forum.

  3. Install acados_template Python package:

    pip3 install -e <acados_root>/interfaces/acados_template
    

    Note: If you are working with a virtual Python environment, use the pip corresponding to this Python environment instead of pip3. Note: The option -e makes the installation editable, so you can seeminglessly switch to a later acados version and make changes in the Python interface yourself.

  4. Add the path to the compiled shared libraries libacados.so, libblasfeo.so, libhpipm.so to LD_LIBRARY_PATH (default path is <acados_root/lib>) by running:

    export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:"<acados_root>/lib"
    export ACADOS_SOURCE_DIR="<acados_root>"
    

    Hint: you can add these lines to your .bashrc/.zshrc.

  5. Run a Python example to check that everything works. We suggest to get started with the example <acados_root>/examples/acados_python/getting_started/minimal_example_ocp.py.

  6. Optional: Can be done automatically through the interface: In order to be able to successfully render C code templates, you need to download the t_renderer binaries for your platform from https://github.com/acados/tera_renderer/releases/ and place them in <acados_root>/bin (please strip the version and platform from the binaries (e.g.t_renderer-v0.0.34 -> t_renderer). Notice that you might need to make t_renderer executable. Run export ACADOS_SOURCE_DIR=<acados_root> such that the location of acados will be known to the Python package at run time.

  7. Optional: Set acados_lib_path, acados_include_path. If you want the generated Makefile to refer to a specific path (e.g. when cross-compiling or compiling from a location different from the one where you generate the C code), you will have to set these paths accordingly in the generating Python code.

Overview

The following image shows an overview of the available classes in the acados Python interface and their dependencies.

Overview of acados Python classes

Python API classes overview

acados OCP solver

The class AcadosOcp can be used to formulate optimal control problems, for which an acados solver (AcadosOcpSolver) can be created.

class acados_template.acados_ocp_solver.AcadosOcpSolver(acados_ocp, json_file='acados_ocp_nlp.json', simulink_opts=None)

Class to interact with the acados ocp solver C object.

param acados_ocp

type AcadosOcp - description of the OCP for acados

param json_file

name for the json file used to render the templated code - default: acados_ocp_nlp.json

param simulink_opts

Options to configure Simulink S-function blocks, mainly to activate possible Inputs and Outputs

constraints_set(stage_, field_, value_, api='warn')

Set numerical data in the constraint module of the solver.

param stage

integer corresponding to shooting node

param field

string in [‘lbx’, ‘ubx’, ‘lbu’, ‘ubu’, ‘lg’, ‘ug’, ‘lh’, ‘uh’, ‘uphi’]

param value

of appropriate size

cost_set(stage_, field_, value_, api='warn')

Set numerical data in the cost module of the solver.

param stage

integer corresponding to shooting node

param field

string, e.g. ‘yref’, ‘W’, ‘ext_cost_num_hess’

param value

of appropriate size

dynamics_get(stage_, field_)

Get numerical data from the dynamics module of the solver:

param stage

integer corresponding to shooting node

param field

string, e.g. ‘A’

get(stage_, field_)

Get the last solution of the solver:

param stage

integer corresponding to shooting node

param field

string in [‘x’, ‘u’, ‘z’, ‘pi’, ‘lam’, ‘t’, ‘sl’, ‘su’,]

Note

regarding lam, t:

the inequalities are internally organized in the following order:

[ lbu lbx lg lh lphi ubu ubx ug uh uphi;

lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]

Note

pi: multipliers for dynamics equality constraints

lam: multipliers for inequalities

t: slack variables corresponding to evaluation of all inequalities (at the solution)

sl: slack variables of soft lower inequality constraints

su: slack variables of soft upper inequality constraints

get_cost()

Returns the cost value of the current solution.

get_residuals()

Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].

get_stats(field_)

Get the information of the last solver call.

param field

string in [‘statistics’, ‘time_tot’, ‘time_lin’, ‘time_sim’, ‘time_sim_ad’, ‘time_sim_la’, ‘time_qp’, ‘time_qp_solver_call’, ‘time_reg’, ‘sqp_iter’]

load_iterate(filename)

Loads the iterate stored in json file with filename into the ocp solver.

options_set(field_, value_)

Set options of the solver.

param field

string, e.g. ‘print_level’, ‘rti_phase’, ‘initialize_t_slacks’, ‘step_length’, ‘alpha_min’, ‘alpha_reduction’

param value

of type int, float

print_statistics()
prints statistics of previous solver run as a table:
  • iter: iteration number

  • res_stat: stationarity residual

  • res_eq: residual wrt equality constraints (dynamics)

  • res_ineq: residual wrt inequality constraints (constraints)

  • res_comp: residual wrt complementarity conditions

  • qp_stat: status of QP solver

  • qp_iter: number of QP iterations

  • qp_res_stat: stationarity residual of the last QP solution

  • qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution

  • qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution

  • qp_res_comp: residual wrt complementarity conditions of the last QP solution

set(stage_, field_, value_)

Set numerical data inside the solver.

param stage

integer corresponding to shooting node

param field

string in [‘x’, ‘u’, ‘pi’, ‘lam’, ‘t’, ‘p’]

Note

regarding lam, t:

the inequalities are internally organized in the following order:

[ lbu lbx lg lh lphi ubu ubx ug uh uphi;

lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]

Note

pi: multipliers for dynamics equality constraints

lam: multipliers for inequalities

t: slack variables corresponding to evaluation of all inequalities (at the solution)

sl: slack variables of soft lower inequality constraints

su: slack variables of soft upper inequality constraints

solve()

Solve the ocp with current input.

store_iterate(filename='', overwrite=False)

Stores the current iterate of the ocp solver in a json file.

param filename

if not set, use model_name + timestamp + ‘.json’

param overwrite

if false and filename exists add timestamp to filename

class acados_template.acados_ocp.AcadosOcp(acados_path='')

Class containing the full description of the optimal control problem. This object can be used to create an acados_template.acados_ocp_solver.AcadosOcpSolver.

The class has the following properties that can be modified to formulate a specific OCP, see below:

acados_include_path

Path to acados include directory, type: string

acados_lib_path

Path to where acados library is located, type: string

code_export_directory

Path to where code will be exported. Default: c_generated_code.

constraints

Constraints definitions, type acados_template.acados_ocp.AcadosOcpConstraints

cost

Cost definitions, type acados_template.acados_ocp.AcadosOcpCost

dims

Dimension definitions, type acados_template.acados_ocp.AcadosOcpDims

model

Model definitions, type acados_template.acados_model.AcadosModel

property parameter_values

\(p\) - initial values for parameter - can be updated stagewise

solver_options

Solver Options, type acados_template.acados_ocp.AcadosOcpOptions

class acados_template.acados_ocp.AcadosOcpConstraints

class containing the description of the constraints

property C

\(C\) - C matrix in \(\underline{g} \leq D \, u + C \, x \leq \bar{g}\) at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array((0,0)).

property C_e

\(C^e\) - C matrix at terminal shooting node N. Type: np.ndarray; default: np.array((0,0)).

property D

\(D\) - D matrix in \(\underline{g} \leq D \, u + C \, x \leq \bar{g}\) at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array((0,0))

property Jbu

\(J_{bu}\) - matrix coefficient for bounds on u at shooting nodes (0 to N-1). Translated internally to idxbu.

property Jbx

\(J_{bx}\) - matrix coefficient for bounds on x at intermediate shooting nodes (1 to N-1). Translated internally into idxbx.

property Jbx_0

\(J_{bx,0}\) - matrix coefficient for bounds on x at initial stage 0. Translated internally to idxbx_0

property Jbx_e

\(J_{bx}^e\) matrix coefficient for bounds on x at terminal shooting node N. Translated internally into idxbx_e.

property Jsbu

\(J_{sbu}\) - matrix coefficient for soft bounds on u at stages (0 to N-1); internally translated into idxsbu

property Jsbx

\(J_{sbx}\) - matrix coefficient for soft bounds on x at stages (1 to N-1); Translated internally into idxsbx.

property Jsbx_e

\(J_{sbx}^e\) - matrix coefficient for soft bounds on x at terminal shooting node N. Translated internally to idxsbx_e

property Jsg

\(J_{sg}\) - matrix coefficient for soft bounds on general linear constraints. Translated internally to idxsg

property Jsg_e

\(J_{s,h}^e\) - matrix coefficient for soft bounds on general linear constraints at terminal shooting node N. Translated internally to idxsg_e

property Jsh

\(J_{sh}\) - matrix coefficient for soft bounds on nonlinear constraints. Translated internally to idxsh

property Jsh_e

\(J_{s,h}^e\) - matrix coefficient for soft bounds on nonlinear constraints at terminal shooting node N; fills idxsh_e

property Jsphi

\(J_{s, \phi}\) - matrix coefficient for soft bounds on convex-over-nonlinear constraints. Translated internally into idxsphi.

property Jsphi_e

\(J_{sh}^e\) - matrix coefficient for soft bounds on convex-over-nonlinear constraints at shooting node N. Translated internally to idxsphi_e

property constr_type

Constraints type for shooting nodes (0 to N-1). string in {BGH, BGP}. Default: BGH; BGP is for convex over nonlinear.

property constr_type_e

Constraints type for terminal shooting node N. string in {BGH, BGP}. Default: BGH; BGP is for convex over nonlinear.

property idxbu

Indices of bounds on u (defines \(J_{bu}\)) at shooting nodes (0 to N-1). Can be set by using Jbu. Type: np.ndarray; default: np.array([])

property idxbx

indices of bounds on x (defines \(J_{bx}\)) at intermediate shooting nodes (1 to N-1). Can be set by using Jbx. Type: np.ndarray; default: np.array([])

property idxbx_0

Indices of bounds on x at initial stage 0 – can be set automatically via x0. Can be set by using Jbx_0. Type: np.ndarray; default: np.array([])

property idxbx_e

Indices for bounds on x at terminal shooting node N (defines \(J_{bx}^e\)). Can be set by using Jbx_e. Type: np.ndarray; default: np.array([])

property idxbxe_0

Indices of bounds on x0 that are equalities – can be set automatically via x0. Type: np.ndarray; default: np.array([])

property idxsbu

Indices of soft bounds on u within the indices of bounds on u at stages (0 to N-1). Can be set by using Jsbu. Type: np.ndarray; default: np.array([])

property idxsbx

Indices of soft bounds on x within the indices of bounds on x at stages (1 to N-1). Can be set by using Jsbx. Type: np.ndarray; default: np.array([])

property idxsbx_e

Indices of soft bounds on x at shooting node N, within the indices of bounds on x at terminal shooting node N. Can be set by using Jsbx_e. Type: np.ndarray; default: np.array([])

property idxsg

Indices of soft general linear constraints within the indices of general linear constraints. Can be set by using Jsg. Type: np.ndarray; default: np.array([])

property idxsg_e

Indices of soft general linear constraints at shooting node N within the indices of general linear constraints at shooting node N. Can be set by using Jsg_e.

property idxsh

Indices of soft nonlinear constraints within the indices of nonlinear constraints. Can be set by using Jbx. Type: np.ndarray; default: np.array([])

property idxsh_e

Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at terminal shooting node N. Can be set by using Jsh_e.

property idxsphi

Indices of soft convex-over-nonlinear constraints within the indices of nonlinear constraints. Can be set by using Jsphi. Type: np.ndarray; default: np.array([])

property idxsphi_e

Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at terminal shooting node N. Can be set by using Jsphi_e. Type: np.ndarray; default: np.array([])

property lbu

\(\underline{u}\) - lower bounds on u at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([])

property lbx

\(\underline{x}\) - lower bounds on x at intermediate shooting nodes (1 to N-1). Type: np.ndarray; default: np.array([])

property lbx_0

\(\underline{x_0}\) - lower bounds on x at initial stage 0. Type: np.ndarray; default: np.array([]).

property lbx_e

\(\underline{x}^e\) - lower bounds on x at terminal shooting node N. Type: np.ndarray; default: np.array([])

property lg

\(\underline{g}\) - lower bound for general polytopic inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([])

property lg_e

\(\underline{g}^e\) - lower bound on general polytopic inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property lh

\(\underline{h}\) - lower bound for nonlinear inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([]).

property lh_e

\(\underline{h}^e\) - lower bound on nonlinear inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property lphi

\(\underline{\phi}\) - lower bound for convex-over-nonlinear inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([]).

property lphi_e

\(\underline{\phi}^e\) - lower bound on convex-over-nonlinear inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property lsbu

Lower bounds on slacks corresponding to soft lower bounds on u at stages (0 to N-1). Not required - zeros by default.

property lsbx

Lower bounds on slacks corresponding to soft lower bounds on x at stages (1 to N-1); not required - zeros by default

property lsbx_e

Lower bounds on slacks corresponding to soft lower bounds on x at shooting node N. Not required - zeros by default

property lsg

Lower bounds on slacks corresponding to soft lower bounds for general linear constraints at stages (0 to N-1). Type: np.ndarray; default: np.array([])

property lsg_e

Lower bounds on slacks corresponding to soft lower bounds for general linear constraints at shooting node N. Not required - zeros by default

property lsh

Lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints. Not required - zeros by default

property lsh_e

Lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints at terminal shooting node N. Not required - zeros by default

property lsphi

Lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints. Not required - zeros by default

property lsphi_e

Lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints at terminal shooting node N. Not required - zeros by default

property ubu

\(\bar{u}\) - upper bounds on u at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([])

property ubx

\(\bar{x}\) - upper bounds on x at intermediate shooting nodes (1 to N-1). Type: np.ndarray; default: np.array([])

property ubx_0

\(\bar{x_0}\) - upper bounds on x at initial stage 0. Type: np.ndarray; default: np.array([])

property ubx_e

\(\bar{x}^e\) - upper bounds on x at terminal shooting node N. Type: np.ndarray; default: np.array([])

property ug

\(\bar{g}\) - upper bound for general polytopic inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([]).

property ug_e

\(\bar{g}^e\) - upper bound on general polytopic inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property uh

\(\bar{h}\) - upper bound for nonlinear inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([]).

property uh_e

\(\bar{h}^e\) - upper bound on nonlinear inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property uphi

\(\bar{\phi}\) - upper bound for convex-over-nonlinear inequalities at shooting nodes (0 to N-1). Type: np.ndarray; default: np.array([]).

property uphi_e

\(\bar{\phi}^e\) - upper bound on convex-over-nonlinear inequalities at terminal shooting node N. Type: np.ndarray; default: np.array([]).

property usbu

Lower bounds on slacks corresponding to soft upper bounds on u at stages (0 to N-1); not required - zeros by default

property usbx

Lower bounds on slacks corresponding to soft upper bounds on x at stages (1 to N-1); not required - zeros by default

property usbx_e

Lower bounds on slacks corresponding to soft upper bounds on x at shooting node N. Not required - zeros by default

property usg

Lower bounds on slacks corresponding to soft upper bounds for general linear constraints. Not required - zeros by default

property usg_e

Lower bounds on slacks corresponding to soft upper bounds for general linear constraints at shooting node N. Not required - zeros by default

property ush

Lower bounds on slacks corresponding to soft upper bounds for nonlinear constraints. Not required - zeros by default

property ush_e

Lower bounds on slacks corresponding to soft upper bounds for nonlinear constraints at terminal shooting node N. Not required - zeros by default

property usphi

Lower bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints. Not required - zeros by default

property usphi_e

Lower bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints at terminal shooting node N. Not required - zeros by default

property x0

\(x_0 \in \mathbb{R}^{n_x}\) - initial state – Translated internally to idxbx_0, lbx_0, ubx_0, idxbxe_0

class acados_template.acados_ocp.AcadosOcpCost

Class containing the numerical data of the cost:

In case of LINEAR_LS: stage cost is \(l(x,u,z) = || V_x \, x + V_u \, u + V_z \, z - y_\text{ref}||^2_W\), terminal cost is \(m(x) = || V^e_x \, x - y_\text{ref}^e||^2_{W^e}\)

In case of NONLINEAR_LS: stage cost is \(l(x,u,z) = || y(x,u,z) - y_\text{ref}||^2_W\), terminal cost is \(m(x) = || y^e(x) - y_\text{ref}^e||^2_{W^e}\)

property Vu

\(V_u\) - u matrix coefficient at intermediate shooting nodes (1 to N-1). Default: np.zeros((0,0)).

property Vu_0

\(V_u^0\) - u matrix coefficient at initial shooting node (0). Default: None.

property Vx

\(V_x\) - x matrix coefficient at intermediate shooting nodes (1 to N-1). Default: np.zeros((0,0)).

property Vx_0

\(V_x^0\) - x matrix coefficient at initial shooting node (0). Default: None.

property Vx_e

\(V_x^e\) - x matrix coefficient for cost at terminal shooting node (N). Default: np.zeros((0,0)).

property Vz

\(V_z\) - z matrix coefficient at intermediate shooting nodes (1 to N-1). Default: np.zeros((0,0)).

property Vz_0

\(V_z^0\) - z matrix coefficient at initial shooting node (0). Default: None.

property W

\(W\) - weight matrix at intermediate shooting nodes (1 to N-1). Default: np.zeros((0,0)).

property W_0

\(W_0\) - weight matrix at initial shooting node (0). Default: None.

property W_e

\(W_e\) - weight matrix at terminal shooting node (N). Default: np.zeros((0,0)).

property Zl

\(Z_l\) - diagonal of Hessian wrt lower slack at intermediate shooting nodes (1 to N-1). Default: np.array([]).

property Zl_e

\(Z_l^e\) - diagonal of Hessian wrt lower slack at terminal shooting node (N). Default: np.array([]).

property Zu

\(Z_u\) - diagonal of Hessian wrt upper slack at intermediate shooting nodes (1 to N-1). Default: np.array([]).

property Zu_e

\(Z_u^e\) - diagonal of Hessian wrt upper slack at terminal shooting node (N). Default: np.array([]).

property cost_ext_fun_type

Type of external function for cost at intermediate shooting nodes (1 to N-1). – string in {casadi, generic} Default: :code:’casadi’.

property cost_ext_fun_type_0

Type of external function for cost at initial shooting node (0) – string in {casadi, generic} or None Default: :code:’casadi’.

Note

Cost at initial stage is the same as for intermediate shooting nodes if not set differently explicitly.

property cost_ext_fun_type_e

Type of external function for cost at intermediate shooting nodes (1 to N-1). – string in {casadi, generic} Default: :code:’casadi’.

property cost_type

Cost type at intermediate shooting nodes (1 to N-1) – string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS}. Default: ‘LINEAR_LS’.

property cost_type_0

Cost type at initial shooting node (0) – string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS} or None. Default: None.

Note

Cost at initial stage is the same as for intermediate shooting nodes if not set differently explicitly.

Note

If cost_type_0 is set to None values in W_0, Vx_0, Vu_0, Vz_0 and yref_0 are ignored (set to None).

property cost_type_e

Cost type at terminal shooting node (N) – string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS}. Default: ‘LINEAR_LS’.

property yref

\(y_\text{ref}\) - reference at intermediate shooting nodes (1 to N-1). Default: np.array([]).

property yref_0

\(y_\text{ref}^0\) - reference at initial shooting node (0). Default: None.

property yref_e

\(y_\text{ref}^e\) - cost reference at terminal shooting node (N). Default: np.array([]).

property zl

\(z_l\) - gradient wrt lower slack at intermediate shooting nodes (1 to N-1). Default: np.array([]).

property zl_e

\(z_l^e\) - gradient wrt lower slack at terminal shooting node (N). Default: np.array([]).

property zu

\(z_u\) - gradient wrt upper slack at intermediate shooting nodes (1 to N-1). Default: np.array([]).

property zu_e

\(z_u^e\) - gradient wrt upper slack at terminal shooting node (N). Default: np.array([]).

class acados_template.acados_ocp.AcadosOcpDims

Class containing the dimensions of the optimal control problem.

property N

\(N\) - prediction horizon. Type: int; default: None

property nbu

\(n_{b_u}\) - number of input bounds. Type: int; default: 0

property nbx

\(n_{b_x}\) - number of state bounds. Type: int; default: 0

property nbx_0

\(n_{b_{x0}}\) - number of state bounds for initial state. Type: int; default: 0

property nbx_e

\(n_{b_x}\) - number of state bounds at terminal shooting node N. Type: int; default: 0

property nbxe_0

\(n_{be_{x0}}\) - number of state bounds at initial shooting node that are equalities. Type: int; default: None

property ng

\(n_{g}\) - number of general polytopic constraints. Type: int; default: 0

property ng_e

\(n_{g}^e\) - number of general polytopic constraints at terminal shooting node N. Type: int; default: 0

property nh

\(n_h\) - number of nonlinear constraints. Type: int; default: 0

property nh_e

\(n_{h}^e\) - number of nonlinear constraints at terminal shooting node N. Type: int; default: 0

property np

\(n_p\) - number of parameters. Type: int; default: 0

property nphi

\(n_{\phi}\) - number of convex-over-nonlinear constraints. Type: int; default: 0

property nphi_e

\(n_{\phi}^e\) - number of convex-over-nonlinear constraints at terminal shooting node N. Type: int; default: 0

property nr

\(n_{\pi}\) - dimension of the image of the inner nonlinear function in positive definite constraints. Type: int; default: 0

property nr_e

\(n_{\pi}^e\) - dimension of the image of the inner nonlinear function in positive definite constraints. Type: int; default: 0

property ns

\(n_{s}\) - total number of slacks. Type: int; default: 0

property ns_e

\(n_{s}^e\) - total number of slacks at terminal shooting node N. Type: int; default: 0

property nsbu

\(n_{{sb}_u}\) - number of soft input bounds. Type: int; default: 0

property nsbx

\(n_{{sb}_x}\) - number of soft state bounds. Type: int; default: 0

property nsbx_e

\(n_{{sb}^e_{x}}\) - number of soft state bounds at terminal shooting node N. Type: int; default: 0

property nsg

\(n_{{sg}}\) - number of soft general linear constraints. Type: int; default: 0

property nsg_e

\(n_{{sg}^e}\) - number of soft general linear constraints at terminal shooting node N. Type: int; default: 0

property nsh

\(n_{{sh}}\) - number of soft nonlinear constraints. Type: int; default: 0

property nsh_e

\(n_{{sh}}^e\) - number of soft nonlinear constraints at terminal shooting node N. Type: int; default: 0

property nsphi

\(n_{{s\phi}}\) - number of soft convex-over-nonlinear constraints. Type: int; default: 0

property nsphi_e

\(n_{{s\phi}^e}\) - number of soft convex-over-nonlinear constraints at terminal shooting node N. Type: int; default: 0

property nu

\(n_u\) - number of inputs. Type: int; default: None

property nx

\(n_x\) - number of states. Type: int; default: None

property ny

\(n_y\) - number of residuals in Lagrange term. Type: int; default: 0

property ny_0

\(n_{y}^0\) - number of residuals in Mayer term. Type: int; default: 0

property ny_e

\(n_{y}^e\) - number of residuals in Mayer term. Type: int; default: 0

property nz

\(n_z\) - number of algebraic variables. Type: int; default: 0

class acados_template.acados_ocp.AcadosOcpOptions

class containing the description of the solver options

property Tsim

Time horizon for one integrator step. Automatically calculated as tf/N. Default: None

property alpha_min

Minimal step size for globalization MERIT_BACKTRACKING, default: 0.05.

property alpha_reduction

Step size reduction factor for globalization MERIT_BACKTRACKING, default: 0.7.

property exact_hess_constr

Used in case of hessian_approx == ‘EXACT’.

Can be used to turn off exact hessian contributions from the constraints module.

property exact_hess_cost

Used in case of hessian_approx == ‘EXACT’.

Can be used to turn off exact hessian contributions from the cost module.

property exact_hess_dyn

Used in case of hessian_approx == ‘EXACT’.

Can be used to turn off exact hessian contributions from the dynamics module.

property ext_cost_num_hess

Determines if custom hessian approximation for cost contribution is used (> 0).

Or if hessian contribution is evaluated exactly using CasADi external function (=0 - default).

property globalization

Globalization type. String in (‘FIXED_STEP’, ‘MERIT_BACKTRACKING’). Default: ‘FIXED_STEP’.

Note

preliminary implementation.

property hessian_approx

Hessian approximation. String in (‘GAUSS_NEWTON’, ‘EXACT’). Default: ‘GAUSS_NEWTON’.

property integrator_type

Integrator type. String in (‘ERK’, ‘IRK’, ‘GNSF’, ‘DISCRETE’). Default: ‘ERK’.

property levenberg_marquardt

Factor for LM regularization. Type: float >= 0 Default: 0.0.

property model_external_shared_lib_dir

Path to the .so lib

property model_external_shared_lib_name

Name of the .so lib

property nlp_solver_max_iter

NLP solver maximum number of iterations. Type: int > 0 Default: 100

property nlp_solver_step_length

Fixed Newton step length. Type: float > 0. Default: 1.0.

property nlp_solver_tol_comp

NLP solver complementarity tolerance

property nlp_solver_tol_eq

NLP solver equality tolerance

property nlp_solver_tol_ineq

NLP solver inequality tolerance

property nlp_solver_tol_stat

NLP solver stationarity tolerance. Type: float > 0 Default: 1e-6

property nlp_solver_type

NLP solver. String in (‘SQP’, ‘SQP_RTI’). Default: ‘SQP_RTI’.

property print_level

Verbosity of printing. Type: int >= 0 Default: 0

property qp_solver

QP solver to be used in the NLP solver. String in (‘PARTIAL_CONDENSING_HPIPM’, ‘FULL_CONDENSING_QPOASES’, ‘FULL_CONDENSING_HPIPM’, ‘PARTIAL_CONDENSING_QPDUNES’, ‘PARTIAL_CONDENSING_OSQP’). Default: ‘PARTIAL_CONDENSING_HPIPM’.

property qp_solver_cond_N

QP solver: New horizon after partial condensing. Set to N by default -> no condensing.

property qp_solver_iter_max

QP solver: maximum number of iterations. Type: int > 0 Default: 50

property qp_solver_tol_comp

QP solver complementarity. Default: None

property qp_solver_tol_eq

QP solver equality tolerance. Default: None

property qp_solver_tol_ineq

QP solver inequality. Default: None

property qp_solver_tol_stat

QP solver stationarity tolerance. Default: None

property qp_solver_warm_start

QP solver: Warm starting. 0: no warm start; 1: warm start; 2: hot start.

property qp_tol

QP solver tolerance. Sets all of the following at once or gets the max of qp_solver_tol_eq, qp_solver_tol_ineq, qp_solver_tol_comp and qp_solver_tol_stat.

property regularize_method

Regularization method for the Hessian. String in (‘NO_REGULARIZE’, ‘MIRROR’, ‘PROJECT’, ‘PROJECT_REDUC_HESS’, ‘CONVEXIFY’) or None.

Default: None.

property shooting_nodes

Vector with the shooting nodes, time_steps will be computed from it automatically. Default: None

property sim_method_jac_reuse

Boolean determining if jacobians are reused within integrator. Default: False

property sim_method_newton_iter

Number of Newton iterations in simulation method. Type: int > 0 Default: 3

property sim_method_num_stages

Number of stages in the integrator. Type: int > 0 or ndarray of ints > 0 of shape (N,). Default: 4

property sim_method_num_steps

Number of steps in the integrator. Type: int > 0 or ndarray of ints > 0 of shape (N,). Default: 1

property tf

Prediction horizon Type: float > 0 Default: None

property time_steps

Vector with time steps between the shooting nodes. Set automatically to uniform discretization if N and tf are provided. Default: None

property tol

NLP solver tolerance. Sets or gets the max of nlp_solver_tol_eq, nlp_solver_tol_ineq, nlp_solver_tol_comp and nlp_solver_tol_stat.

class acados_template.acados_model.AcadosModel

Class containing all the information to code generate the external CasADi functions that are needed when creating an acados ocp solver or acados integrator. Thus, this class contains:

  1. the name of the model,

  2. all CasADi variables/expressions needed in the CasADi function generation process.

con_h_expr

CasADi expression for the constraint \(h\); Default: None

con_h_expr_e

CasADi expression for the terminal constraint \(h^e\); Default: None

con_phi_expr

CasADi expression for the constraint phi; Default: None

con_phi_expr_e

CasADi expression for the terminal constraint; Default: None

con_r_expr

CasADi expression for the constraint phi(r); Default: None

con_r_expr_e

CasADi expression for the terminal constraint; Default: None

cost_expr_ext_cost

CasADi expression for external cost; Default: None

cost_expr_ext_cost_0

CasADi expression for external cost, initial; Default: None

cost_expr_ext_cost_e

CasADi expression for external cost, terminal; Default: None

cost_y_expr

CasADi expression for nonlinear least squares; Default: None

cost_y_expr_0

CasADi expression for nonlinear least squares, initial; Default: None

cost_y_expr_e

CasADi expression for nonlinear least squares, terminal; Default: None

disc_dyn_expr

CasADi expression for the discrete dynamics \(x_{+} = f_\text{disc}(x, u, p)\). Used if acados_template.acados_ocp.AcadosOcpOptions.integrator_type == ‘DISCRETE’. Default: None

dyn_disc_fun

name of function discrete dyanamics; Default: None

dyn_disc_fun_jac

name of function discrete dyanamics + jacobian; Default: None

dyn_disc_fun_jac_hess

name of function discrete dyanamics + jacobian and hessian; Default: None

dyn_ext_fun_type

type of external functions for dynamics module; ‘casadi’ or ‘generic’; Default: ‘casadi’

dyn_source_discrete

name of source file for discrete dyanamics; Default: None

f_expl_expr

CasADi expression for the explicit dynamics \(\dot{x} = f_\text{expl}(x, u, p)\). Used if acados_template.acados_ocp.AcadosOcpOptions.integrator_type == ‘ERK’. Default: None

f_impl_expr

CasADi expression for the implicit dynamics \(f_\text{impl}(\dot{x}, x, u, z, p) = 0\). Used if acados_template.acados_ocp.AcadosOcpOptions.integrator_type == ‘IRK’. Default: None

name

The model name is used for code generation. Type: string. Default: None

p

CasADi variable describing parameters of the DAE; Default: empty

u

CasADi variable describing the input of the system; Default: None

x

CasADi variable describing the state of the system; Default: None

xdot

CasADi variable describing the derivative of the state wrt time; Default: None

z

CasADi variable describing the algebraic variables of the DAE; Default: empty

acados integrator interface

The class AcadosSim can be used to formulate a simulation problem, for which an acados integrator (AcadosSimSolver) can be created.

class acados_template.acados_sim.AcadosSim(acados_path='')

The class has the following properties that can be modified to formulate a specific simulation problem, see below:

Parameters

acados_path – string with the path to acados. It is used to generate the include and lib paths.

acados_include_path

Path to acados include directors (set automatically), type: string

acados_lib_path

Path to where acados library is located (set automatically), type: string

code_export_directory

Path to where code will be exported. Default: c_generated_code.

dims

Dimension definitions, automatically detected from model. Type acados_template.acados_sim.AcadosSimDims

model

Model definitions, type acados_template.acados_model.AcadosModel

solver_options

Solver Options, type acados_template.acados_sim.AcadosSimOpts

class acados_template.acados_sim.AcadosSimDims

Class containing the dimensions of the model to be simulated.

property np

\(n_p\) - number of parameters. Type: int >= 0

property nu

\(n_u\) - number of inputs. Type: int >= 0

property nx

\(n_x\) - number of states. Type: int > 0

property nz

\(n_z\) - number of algebraic variables. Type: int >= 0

class acados_template.acados_sim.AcadosSimOpts

class containing the solver options

property T

Time horizon

property integrator_type

Integrator type. Default: ‘ERK’.

property newton_iter

Number of Newton iterations in simulation method. Default: 3

property num_stages

Number of stages in the integrator. Default: 1

property num_steps

Number of steps in the integrator. Default: 1

property output_z

Boolean determining if values for algebraic variables (corresponding to start of simulation interval) are computed. Default: False

property sens_adj

Boolean determining if adjoint sensitivities are computed. Default: False

property sens_algebraic

Boolean determining if sensitivities wrt algebraic variables are computed. Default: False

property sens_forw

Boolean determining if forward sensitivities are computed. Default: True

property sens_hess

Boolean determining if hessians are computed. Default: False

property sim_method_jac_reuse

Boolean determining if jacobians are reused. Default: False

class acados_template.acados_sim_solver.AcadosSimSolver(acados_sim_, json_file='acados_sim.json')

Class to interact with the acados integrator C object.

Parameters
get(field_)

Get the last solution of the solver.

param str field

string in [‘x’, ‘u’, ‘z’, ‘S_forw’, ‘Sx’, ‘Su’, ‘S_adj’, ‘S_hess’, ‘S_algebraic’]

set(field_, value_)

Set numerical data inside the solver.

param field

string in [‘p’, ‘S_adj’, ‘T’, ‘x’, ‘u’, ‘xdot’, ‘z’]

param value

the value with appropriate size.

solve()

Solve the simulation problem with current input.