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.

One can interact with the generated solver using the Python wrapper. There is a ctypes based wrapper which is the default and a cython based wrapper which allows for faster interaction with the C code, to allow deployment of the acados solver in a Python framework with less overhead.

Optimal Control Problem description

The Python interface relies on the same problem formulation as the MATLAB interface see here. Currently, Python >= 3.8 is required.

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
    # 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:

    pip install -e <acados_root>/interfaces/acados_template
    

    Note: The option -e makes the installation editable, so you can seamlessly 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>"
    

    NOTE: On MacOS DYLD_LIBRARY_PATH should be used instead of LD_LIBRARY_PATH. 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. The example has to be run from the folder in which it is located.

  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.

Windows 10+ (WSL) and VSCode

Virtual Environment

Follow the installation instructions above, using a virtual environment.

Connect to VS-Code

code .

to start VS-Code in the current folder.

  • Select the created virtual environment as Python interpreter.

Windows

The Python interface of acados can run natively under Windows using the CMake process. Take a look at the CMake installation instructions for Workflow with Microsoft Visual C Compiler (MSVC). We suggest to get started with the example <acados_root>/examples/acados_python/getting_started/minimal_example_ocp_cmake.py. It uses CMake instead of Make by providing an instance of the CMakeBuilder class to the constructor of AcadosOcpSolver or AcadosSimSolver. Depending on your Visual Studio Version the CMake generator might have to be adapted (see CMakeBuilder.generator).

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 interface – AcadosOcp and AcadosOcpSolver

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

The interface to interact with the acados OCP solver in C is based on ctypes.

Additionally, there is the option to use a Cython based wrapper around the C part. This offers faster interaction with the solver, because getter and setter calls, which include shape checking are done in compiled C code. The cython based wrapper is called AcadosOcpSolverCython and was added in PR #791. AcadosOcpSolverCython and AcadosOcpSolver offer the same functionality and equivalent behavior is ensured in CI tests.

class acados_template.acados_ocp_solver.AcadosOcpSolver(acados_ocp: Union[acados_template.acados_ocp.AcadosOcp, acados_template.acados_multiphase_ocp.AcadosMultiphaseOcp], json_file=None, simulink_opts=None, build=True, generate=True, cmake_builder: acados_template.builders.CMakeBuilder = None, verbose=True)

Class to interact with the acados ocp solver C object.

param acados_ocp

type AcadosOcp or AcadosMultiphaseOcp - 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

classmethod build(code_export_dir, with_cython=False, cmake_builder: acados_template.builders.CMakeBuilder = None, verbose: bool = True)
Builds the code for an acados OCP solver, that has been generated in code_export_dir
param code_export_dir

directory in which acados OCP solver has been generated, see generate()

param with_cython

option indicating if the cython interface is build, default: False.

param cmake_builder

type CMakeBuilder generate a CMakeLists.txt and use the CMake pipeline instead of a Makefile (CMake seems to be the better option in conjunction with MS Visual Studio); default: None

param verbose

indicating if build command is printed

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’, ‘C’, ‘D’]

param value

of appropriate size

