Interfaces

C API

The C API of acados is an efficient interface to the core functionalities of acados. It provides setters and getters that can be used to interact with the core of acados with negligible computation overhead. In order to learn about the acados C API, you can look at the examples in acados/examples/c/.

MATLAB/Octave (rapid prototyping)

This interface makes a broad set of acados functionalities available from Matlab or Octave. As of now, this closely tracks the latest developments in the core of acados, e.g. exact Hessians, adjoint corrections, regularization, etc.

To get started with this interface we recommend the examples in <acados_root>/examples/acados_matlab_octave/getting_started.

The problem formulation is stated in this PDF.

The explanation of the various options can be found also in a spreadsheet style at this link (thanks to @EnricaSo).

This interface uses the shared libraries created using the make command from the main acados folder

make shared_library

To run the examples, navigate into the selected folder, and there run the command

export ACADOS_INSTALL_DIR="<acados_root>"
source env.sh # Which can be found in the folder of one of the examples

If ACADOS_INSTALL_DIR is not specified, it will be assumed that the examples are run from the sub-folders of the current folder (i.e. acados main folder is 2 folders up from the current folder).

Afterwards, launch Matlab or Octave from the same shell.

If you want to run the examples in a different folder, please close the current shell and open a new one to repeat the procedure: this ensures the correct setting of the environment variables.

MATLAB/Octave (templates, Work In Progress)

There is the option to generate embeddable C code from Matlab. The workflow uses the same templates as the Python interface (see below) and the Tera renderer. After creating an acados solver ocp, you can use the routine ocp.generate_c_code to generate C code which can be used for embedded applications.

Note: This part of the MATLAB/Octave interface does not yet support all features of the one mentioned before.

Python (templates)

acados_template is a Python package that can be used to specify optimal control problems from Python and to generate self-contained C code that uses the acados solvers to solve them. 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 running:

cd <acados_root>/build
cmake -DACADOS_WITH_QPOASES=ON ..
make install -j4
  1. Install acados_template Python package by running

pip3 install <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.

  1. 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"

Tipp: you can add this line to your .bashrc/.zshrc.

  1. 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.

  2. 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.

  3. 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.

For more information contact @zanellia.

Python API

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

class containing the full description of the optimal control problem

parameter_values

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

class acados_template.acados_ocp.AcadosOcpConstraints

class containing the description of the constraints

C

\(C\) - C matrix in lg <= D * u + C * x <= ug

C_e

\(C^e\) - C matrix at t=T

D

\(D\) - D matrix in lg <= D * u + C * x <= ug

Jbu

\(J_{bu}\) - matrix coefficient for bounds on u

Jbx

\(J_{bx}\) - matrix coefficient for bounds on x

Jbx_e

\(J_{bx}^e\) matrix coefficient for bounds on x at t=T

Jsbu

\(J_{sbu}\) - matrix coefficient for soft bounds on u

Jsbx

\(J_{sbx}\) - matrix coefficient for soft bounds on x

Jsbx_e

\(J_{sbx}^e\) - matrix coefficient for soft bounds on x at t=T

Jsg

\(J_{sg}\) - matrix coefficient for soft bounds on general linear constraints

Jsg_e

\(J_{s,h}^e\) - matrix coefficient for soft bounds on general linear constraints at t=T

Jsh

\(J_{sh}\) - matrix coefficient for soft bounds on nonlinear constraints

Jsh_e

\(J_{s,h}^e\) - matrix coefficient for soft bounds on nonlinear constraints at t=T

Jsphi

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

Jsphi_e

\(J_{sh}^e\) - matrix coefficient for soft bounds on convex-over-nonlinear constraints at t=T

constr_type

Constraints type

constr_type_e

Constraints type t=T

idxbu

indexes of bounds on u (defines \(J_{bu}\))

idxbx

indexes of bounds on x (defines \(J_{bx}\))

idxbx_0

indexes of bounds on x0

idxbx_e

indexes for bounds on x at t=T (defines \(J_{bx}^e\))

idxbxe_0

indexes of bounds on x0 that are equalities (set automatically)

