Skip to main content

Rapid Optimal Control Kit

Project description

rockit

pipeline status coverage report html docs pdf docs

Description

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

Notably, the software allows free end-time problems and multi-stage optimal problems. The software is currently focused on direct methods and relieas eavily on CasADi . Rockit is maintained by the MECO research group at KU Leuven.

Installation

Install using pip: pip install rockit-meco

Hello world

(Taken from the example directory)

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 (free time problems can be configured with FreeTime(initial_guess)).

ocp = Ocp(T=10)

Define two scalar states (vectors and matrices also supported):

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

Define one control input:

u = ocp.control(order=0)

Specify ODE (DAEs also supported with ocp.algebraic and add_alg):

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

Lagrange objective:

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

Path constraints:

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

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

method = MultipleShooting(N=10, M=1, intg='rk')
#method = DirectCollocation(N=20)
ocp.method(method)

Solve:

sol = ocp.solve()

Show structure:

ocp.spy()

Post-processing. Sample states/control or expressions thereof on a specific grid:

tsa, x1a = sol.sample(x1, grid='control')
tsa, x2a = sol.sample(x2, grid='control')

tsb, x1b = sol.sample(x1, grid='integrator')
tsb, x2b = sol.sample(x2, grid='integrator')


from pylab import *

figure(figsize=(10, 4))
subplot(1, 2, 1)
plot(tsb, x1b, '.-')
plot(tsa, x1a, 'o')
xlabel("Times [s]", fontsize=14)
grid(True)
title('State x1')

subplot(1, 2, 2)
plot(tsb, x2b, '.-')
plot(tsa, x2a, 'o')
legend(['grid_integrator', 'grid_control'])
xlabel("Times [s]", fontsize=14)
title('State x2')
grid(True)

tsol, usol = sol.sample(u, grid='integrator',refine=100)

figure()
plot(tsol,usol)
title("Control signal")
xlabel("Times [s]")
grid(True)

tsc, x1c = sol.sample(x1, grid='integrator', refine=100)

figure(figsize=(15, 4))
plot(tsc, x1c, '-')
plot(tsa, x1a, 'o')
plot(tsb, x1b, '.')
xlabel("Times [s]")
grid(True)

Citing

If you find rockit useful in your research, pleasse cite the project URL https://gitlab.mech.kuleuven.be/meco-software/rockit. A proper publication is in the pipeline..

Project details


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.2.tar.gz (28.8 kB view hashes)

Uploaded Source

Supported by

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