cost_set(stage_: int, field_: str, 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’, ‘zl’, ‘zu’, ‘Zl’, ‘Zu’

param value

of appropriate size

classmethod create_cython_solver(json_file)

Returns an AcadosOcpSolverCython object.

This is an alternative Cython based Python wrapper to the acados OCP solver in C. This offers faster interaction with the solver, because getter and setter calls, which include shape checking are done in compiled C code.

The default wrapper AcadosOcpSolver is based on ctypes.

custom_update(data_: numpy.ndarray)

A custom function that can be implemented by a user to be called between solver calls. By default this does nothing. The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C, in a function that is compiled into the solver library and can be conveniently used in the Python environment.

dump_last_qp_to_json(filename: str = '', overwrite=False)

Dumps the latest QP data into a json file

param filename

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

param overwrite

if false and filename exists add timestamp to filename

eval_param_sens(index: int, stage: int = 0, field='ex')

Calculate the sensitivity of the current solution with respect to the initial state component of index.

NOTE: Correct computation of sensitivities requires

  1. HPIPM as QP solver,

  2. the usage of an exact Hessian,

  3. positive definiteness of the full-space Hessian if the square-root version of the Riccati recursion is used OR positive definiteness of the reduced Hessian if the classic Riccati recursion is used (compare: solver_options.qp_solver_ric_alg),

  4. the solution of at least one QP in advance to evaluation of the sensitivities as the factorization is reused.

    param index

    integer corresponding to initial state index in range(nx)

classmethod generate(acados_ocp: Union[acados_template.acados_ocp.AcadosOcp, acados_template.acados_multiphase_ocp.AcadosMultiphaseOcp], json_file: str, simulink_opts=None, cmake_builder: acados_template.builders.CMakeBuilder = None)
Generates the code for an acados OCP solver, given the description in acados_ocp.
param acados_ocp

type Union[AcadosOcp, AcadosMultiphaseOcp] - 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; default: None

param cmake_builder

type CMakeBuilder generate a CMakeLists.txt and use the CMake pipeline instead of a Makefile (CMake seems to be the better option in conjunction with MS Visual Studio); default: None

get(stage_: int, field_: str)

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_from_qp_in(stage_: int, field_: str)

Get numerical data from the current QP.

param stage

integer corresponding to shooting node

param field

string in [‘A’, ‘B’, ‘b’, ‘Q’, ‘R’, ‘S’, ‘q’, ‘r’, ‘C’, ‘D’, ‘lg’, ‘ug’, ‘lbx’, ‘ubx’, ‘lbu’, ‘ubu’]

Note: additional supported fields are [‘P’, ‘K’, ‘Lr’], which can be extracted form QP solver PARTIAL_CONDENSING_HPIPM.

get_hessian_block(stage: int) → numpy.ndarray

Get Hessian block from last QP at stage i In HPIPM form [[R, S^T], [S, Q]]

get_optimal_value_gradient()

Returns the gradient of the optimal value function w.r.t. the current initial state. Disclaimer: This function only returns reasonable values if the solver has converged for the current problem instance.

get_residuals(recompute=False)

Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. This residual has to be computed for SQP_RTI solver, since it is not available by default.

  • res_stat: stationarity residual

  • res_eq: residual wrt equality constraints (dynamics)

  • res_ineq: residual wrt inequality constraints (constraints)

  • res_comp: residual wrt complementarity conditions

get_stats(field_: str) → Union[int, float, numpy.ndarray]

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’, ‘residuals’, ‘qp_iter’, ‘alpha’]

Available fileds:
  • time_tot: total CPU time previous call

  • time_lin: CPU time for linearization

  • time_sim: CPU time for integrator

  • time_sim_ad: CPU time for integrator contribution of external function calls

  • time_sim_la: CPU time for integrator contribution of linear algebra

  • time_qp: CPU time qp solution

  • time_qp_solver_call: CPU time inside qp solver (without converting the QP)

  • time_qp_xcond: time_glob: CPU time globalization

  • time_solution_sensitivities: CPU time for previous call to eval_param_sens

  • time_reg: CPU time regularization

  • sqp_iter: number of SQP iterations

  • qp_stat: status of QP solver

  • qp_iter: vector of QP iterations for last SQP call

  • statistics: table with info about last iteration

  • stat_m: number of rows in statistics matrix

  • stat_n: number of columns in statistics matrix

  • residuals: residuals of last iterate

  • alpha: step sizes of SQP iterations

load_iterate(filename: str, verbose: bool = True)

Loads the iterate stored in json file with filename into the ocp solver. Note: This does not contain the iterate of the integrators, and the parameters.

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’, ‘qp_warm_start’, ‘line_search_use_sufficient_descent’, ‘full_step_dual’, ‘globalization_use_SOC’, ‘qp_tol_stat’, ‘qp_tol_eq’, ‘qp_tol_ineq’, ‘qp_tol_comp’, ‘qp_tau_min’, ‘qp_mu0’