idxsbu

indexes of soft bounds on u within the indices of bounds on u

idxsbx

indexes of soft bounds on x within the indices of bounds on x

idxsbx_e

indexes of soft bounds on x at t=T, within the indices of bounds on x at t=T

idxsg

indexes of soft general linear constraints within the indices of general linear constraints

idxsg_e

indexes of soft general linear constraints at t=T within the indices of general linear constraints at t=T

idxsh

indexes of soft nonlinear constraints within the indices of nonlinear constraints

idxsh_e

indexes of soft nonlinear constraints at t=T within the indices of nonlinear constraints at t=T

idxsphi

indexes of soft convex-over-nonlinear constraints within the indices of nonlinear constraints

idxsphi_e

indexes of soft nonlinear constraints at t=T within the indices of nonlinear constraints at t=T

lbu

\(\underline{u}\) - lower bounds on u

lbx

\(\underline{x}\) - lower bounds on x

lbx_0

\(\underline{x_0}\) - lower bounds on x0

lbx_e

\(\underline{x}^e\) - lower bounds on x at t=T

lg

\(\underline{g}\) - lower bound for general polytopic inequalities

lg_e

\(\underline{g}^e\) - lower bound on general polytopic inequalities at t=T

lh

\(\underline{h}\) - lower bound for nonlinear inequalities

lh_e

\(\underline{h}^e\) - lower bound on nonlinear inequalities at t=T

lphi

\(\underline{\phi}\) - lower bound for convex-over-nonlinear inequalities

lphi_e

\(\underline{\phi}^e\) - lower bound on convex-over-nonlinear inequalities at t=T

lsbu

lower bounds on slacks corresponding to soft lower bounds on u

lsbx

lower bounds on slacks corresponding to soft lower bounds on x

lsbx_e

lower bounds on slacks corresponding to soft lower bounds on x at t=T

lsg

lower bounds on slacks corresponding to soft lower bounds for general linear constraints

lsg_e

lower bounds on slacks corresponding to soft lower bounds for general linear constraints at t=T

lsh

lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints

lsh_e

lower bounds on slacks corresponding to soft lower bounds for nonlinear constraints at t=T

lsphi

lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints

lsphi_e

lower bounds on slacks corresponding to soft lower bounds for convex-over-nonlinear constraints at t=T

ubu

\(\bar{u}\) - upper bounds on u

ubx

\(\bar{x}\) - upper bounds on x

ubx_0

\(\bar{x_0}\) - upper bounds on x0

ubx_e

\(\bar{x}^e\) - upper bounds on x at t=T

ug

\(\bar{g}\) - upper bound for general polytopic inequalities

ug_e

\(\bar{g}^e\) - upper bound on general polytopic inequalities at t=T

uh

\(\bar{h}\) - upper bound for nonlinear inequalities

uh_e

\(\bar{h}^e\) - upper bound on nonlinear inequalities at t=T

uphi

\(\bar{\phi}\) - upper bound for convex-over-nonlinear inequalities

uphi_e

\(\bar{\phi}^e\) - upper bound on convex-over-nonlinear inequalities at t=T

usbu

upper bounds on slacks corresponding to soft upper bounds on u

usbx

upper bounds on slacks corresponding to soft upper bounds on x

usbx_e

upper bounds on slacks corresponding to soft upper bounds on x at t=T

usg

upper bounds on slacks corresponding to soft upper bounds for general linear constraints

usg_e

upper bounds on slacks corresponding to soft upper bounds for general linear constraints at t=T

ush

upper bounds on slacks corresponding to soft upper bounds for nonlinear constraints

ush_e

upper bounds on slacks corresponding to soft upper bounds for nonlinear constraints at t=T

usphi

upper bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints

usphi_e

upper bounds on slacks corresponding to soft upper bounds for convex-over-nonlinear constraints at t=T

x0

\(\bar{x}_0\) - initial state

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}\)

Vu

\(V_u\) - u matrix coefficient

Vx

\(V_x\) - x matrix coefficient

Vx_e

