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. In comparison with the MATLAB interface for rapid prototyping (see above), it supports less features, but it allows the user to generate a self-contained C library that can be easily deployed on an embedded system.

The framework is based on templated C files which are rendered from Python using the templating engine Tera.

Optimal Control Problem description

The currently supported formulation reads as

\[\begin{split}\begin{equation} \begin{aligned} &\underset{\begin{subarray}{c} x(\cdot),\,u(\cdot), \, z(\cdot) \end{subarray}}{\min} &&\int_0^T l(x(\tau), u(\tau), z(\tau), p)\mathrm{d}\tau + m(x(T), z(T), p)\\ &\,\,\,\quad \text{s.t.} &&x(0) - \bar{x}_0 = 0, &&\\ &&&F(x(t), \dot{x}(t), u(t), z(t), p) = 0, &&\quad t \in [0,\,T),\\ &&&\underline{h} \leq h(x(t), u(t), p) \leq \bar{h}, &&\quad t \in [0,\,T),\\ &&&\underline{x} \leq \Pi_{x}x(t) \leq \bar{x}, &&\quad t \in [0,\,T),\\ &&&\underline{u} \leq \Pi_{u}u(t) \leq \bar{u}, &&\quad t \in [0,\,T),\\ &&&\underline{c} \leq Cx(t) + Du(t)\leq \bar{c}, &&\quad t \in [0,\,T), \\ &&& && \\[-1em] &&&\underline{h}^e \leq h^e(x(T), p) \leq \bar{h}^e, &&\\ &&&\underline{x}^e \leq \Pi_{x}^e x(T) \leq \bar{x}^{e}, &&\\ &&&\underline{c}^e \leq C^e x(T)\leq \bar{c}^e, &&\\ \end{aligned} \end{equation}\end{split}\]

Where:

  • \(l: \mathbb{R}^{n_x}\times\mathbb{R}^{n_u}\times\mathbb{R}^{n_z} \rightarrow \mathbb{R}\) is the Lagrange objective term.

  • \(m: \mathbb{R}^{n_x}\times\mathbb{R}^{n_z} \rightarrow \mathbb{R}\) is the Mayer objective term.

  • \(F: \mathbb{R}^{n_x}\times\mathbb{R}^{n_x}\times\mathbb{R}^{n_u}\times\mathbb{R}^{n_z}\times\mathbb{R}^{n_p} \rightarrow \mathbb{R}^{n_x+n_z}\) describes the (potentially) fully implicit dynamics.

  • \(h: \mathbb{R}^{n_x}\times\mathbb{R}^{n_u}\times\mathbb{R}^{n_z}\times\mathbb{R}^{n_p} \rightarrow \mathbb{R}^{n_h}\) and \(h^e: \mathbb{R}^{n_x}\times\mathbb{R}^{n_z}\times\mathbb{R}^{n_p} \rightarrow \mathbb{R}^{n_{h_e}}\) are general nonlinear functions.

  • \(C,\,D,\,C^e,\,\Pi_x,\,\Pi_u,\,\Pi_x^e\) are matrices of appropriate dimensions defining the polytopic and box constraints.

The acados_template interface makes some limiting assumptions on the problem formulation above, namely: * \(l\) must be in linear least-squares form \(l = \frac{1}{2}\| V_x x(t) + V_u u(t) + V_z z(t) - y_{\text{ref}}\|_W^2\) * \(m\) must be in linear least-squares form \(m = \frac{1}{2}\| V^e_x x(t) - y_{\text{ref}}^e\|_{W^e}^2\) * Constraints cannot depend on algebraic variables (yet)

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

(Notice that, of course, you might need to use pip instead, if you run, for example, from within a Python virtual environment) You should now be able to import it as a Python module and use it as shown in the examples in <acados_root>/examples/acados_template/python/<example_name>/generate_c_code.py.

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.20 -> 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. Additionally, you will have to make sure that the environment variable LD_LIBRARY_PATH contains the path to libacados.so (default path is <acados_root/lib>). Notice that, if you want to run the examples from a location that differs from ‘<acados_root>/interfaces/acados_template’ or 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 adapt ‘ocp.acados_include_path’ and ‘ocp.acados_lib_path’ accordingly in the generating Python code.

For more information contact @zanellia.

Python API

class acados_template.casadi_functions.acados_constraint
con_h_expr = None

CasADi expression for the constraint

con_phi_expr = None

CasADi expression for the constraint

con_r_expr = None

CasADi expression for the constraint

name = None

name associated with the function

nh = None

dimension of image of h

nphi = None

dimension of image of h

nr = None

dimension of image of nonlinear residuals

p = None

CasADi variable describing parameters in the constraints

r = None

CasADi variable describing the output of nonconvex part in convex-over nonconvex constraints

u = None

CasADi variable describing the input of the system

x = None

CasADi variable describing the state of the system

z = None

CasADi variable describing the algebraic variables

acados_template.casadi_functions.acados_constraint_strip_non_num(acados_constraint)
class acados_template.casadi_functions.acados_cost
expr = None

CasADi expression for the cost

name = None

name associated with the function

ny = None

number of residuals

p = None

CasADi variable describing parameters in the cost

u = None

CasADi variable describing the input of the system

x = None

CasADi variable describing the state of the system

acados_template.casadi_functions.acados_cost_strip_non_num(acados_cost)
class acados_template.casadi_functions.acados_dae
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

name associated with the function

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

acados_template.casadi_functions.acados_dae_strip_non_num(acados_constraint)
class acados_template.acados_ocp_nlp.acados_ocp_nlp

class containing the full description of the optimal control problem

class acados_template.acados_ocp_nlp.ocp_nlp_constraints

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_u\) - matrix coefficient for bounds on u

Jbx

\(J_x\) - matrix coefficient for bounds on x

Jbx_e

\(J_{x}^e\)Pi_x`)

Jsbu

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

Jsbx

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

Jsbx_e

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

Jsh

\(J_{s,h}\) - 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,h}\) - matrix coefficient for soft bounds on convex-over-nonlinear constraints

Jsphi_e

\(J_{s,h}^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 \(\Pi_u\))

idxbx

indexes of bounds on x (defines \(\Pi_x\))

idxbx_e

indexes for bounds on x at t=T (defines \(\Pi_x^e\))

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

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_e

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

lg

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

lg_e

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

lh

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

lh_e

\(\bar{h}^e\) - upper 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

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

p

\(p\) - parameters

ubu

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

ubx

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

ubx_e

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

ug

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

ug_e

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

uh

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

uh_e

\(\underline{h}^e\) - lower 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

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_nlp.ocp_nlp_cost

class containing the description of the cost (linear and nonlinear least-squares cost for the time being) \(l(x,u,z) = || V_x x + V_u u + V_z z - y_{\text{ref}}||^2_W\), \(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\) - Hessian wrt lower slack

Zl_e

\(y_{ ext{ref}}^e\) - reference for Mayer term

Zu

\(Z_u\) - Hessian wrt upper slack

Zu_e

\(Z_l^e\) - Hessian wrt lower 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_nlp.ocp_nlp_dims

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_e

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

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

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_nlp.ocp_nlp_solver_options

class containing the description of the solver options

hessian_approx

Hessian approximation

integrator_type

Integrator type

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

nlp_solver_tol_eq

NLP solver equality tolerance

nlp_solver_tol_ineq

NLP solver inequality

nlp_solver_tol_stat

NLP solver stationarity tolerance

nlp_solver_type

NLP solver

qp_solver

QP solver to be used in the NLP solver

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

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