param value

of type int, float, string

  • qp_tol_stat: QP solver tolerance stationarity

  • qp_tol_eq: QP solver tolerance equalities

  • qp_tol_ineq: QP solver tolerance inequalities

  • qp_tol_comp: QP solver tolerance complementarity

  • qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM

  • qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness

  • warm_start_first_qp: indicates if first QP in SQP is warm_started

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

  • alpha: SQP step size

  • 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

reset(reset_qp_solver_mem=1)

Sets current iterate to all zeros.

set(stage_: int, field_: str, value_)

Set numerical data inside the solver.

param stage

integer corresponding to shooting node

param field

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

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

set_new_time_steps(new_time_steps)

Set new time steps. Recreates the solver if N changes.

param new_time_steps

1 dimensional np array of new time steps for the solver

Note

This allows for different use-cases: either set a new size of time_steps or a new distribution of the shooting nodes without changing the number, e.g., to reach a different final time. Both cases do not require a new code export and compilation.

set_params_sparse(stage_: int, idx_values_: numpy.ndarray, param_values_)

set parameters of the solvers external function partially: Pseudo: solver.param[idx_values] = param_values; Parameters:

param stage

integer corresponding to shooting node

param idx_values

0 based np array (or iterable) of integers: indices of parameter to be set

param param_values

new parameter values as numpy array

solve()

Solve the ocp with current input.

solve_for_x0(x0_bar, fail_on_nonzero_status=True, print_stats_on_failure=True)

Wrapper around solve() which sets initial state constraint, solves the OCP, and returns u0.

store_iterate(filename: str = '', overwrite=False, verbose=True)

Stores the current iterate of the ocp solver in a json file. Note: This does not contain the iterate of the integrators, and the parameters.

param filename

if not set, use f’{self.name}_iterate.json’

param overwrite

if false and filename exists add timestamp to filename

update_qp_solver_cond_N(qp_solver_cond_N: int)

Recreate solver with new value qp_solver_cond_N with a partial condensing QP solver. This function is relevant for code reuse, i.e., if either set_new_time_steps(…) is used or the influence of a different qp_solver_cond_N is studied without code export and compilation.

param qp_solver_cond_N

new number of condensing stages for the solver

Note

This function can only be used in combination with a partial condensing QP solver.

Note

After set_new_time_steps(…) is used and depending on the new number of time steps it might be necessary to change qp_solver_cond_N as well (using this function), i.e., typically qp_solver_cond_N < N.

acados_template.acados_ocp_solver.__mocp_get_template_list(ocp: acados_template.acados_multiphase_ocp.AcadosMultiphaseOcp, cmake_builder=None, simulink_opts=None) → list

returns a list of tuples in the form: (input_filename, output_filname) or (input_filename, output_filname, output_directory)

acados_template.acados_ocp_solver.__ocp_get_template_list(ocp: acados_template.acados_ocp.AcadosOcp, cmake_builder=None, simulink_opts=None) → list

returns a list of tuples in the form: (input_filename, output_filname) or (input_filename, output_filname, output_directory)

acados_template.acados_ocp_solver.ocp_get_default_cmake_builder()acados_template.builders.CMakeBuilder

If AcadosOcpSolver is used with CMake this function returns a good first setting. :return: default CMakeBuilder

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 (set automatically), type: string

acados_lib_path

Path to where acados library is located, type: string

add_linear_constraint(C: numpy.ndarray, D: numpy.ndarray, lg: numpy.ndarray, ug: numpy.ndarray) → None

Add a linear constraint of the form lg <= C * x + D * u <= ug to the OCP.

code_export_directory

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

constraints

Constraints definitions, type acados_template.acados_ocp_constraints.AcadosOcpConstraints

cost

Cost definitions, type acados_template.acados_ocp_cost.AcadosOcpCost

dims

