simple_pendulum.controllers.ilqr

iLQR Model Predictive Control

Submodules

simple_pendulum.controllers.ilqr.iLQR_MPC_controller

iLQR MPC Controller

class simple_pendulum.controllers.ilqr.iLQR_MPC_controller.iLQRMPCController(mass=0.5, length=0.5, damping=0.15, coulomb_friction=0.0, gravity=9.81, inertia=0.125, torque_limit=2.0, dt=0.01, n=50, max_iter=1, break_cost_redu=1e-06, sCu=10.0, sCp=0.001, sCv=0.001, sCen=0.0, fCp=1000.0, fCv=10.0, fCen=300.0, dynamics='runge_kutta', n_x=3)

Bases: AbstractController

Controller which computes an ilqr solution at every timestep and uses the first control output.

compute_initial_guess(N=None, verbose=True)

compute initial guess

Parameters:
Nint, default=None

number of timesteps to plan ahead if N==None, N defaults to the number of timesteps that is also used during the online optimization (n in the class __init__)

verbosebool, default=True

whether to print when the initial guess calculation is finished

get_control_output(meas_pos, meas_vel, meas_tau=0, meas_time=0)

The function to compute the control input for the pendulum actuator

Parameters:
meas_posfloat

the position of the pendulum [rad]

meas_velfloat

the velocity of the pendulum [rad/s]

meas_taufloat, default=0

the meastured torque of the pendulum [Nm] (not used)

meas_timefloat, default=0

the collapsed time [s] (not used)

Returns:
des_posfloat

the desired position of the pendulum [rad] (not used, returns None)

des_velfloat

the desired velocity of the pendulum [rad/s] (not used, returns None)

des_taufloat

the torque supposed to be applied by the actuator [Nm]

init(x0)

Initialize the controller. May not be necessary.

Parameters:
``x0``: ``array like``

The start state of the pendulum

load_initial_guess(filepath='Pendulum_data/trajectory.csv', verbose=True)

load initial guess trajectory from file

Parameters:
filepathstring, default=”Pendulum_data/trajectory.csv”

path to the csv file containing the initial guess for the trajectory

verbosebool, default=True

whether to print from where the initial guess is loaded

set_goal(x)

Set a goal for the controller. Initializes the cost functions.

Parameters:
xarray-like

goal state for the pendulum

set_initial_guess(u_trj=None, x_trj=None)

set initial guess from array like object

Parameters:
u_trjarray-like, default=None

initial guess for control inputs u ignored if u_trj==None

x_trjarray-like, default=None

initial guess for state space trajectory ignored if x_trj==None

simple_pendulum.controllers.ilqr.unit_test

Unit Tests

class simple_pendulum.controllers.ilqr.unit_test.Test(methodName='runTest')

Bases: TestCase

epsilon = 0.2
test_0_iLQR_MPC_swingup_nx2()
test_1_iLQR_MPC_swingup_nx3()