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

acados MATLAB (rapid prototyping)

This interface makes a broad set of acados functionalities available from Matlab or Octave for prototyping purpose. As of now, this closely tracks the latest developments in the core of acados, e.g. exact Hessians, adjoint corrections, regularization, etc. However, for the time being, it will not be possible to generate a self-contained C library that can be deployed on an embedded system. For this purpose see the acados emebedded high-level interface below.

Some examples for the use of this interface can be found in <acados_root>/examples/matlab_mex

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

make acados_shared

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.

acados embedded - Python

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 librarythat 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 Jinja2.

The currently supported formulations 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.

Currently not yet implemented features:

  • \(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

pip install <acados_root>/interfaces/acados_template

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

For more information contact @zanellia

optimal control description

class acados_template.casadi_functions.acados_constraint
expr = None

CasADi expression for the constraint

name = None

name associated with the function

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 of the DAE

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

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

class containing the full description if the optimal control problem

class acados_template.acados_ocp_nlp.ocp_nlp_constraints

class containing the description of the constraints

__C = None

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

__C_e = None

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

__D = None

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

__idxbu = None

indexes of bounds on u (defines \(\Pi_u\))

__idxbx = None

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

__idxbx_e = None

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

__idxsbu = None

indexes of soft bounds on u

__idxsbx = None

indexes of soft bounds on x

__idxsbx_e = None

indexes of soft bounds on x at t=T

__idxsh = None

indexes of soft nonlinear constraints

__idxsh_e = None

indexes of soft nonlinear constraints at t=T

__lbu = None

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

__lbx = None

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

__lbx_e = None

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

__lg = None

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

__lg_e = None

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

__lh = None

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

__lh_e = None

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

__lsbu = None

soft lower bounds on u

__lsbx = None

soft lower bounds on x

__lsbx_e = None

soft lower bounds on x at t=T

__lsh = None

soft lower bounds for nonlinear constraints

__lsh_e = None

soft lower bounds for nonlinear constraints

__p = None

\(p\) - parameters

__ubu = None

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

__ubx = None

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

__ubx_e = None

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

__ug = None

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

__ug_e = None

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

__uh = None

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

__uh_e = None

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

__usbu = None

soft upper bounds on u

__usbx = None

soft upper bounds on x

__usbx_e = None

soft upper bounds on x at t=T

__ush = None

soft upper bounds for nonlinear constraints

__ush_e = None

soft upper bounds for nonlinear constraints

__x0 = None

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

class acados_template.acados_ocp_nlp.ocp_nlp_cost

class containing the description of the cost (linear 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 = None

\(V_u\) - u matrix coefficient

__Vx = None

\(V_x\) - x matrix coefficient

__Vx_e = None

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

__Vz = None

\(V_z\) - z matrix coefficient

__W = None

\(W\) - weight matrix

__W_e = None

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

__Zl = None

\(Z_l\) - Hessian wrt lower slack

__Zl_e = None

\(Z_l^e\) - Hessian wrt lower slack for Mayer term

__Zu = None

\(Z_u\) - Hessian wrt upper slack

__Zu_e = None

\(Z_u^e\) - Hessian wrt upper slack for Mayer term

__yref = None

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

__yref_e = None

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

__zl = None

\(z_l\) - gradient wrt lower slack

__zl_e = None

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

__zu = None

\(z_u\) - gradient wrt upper slack

__zu_e = None

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

\(N\) - prediction horizon

__nbu = None

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

__nbx = None

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

__nbx_e = None

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

__ng = None

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

__ng_e = None

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

__nh = None

\(n_h\) - number of nonlinear constraints

__nh_e = None

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

__np = None

\(n_p\) - number of parameters

__npd = None

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

__npd_e = None

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

__ns = None

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

__ns_e = None

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

__nsbu = None

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

__nsbx = None

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

__nsbx_e = None

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

__nsh = None

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

__nsh_e = None

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

__nu = None

\(n_u\) - number of inputs

__nx = None

\(n_x\) - number of states

__ny = None

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

__ny_e = None

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

__nz = None

\(n_z\) - number of algebraic variables

class acados_template.acados_ocp_nlp.ocp_nlp_solver_config

class containing the description of the solver configuration

__hessian_approx = None

hessian approximation

__integrator_type = None

integrator type

__nlp_solver_type = None

NLP solver

__qp_solver = None

qp solver to be used in the NLP solver

__tf = None

prediction horizon

acados embedded - MATLAB

TODO!