Dimension definitions, type acados_template.acados_dims.AcadosOcpDims

formulate_constraint_as_Huber_penalty(constr_expr: casadi.casadi.SX, weight: float, upper_bound: Optional[float, None], lower_bound: Optional[float, None], residual_name: str = 'new_residual', huber_delta: float = 1.0, use_xgn=True, min_hess=0) → None

Formulate a constraint as Huber penalty and add it to the current cost.

use_xgn: if true an XGN Hessian is used, if false a GGN Hessian (= exact Hessian, in this case) is used. min_hess: provide a minimum value for the hessian

formulate_constraint_as_L2_penalty(constr_expr: casadi.casadi.SX, weight: float, upper_bound: Optional[float, None], lower_bound: Optional[float, None], residual_name: str = 'new_residual') → None

Formulate a constraint as an L2 penalty and add it to the current cost.

model

Model definitions, type acados_template.acados_model.AcadosModel

property parameter_values

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

solver_options

Solver Options, type acados_template.acados_ocp_options.AcadosOcpOptions

translate_nls_cost_to_conl()

Translates a NONLINEAR_LS cost to a CONVEX_OVER_NONLINEAR cost.

zoro_description

zoRO - zero order robust optimization - description: for advanced users.

class acados_template.acados_ocp_cost.AcadosOcpCost

Class containing the numerical data of the cost:

NOTE: all cost terms, except for the terminal one are weighted with the corresponding time step. This means given the time steps are \(\Delta t_0,..., \Delta t_N\), the total cost is given by: \(c_\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + ... + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)\).

This means the Lagrange cost term is given in continuous time, this makes up for a seeminglessly OCP discretization with a nonuniform time grid.

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,p) = || y(x,u,z,p) - y_\text{ref}||^2_W\), terminal cost is \(m(x,p) = || y^e(x,p) - y_\text{ref}^e||^2_{W^e}\)

In case of CONVEX_OVER_NONLINEAR: stage cost is \(l(x,u,p) = \psi(y(x,u,p) - y_\text{ref}, p)\), terminal cost is \(m(x, p) = \psi^e (y^e(x,p) - y_\text{ref}^e, p)\)

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 (0 to N-1). Default: np.array([]).

property Zl_0

\(Z_l^0\) - diagonal of Hessian wrt lower slack at initial node 0. 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 (0 to N-1). Default: np.array([]).

property Zu_0

\(Z_u^0\) - diagonal of Hessian wrt upper slack at initial node 0. 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 terminal shooting node (N). – 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, CONVEX_OVER_NONLINEAR}. Default: ‘LINEAR_LS’.

property cost_type_0

Cost type at initial shooting node (0) – string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR} 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, CONVEX_OVER_NONLINEAR}. 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 (0 to N-1). Default: np.array([]).

property zl_0

\(z_l^0\) - gradient wrt lower slack at initial node 0. 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 (0 to N-1). Default: np.array([]).

property zu_0

\(z_u^0\) - gradient wrt upper slack at initial node 0. 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_constraints.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_0

\(J_{s,h}^0\) - matrix coefficient for soft bounds on nonlinear constraints at initial shooting node 0; fills idxsh_0

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_0

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

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}. Detected automatically from model. Default: BGH; BGP is for convex over nonlinear.

property constr_type_0

Constraints type for initial shooting node. string in {BGH, BGP}. Detected automatically from model. Default: BGH; BGP is for convex over nonlinear.

property constr_type_e

Constraints type for terminal shooting node N. string in {BGH, BGP}. Detected automatically from model. 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_0

Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at initial shooting node 0. Can be set by using Jsh_0.

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_0

Indices of soft nonlinear constraints at shooting node N within the indices of nonlinear constraints at initial shooting node 0. Can be set by using Jsphi_0. 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 intermediate shooting nodes (1 to N-1). Type: np.ndarray; default: np.array([]).

property lh_0

\(\underline{h}^0\) - lower bound on nonlinear inequalities at initial shooting node (0). 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_0