\(W^e\) - weight matrix for Mayer term

Vz

\(V_z\) - z matrix coefficient

W

\(W\) - weight matrix

W_e

\(W\) - weight matrix

Zl

\(Z_l\) - diagonal of Hessian wrt lower slack

Zl_e

\(Z_l^e\) - diagonal of Hessian wrt upper slack for Mayer term

Zu

\(Z_u\) - diagonal of Hessian wrt upper slack

Zu_e

\(Z_l^e\) - diagonal of Hessian wrt upper slack for Mayer term

cost_type

cost type

cost_type_e

cost type for Mayer term, either LINEAR_LS, NONLINEAR_LS, AUTO

yref

\(y_{ ext{ref}}\) - reference

yref_e

\(V_x^e\) - x matrix coefficient for Mayer term

zl

\(z_l\) - gradient wrt lower slack

zl_e

\(z_l^e\) - gradient wrt lower slack for Mayer term

zu

\(z_u\) - gradient wrt upper slack

zu_e

\(z_u^e\) - gradient wrt upper slack for Mayer term

class acados_template.acados_ocp.AcadosOcpDims

class containing the dimensions of the optimal control problem

N

\(N\) - prediction horizon

nbu

\(n_{b_u}\) - number of input bounds

nbx

\(n_{b_x}\) - number of state bounds

nbx_0

\(n_{b_{x0}}\) - number of state bounds for initial state

nbx_e

\(n_{b_x}\) - number of state bounds at t=T

nbxe_0

\(n_{be_{x0}}\) - number of state bounds at initial shooting node that are equalities

ng

\(n_{g}\) - number of general polytopic constraints

ng_e

\(n_{g}^e\) - number of general polytopic constraints at t=T

nh

\(n_h\) - number of nonlinear constraints

nh_e

\(n_{h}^e\) - number of nonlinear constraints at t=T

np

\(n_p\) - number of parameters

nphi

\(n_{\phi}\) - number of convex-over-nonlinear constraints

nphi_e

\(n_{\phi}^e\) - number of convex-over-nonlinear constraints at t=T

nr

\(n_{\pi}\) - dimension of the image of the inner nonlinear function in positive definite constraints

nr_e

\(n_{\pi}^e\) - dimension of the image of the inner nonlinear function in positive definite constraints

ns

\(n_{s}\) - total number of slacks

ns_e

\(n_{s}^e\) - total number of slacks at t=T

nsbu

\(n_{{sb}_u}\) - number of soft input bounds

nsbx

\(n_{{sb}_x}\) - number of soft state bounds

nsbx_e

\(n_{{sb}^e_{x}}\) - number of soft state bounds at t=T

nsg

\(n_{{sg}}\) - number of soft general linear constraints

nsg_e

\(n_{{sg}^e}\) - number of soft general linear constraints at t=T

nsh

\(n_{{sh}}\) - number of soft nonlinear constraints

nsh_e

\(n_{{sh}}^e\) - number of soft nonlinear constraints at t=T

nsphi

\(n_{{s\phi}}\) - number of soft convex-over-nonlinear constraints

nsphi_e

\(n_{{s\phi}^e}\) - number of soft convex-over-nonlinear constraints at t=T

nu

\(n_u\) - number of inputs

nx

\(n_x\) - number of states

ny

\(n_y\) - number of residuals in Lagrange term

ny_e

\(n_{y}^e\) - number of residuals in Mayer term

nz

\(n_z\) - number of algebraic variables

class acados_template.acados_ocp.AcadosOcpOptions

class containing the description of the solver options

Tsim

Time horizon for one integrator step

exact_hess_constr

Used in case of hessian_approx == ‘EXACT’.

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

exact_hess_cost

Used in case of hessian_approx == ‘EXACT’.

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

exact_hess_dyn

Used in case of hessian_approx == ‘EXACT’.

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

hessian_approx

Hessian approximation

integrator_type

Integrator type

levenberg_marquardt

Factor for LM regularization

model_external_shared_lib_dir

Path to the .so lib

model_external_shared_lib_name

Name of the .so lib

