Skip to main content

Rapid Optimal Control Kit

Project description

rockit

pipeline status coverage report html docs pdf docs

Description

Rockit logo

Rockit (Rapid Optimal Control kit) is a software framework to quickly prototype optimal control problems (aka dynamic optimization) that may arise in engineering: e.g. iterative learning (ILC), model predictive control (NMPC), system identification, and motion planning.

Notably, the software allows free end-time problems and multi-stage optimal problems. The software is currently focused on direct methods and relies heavily on CasADi. The software is developed by the KU Leuven MECO research team.

Installation

Install using pip: pip install rockit-meco

Hello world

(Taken from the example gallery)

You may try it live in your browser: Binder.

Import the project:

from rockit import *

Start an optimal control environment with a time horizon of 10 seconds starting from t0=0s. (free-time problems can be configured with `FreeTime(initial_guess))

ocp = Ocp(t0=0, T=10)

Define two scalar states (vectors and matrices also supported)

x1 = ocp.state()
x2 = ocp.state()

Define one piecewise constant control input (use order=1 for piecewise linear)

u = ocp.control()

Compose time-dependent expressions a.k.a. signals (explicit time-dependence is supported with ocp.t)

e = 1 - x2**2

Specify differential equations for states (DAEs also supported with ocp.algebraic and add_alg)

ocp.set_der(x1, e * x1 - x2 + u)
ocp.set_der(x2, x1)

Lagrange objective term: signals in an integrand

ocp.add_objective(ocp.integral(x1**2 + x2**2 + u**2))

Mayer objective term: signals evaluated at t_f = t0_+T

ocp.add_objective(ocp.at_tf(x1**2))

Path constraints (must be valid on the whole time domain running from t0 to tf, grid options available such as grid='integrator' or grid='inf')

ocp.subject_to(x1 >= -0.25)
ocp.subject_to(-1 <= (u <= 1 ))

Boundary constraints

ocp.subject_to(ocp.at_t0(x1) == 0)
ocp.subject_to(ocp.at_t0(x2) == 1)

Pick an NLP solver backend (CasADi nlpsol plugin)

ocp.solver('ipopt')

Pick a solution method such as SingleShooting, MultipleShooting, DirectCollocation with arguments:

  • N -- number of control intervals
  • M -- number of integration steps per control interval
  • grid -- could specify e.g. UniformGrid() or GeometricGrid(4)
method = MultipleShooting(N=10, intg='rk')
ocp.method(method)

Solve:

sol = ocp.solve()

Show structure:

ocp.spy()

Structure of optimization problem

Post-processing:

tsa, x1a = sol.sample(x1, grid='control')
tsb, x1b = sol.sample(x1, grid='integrator')
tsc, x1c = sol.sample(x1, grid='integrator', refine=100)
plot(tsa, x1a, '-')
plot(tsb, x1b, 'o')
plot(tsc, x1c, '.')

Solution trajectory of states

Presentations

Project details


Release history Release notifications | RSS feed

Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

rockit-meco-0.1.10b5.tar.gz (73.1 kB view details)

Uploaded Source

File details

Details for the file rockit-meco-0.1.10b5.tar.gz.

File metadata

  • Download URL: rockit-meco-0.1.10b5.tar.gz
  • Upload date:
  • Size: 73.1 kB
  • Tags: Source
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/2.0.0 pkginfo/1.5.0.1 requests/2.22.0 setuptools/41.4.0 requests-toolbelt/0.9.1 tqdm/4.42.0 CPython/3.7.4

File hashes

Hashes for rockit-meco-0.1.10b5.tar.gz
Algorithm Hash digest
SHA256 350ea3e21a0786e7d329b983eed668f50221083b047c1acf4c4f8b8606cc9045
MD5 b885a9013ffc8eb505f1595cae866f31
BLAKE2b-256 35c730382ba4d5dadb90154ac0249b53e1d01306e9f17aab83da0cb297c98617

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page