\(\underline{\phi}^0\) - lower bound on convex-over-nonlinear inequalities at shooting node 0. 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_0

Lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints at initial shooting node 0. 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_0

Lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints at initial shooting node 0. 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 intermediate shooting nodes (1 to N-1). Type: np.ndarray; default: np.array([]).

property uh_0

\(\bar{h}^0\) - upper bound on nonlinear inequalities at initial shooting node (0). 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_0

\(\bar{\phi}^0\) - upper bound on convex-over-nonlinear inequalities at shooting node 0. 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_0

Lower bounds on slacks corresponding to soft upper bounds for nonlinear constraints at initial shooting node 0. 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_0

Lower bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints at initial shooting node 0. 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_options.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 collocation_type

Collocation type: only relevant for implicit integrators – string in {‘GAUSS_RADAU_IIA’, ‘GAUSS_LEGENDRE’, ‘EXPLICIT_RUNGE_KUTTA’}.

Default: GAUSS_LEGENDRE

property cost_discretization

Cost discretization: string in {‘EULER’, ‘INTEGRATOR’}. Default: ‘EULER’ ‘EULER’: cost is evaluated at shooting nodes ‘INTEGRATOR’: cost is integrated over the shooting intervals - only supported for IRK integrator

property custom_templates

List of tuples of the form: (input_filename, output_filename)

Custom templates are render in OCP solver generation.

Default: [].

property custom_update_copy

Boolean; If True, the custom update function files are copied into the code_export_directory.

property custom_update_filename

Filename of the custom C function to update solver data and parameters in between solver calls

This file has to implement the functions int custom_update_init_function([model.name]_solver_capsule* capsule); int custom_update_function([model.name]_solver_capsule* capsule); int custom_update_terminate_function([model.name]_solver_capsule* capsule);

Default: ‘’.

property custom_update_header_filename

Header filename of the custom C function to update solver data and parameters in between solver calls

This file has to declare the custom_update functions and look as follows:

// Called at the end of solver creation.

// This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory.

int custom_update_init_function([model.name]_solver_capsule* capsule);

// Custom update function that can be called between solver calls

int custom_update_function([model.name]_solver_capsule* capsule, double* data, int data_len);

// Called just before destroying the solver.

// Responsible to free allocated memory, stored at capsule->custom_update_memory.

int custom_update_terminate_function([model.name]_solver_capsule* capsule);

Default: ‘’.

property eps_sufficient_descent

Factor for sufficient descent (Armijo) conditon, see line_search_use_sufficient_descent. Type: float, default: 1e-4.

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 ext_fun_compile_flags

String with compiler flags for external function compilation. Default: ‘-O2’.

property full_step_dual

Determines if dual variables are updated with full steps (alpha=1.0) when primal variables are updated with smaller step. Type: int; 0 or 1; default: 0.

property globalization

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

Note

preliminary implementation.

property globalization_use_SOC

Determines if second order correction (SOC) is done when using MERIT_BACKTRACKING. SOC is done if preliminary line search does not return full step. Type: int; 0 or 1; default: 0.

property hessian_approx

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

property hpipm_mode

Mode of HPIPM to be used,

String in (‘BALANCE’, ‘SPEED_ABS’, ‘SPEED’, ‘ROBUST’).

Default: ‘BALANCE’.

see https://cdn.syscop.de/publications/Frison2020a.pdf and the HPIPM code: https://github.com/giaf/hpipm/blob/master/ocp_qp/x_ocp_qp_ipm.c#L69

property integrator_type

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

property levenberg_marquardt

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

property line_search_use_sufficient_descent

Determines if sufficient descent (Armijo) condition is used in line search. Type: int; 0 or 1; default: 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_ext_qp_res

Determines if residuals of QP are computed externally within NLP solver (for debugging)

Type: int; 0 or 1; Default: 0.

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’, ‘FULL_CONDENSING_DAQP’). 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_cond_ric_alg