nlp_solver_max_iter

NLP solver maximum number of iterations

nlp_solver_step_length

Fixed Newton step length

nlp_solver_tol_comp

NLP solver complementarity tolerance

nlp_solver_tol_eq

NLP solver equality tolerance

nlp_solver_tol_ineq

NLP solver inequality tolerance

nlp_solver_tol_stat

NLP solver stationarity tolerance

nlp_solver_type

NLP solver

print_level

Verbosity of printing

qp_solver

QP solver to be used in the NLP solver

qp_solver_cond_N

QP solver: New horizon after partial condensing

qp_solver_iter_max

QP solver: maximum number of iterations

qp_solver_tol_comp

QP solver complementarity

qp_solver_tol_eq

QP solver equality tolerance

qp_solver_tol_ineq

QP solver inequality

qp_solver_tol_stat

QP solver stationarity tolerance

regularize_method

Regularization method for the Hessian

shooting_nodes

Vector with the shooting nodes, time_steps will be computed from it automatically

sim_method_jac_reuse

Boolean determining if jacobians are reused within integrator

sim_method_newton_iter

Number of Newton iterations in simulation method

sim_method_num_stages

Number of stages in the integrator

sim_method_num_steps

Number of steps in the integrator

tf

Prediction horizon

time_steps

Vector with time steps between the shooting nodes. Set automatically to uniform discretization if N, tf are provided

tol

NLP solver tolerance

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 = None

CasADi expression for the constraint h

con_h_expr_e = None

CasADi expression for the constraint

con_phi_expr = None

CasADi expression for the constraint phi

con_phi_expr_e = None

CasADi expression for the constraint

con_r_expr = None

CasADi expression for the constraint phi(r)

con_r_expr_e = None

CasADi expression for the constraint

cost_expr_ext_cost = None

CasADi expression for external cost

cost_expr_ext_cost_e = None

CasADi expression for external cost, terminal

cost_y_expr = None

CasADi expression for nonlinear least squares

cost_y_expr_e = None

CasADi expression for nonlinear least squares, terminal

f_expl_expr = None

CasADi expression for the explicit dynamics \(\dot{x} = f(x, u)\)

f_impl_expr = None

CasADi expression for the implicit dynamics \(F(\dot{x}, x, u, z) = 0\)

name = None

model name

p = None

CasADi variable describing parameters of the DAE

u = None

CasADi variable describing the input of the system

x = None

CasADi variable describing the state of the system

xdot = None

CasADi variable describing the derivative of the state wrt time

z = None

CasADi variable describing the algebraic variables of the DAE

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

class to interact with the acados ocp solver C object

constraints_set(stage_, field_, value_)

set numerical data in the constraint module of the solver: Parameters:

param stage_

integer corresponding to shooting node

param field_

string, e.g. ‘lbx’

param value_

of appropriate size

cost_set(stage_, field_, value_)
set numerical data in the cost module of the solver:
param stage_

integer corresponding to shooting node

param field_

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

param value_

of appropriate size

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_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’]

options_set(field_, value_)

set options of the solver: Parameters:

param field_

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

param value_

of type int, float

solve()

solve the ocp with current input

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

class containing the full description of the integrator

class acados_template.acados_sim.AcadosSimDims

class containing the dimensions of the model to be simulated

np

\(n_p\) - number of parameters

nu

\(n_u\) - number of inputs

nx

\(n_x\) - number of states

nz

\(n_z\) - number of algebraic variables

class acados_template.acados_sim.AcadosSimOpts

class containing the solver options

T

Time horizon

integrator_type

Integrator type

newton_iter

Number of Newton iterations in simulation method

num_stages

Number of stages in the integrator

num_steps

Number of steps in the integrator

output_z

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

sens_adj

Boolean determining if adjoint sensitivities are computed

sens_algebraic

Boolean determining if sensitivities wrt algebraic variables are computed

sens_forw

Boolean determining if forward sensitivities are computed

sens_hess

Boolean determining if hessians are computed

sim_method_jac_reuse

Boolean determining if jacobians are reused