QP solver: Determines which algorithm is used in HPIPM condensing. 0: dont factorize hessian in the condensing; 1: factorize. Default: 1

property qp_solver_iter_max

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

property qp_solver_ric_alg

QP solver: Determines which algorithm is used in HPIPM OCP QP solver. 0 classical Riccati, 1 square-root Riccati.

Note: taken from [HPIPM paper]:

  1. the classical implementation requires the reduced (projected) Hessian with respect to the dynamics equality constraints to be positive definite, but allows the full-space Hessian to be indefinite)

  2. the square-root implementation, which in order to reduce the flop count employs the Cholesky factorization of the Riccati recursion matrix (P), and therefore requires the full-space Hessian to be positive definite

[HPIPM paper]: HPIPM: a high-performance quadratic programming framework for model predictive control, Frison and Diehl, 2020 https://cdn.syscop.de/publications/Frison2020a.pdf

Default: 1

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. Default: 0

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 reg_epsilon

Epsilon for regularization, used if regularize_method in [‘PROJECT’, ‘MIRROR’, ‘CONVEXIFY’]

property regularize_method

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

  • MIRROR: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, abs(D_ii))

  • PROJECT: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, D_ii)

  • CONVEXIFY: Algorithm 6 from Verschueren2017, https://cdn.syscop.de/publications/Verschueren2017.pdf

  • PROJECT_REDUC_HESS: experimental

Note: default eps = 1e-4

Default: ‘NO_REGULARIZE’.

property shooting_nodes

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

property sim_method_jac_reuse

Integer determining if jacobians are reused within integrator or ndarray of ints > 0 of shape (N,). 0: False (no reuse); 1: True (reuse) Default: 0

property sim_method_newton_iter

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

property sim_method_newton_tol

Tolerance of Newton system in simulation method. Type: float: 0.0 means not used Default: 0.0

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_dims.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_0

\(n_{h}^e\) - number of nonlinear constraints at initial shooting node. 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_0

\(n_{\phi}^0\) - number of convex-over-nonlinear constraints at initial shooting node 0. 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_0

\(n_{\pi}^0\) - 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 at stages (1, N-1). Type: int; default: 0

property ns_0

\(n_{s}^0\) - total number of slacks at shooting node 0. 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_0

\(n_{{sh}}^0\) - number of soft nonlinear constraints at shooting node 0. 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_0

\(n_{{s\phi}^0}\) - number of soft convex-over-nonlinear constraints at shooting node 0. 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_dims.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_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.

augment_model_with_polynomial_control(degree: int) → None

Augment the model with polynomial control.

Replace the original control input \(u\) with a polynomial control input \(v_{\text{poly}} = \sum_{i=0}^d u_i t^i\) New controls are \(u_0, \dots, u_d\).

NOTE: bounds on controls are not changed in this function.

Parameters

degree (int) – degree of the polynomial control

con_h_expr

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

con_h_expr_0

CasADi expression for the initial constraint \(h^0\); 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_0

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

con_phi_expr_e

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

con_r_expr

CasADi expression for the constraint phi(r), dummy input for outer function; Default: None

con_r_expr_0

CasADi expression for the terminal constraint \(\phi_0(r)\), dummy input for outer function; Default: None

con_r_expr_e

CasADi expression for the terminal constraint \(\phi_e(r)\), dummy input for outer function; Default: None

con_r_in_phi

CasADi expression for the terminal constraint \(\phi(r)\), input for outer function; Default: None

con_r_in_phi_0

CasADi expression for the terminal constraint \(\phi_0(r)\), input for outer function; Default: None

con_r_in_phi_e

CasADi expression for the terminal constraint \(\phi_e(r)\), input for outer function; Default: None

cost_conl_custom_outer_hess

CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost); Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type is ‘CONVEX_OVER_NONLINEAR’.

cost_conl_custom_outer_hess_0

CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), initial; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_0 is ‘CONVEX_OVER_NONLINEAR’.

cost_conl_custom_outer_hess_e

CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), terminal; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_e is ‘CONVEX_OVER_NONLINEAR’.

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_custom_hess

CasADi expression for custom hessian (only for external cost); Default: None

cost_expr_ext_cost_custom_hess_0

CasADi expression for custom hessian (only for external cost), initial; Default: None

cost_expr_ext_cost_custom_hess_e

CasADi expression for custom hessian (only for external cost), terminal; Default: None

cost_expr_ext_cost_e

CasADi expression for external cost, terminal; Default: None

cost_psi_expr

CasADi expression for the outer loss function \(\psi(r, p)\); Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type is ‘CONVEX_OVER_NONLINEAR’.

cost_psi_expr_0

CasADi expression for the outer loss function \(\psi(r, p)\), initial; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_0 is ‘CONVEX_OVER_NONLINEAR’.

cost_psi_expr_e

CasADi expression for the outer loss function \(\psi(r, p)\), terminal; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_e is ‘CONVEX_OVER_NONLINEAR’.

cost_r_in_psi_expr

CasADi symbolic input variable for the argument \(r\) to the outer loss function \(\psi(r, p)\); Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type is ‘CONVEX_OVER_NONLINEAR’.

cost_r_in_psi_expr_0

CasADi symbolic input variable for the argument \(r\) to the outer loss function \(\psi(r, p)\), initial; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_0 is ‘CONVEX_OVER_NONLINEAR’.

cost_r_in_psi_expr_e

CasADi symbolic input variable for the argument \(r\) to the outer loss function \(\psi(r, p)\), terminal; Default: None Used if acados_template.acados_ocp_options.AcadosOcpOptions.cost_type_e is ‘CONVEX_OVER_NONLINEAR’.

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_options.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_generic_source

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_options.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_options.AcadosOcpOptions.integrator_type == ‘IRK’. Default: None

gnsf

dictionary containing information on GNSF structure needed when rendering templates. Contains integers nontrivial_f_LO, purely_linear.

name

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

nu_original

Number of original control inputs (before polynomial control augmentation); Default: None

p

CasADi variable describing parameters of the DAE; Default: []

t

CasADi variable representing time t in functions; Default: []

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: []

acados integrator interface – AcadosSim and AcadosSimSolver

The class AcadosSim can be used to formulate a simulation problem, for which an acados integrator (AcadosSimSolver) can be created. The interface to interact with the acados integrator in C is based on ctypes.

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 directory (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_dims.AcadosSimDims

model

Model definitions, type acados_template.acados_model.AcadosModel

property parameter_values

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

solver_options

Solver Options, type acados_template.acados_sim.AcadosSimOpts

class acados_template.acados_sim.AcadosSimOpts

class containing the solver options

property T

Time horizon

property collocation_type

Collocation type: relevant for implicit integrators – string in {‘GAUSS_RADAU_IIA’, ‘GAUSS_LEGENDRE’, ‘EXPLICIT_RUNGE_KUTTA’}.

Default: GAUSS_LEGENDRE

property ext_fun_compile_flags

String with compiler flags for external function compilation. Default: ‘-O2’.

property integrator_type

Integrator type. Default: ‘ERK’.

property newton_iter

Number of Newton iterations in simulation method. Default: 3

property newton_tol

Tolerance for Newton system solved in implicit integrator (IRK, GNSF). 0.0 means this is not used and exactly newton_iter iterations are carried out. Default: 0.0

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: True

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

Integer determining if jacobians are reused (0 or 1). Default: 0

class acados_template.acados_sim_solver.AcadosSimSolver(acados_sim: acados_template.acados_sim.AcadosSim, json_file='acados_sim.json', generate=True, build=True, cmake_builder: acados_template.builders.CMakeBuilder = None, verbose: bool = True)

Class to interact with the acados integrator C object.

param acados_sim

type AcadosOcp (takes values to generate an instance AcadosSim) or AcadosSim

param json_file

Default: ‘acados_sim.json’

param build

Default: True

param cmake_builder

type CMakeBuilder generate a CMakeLists.txt and use the CMake pipeline instead of a Makefile (CMake seems to be the better option in conjunction with MS Visual Studio); default: None

classmethod create_cython_solver(json_file)
classmethod generate(acados_sim: acados_template.acados_sim.AcadosSim, json_file='acados_sim.json', cmake_builder: acados_template.builders.CMakeBuilder = None)

Generates the code for an acados sim solver, given the description in acados_sim

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’, ‘CPUtime’, ‘time_tot’, ‘ADtime’, ‘time_ad’, ‘LAtime’, ‘time_la’]

options_set(field_: str, value_: bool)

Set solver options

param field

string in [‘sens_forw’, ‘sens_adj’, ‘sens_hess’]

param value

Boolean

set(field_: str, value_)

Set numerical data inside the solver.

param field

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

param value

the value with appropriate size.

simulate(x=None, u=None, z=None, p=None)

Simulate the system forward for the given x, u, z, p and return x_next. Wrapper around solve() taking care of setting/getting inputs/outputs.

solve()

Solve the simulation problem with current input.

acados_template.acados_sim_solver.sim_get_default_cmake_builder()acados_template.builders.CMakeBuilder

If AcadosSimSolver is used with CMake this function returns a good first setting. :return: default CMakeBuilder

Builders

The default builder for acados is make using a Makefile generated by acados. If cross-platform compatibility is required CMake can be used to build the binaries required by the solvers.

class acados_template.builders.CMakeBuilder

Class to work with the CMake build system.

build_targets

A comma-separated list of the build targets, if None then all targets will be build; type: List of strings; default: None.

exec(code_export_directory, verbose=True)

Execute the compilation using CMake with the given settings. :param code_export_directory: must be the absolute path to the directory where the code was exported to

host

Defines the generator, options can be found via cmake –help under ‘Generator’. Type: string. Linux default ‘Unix Makefiles’, Windows ‘Visual Studio 15 2017 Win64’; default value: None.

options_on

List of strings as CMake options which are translated to ‘-D Opt[0]=ON -D Opt[1]=ON …’; default: None.

acados multi-phase OCP

Advanced feature interface to formulate multi-phase OCPs.

Added in #1004 and #1007.

class acados_template.acados_multiphase_ocp.AcadosMultiphaseOcp(N_list: list)

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

Initial cost and constraints are defined by the first phase, terminal cost and constraints by the last phase. All other phases are treated as intermediate phases, where only dynamics and path cost and constraints are used. Solver options are shared between all phases. Options that can vary phase-wise must be set via self.mocp_opts of type AcadosMultiphaseOptions.

Parameters

N_list – list containing the number of shooting intervals for each phase

acados_include_path

Path to acados include directory (set automatically), 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_constraints.AcadosOcpConstraints

cost

Cost definitions, type acados_template.acados_ocp_cost.AcadosOcpCost

mocp_opts

Phase-wise varying solver Options, type acados_template.acados_multiphase_ocp.AcadosMultiphaseOptions

model

Model definitions, type acados_template.acados_model.AcadosModel

property parameter_values

\(p\) - list of initial values for parameter vector. Type: list of numpy.ndarray of shape (np_i, ). - can be updated stagewise.

set_phase(ocp: acados_template.acados_ocp.AcadosOcp, phase_idx: int) → None

Set phase of the multiphase OCP to match the given OCP.

NOTE: model, cost, constraints and parameter_values are taken from phase OCP,

all other fields, especially options are ignored.

Parameters
  • ocp – OCP to be set as phase

  • phase_idx – index of the phase, must be in [0, n_phases-1]

solver_options

Solver Options, type acados_template.acados_ocp_options.AcadosOcpOptions

class acados_template.acados_multiphase_ocp.AcadosMultiphaseOptions

Class containing options that might be different for each phase.

All of the fields can be either None, then the corresponding value from ocp.solver_options is used, or a list of length n_phases describing the value for this option at each phase.