double_pendulum.trajectory_optimization.ilqr

Submodules

double_pendulum.trajectory_optimization.ilqr.ilqr_cpp

class double_pendulum.trajectory_optimization.ilqr.ilqr_cpp.ilqr_calculator

Bases: object

Class to calculate a trajectory for the acrobot or pendubot with iterative LQR. Implementation uses the python bindings of the C++ implementation for iLQR.

Reference Paper for iLQR: https://www.scitepress.org/Link.aspx?doi=10.5220/0001143902220229

compute_trajectory()

Perform the trajectory optimization calculation and return the trajectory.

Returns:
numpy_array

time points, unit=[s] shape=(N,)

numpy_array

shape=(N, 4) states, units=[rad, rad, rad/s, rad/s] order=[angle1, angle2, velocity1, velocity2]

numpy_array

shape=(N, 2) actuations/motor torques order=[u1, u2], units=[Nm]

save_trajectory_csv()

Save the trajectory to a csv file. The csv file will be placed in the folder where the script is executed and will be called “trajectory.csv”.

set_cost_parameters(sCu=[0.005, 0.005], sCp=[0.0, 0.0], sCv=[0.0, 0.0], sCen=0.0, fCp=[1000.0, 1000.0], fCv=[10.0, 10.0], fCen=0.0)

Set cost parameters used for optimization.

Parameters:
sCulist

shape=(2,), dtype=float stage cost weights for control input (Default value = [0.005, 0.005])

sCplist

shape=(2,), dtype=float stage cost weights for position error (Default value = [0.,0.])

sCvlist

shape=(2,), dtype=float stage cost weights for velocity error (Default value = [0., 0.])

sCenfloat

stage cost weight for energy error (Default value = 0.)

fCplist

shape=(2,), dtype=float final cost weights for position error

(Default value = [1000., 1000.])

fCvlist

shape=(2,), dtype=float final cost weights for velocity error

(Default value = [10., 10.])

fCenfloat

final cost weight for energy error (Default value = 0.)

set_cost_parameters_(pars=[0.005, 0.0, 0.0, 0.0, 0.0, 1000.0, 1000.0, 10.0, 10.0])

Set cost parameters used for optimization in form of a list. (used for parameter optimization)

Parameters:
parslist

list order=[sCu1, sCp1, sCp2, sCv1, sCv2, fCp1, fCp2, fCv1, fCv2] energy costs are set to 0. (Default value = [0.005, 0., 0., 0., 0., 1000., 1000., 10., 10.])

set_goal(x)

set_goal. Set goal for the trajectory.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s] (Default value=[np.pi, 0., 0., 0.])

set_model_parameters(mass=[0.608, 0.63], length=[0.3, 0.2], com=[0.275, 0.166], damping=[0.081, 0.0], coulomb_fric=[0.093, 0.186], gravity=9.81, inertia=[0.05472, 0.02522], torque_limit=[0.0, 6.0], model_pars=None)

Set the model parameters of the robot.

Parameters:
massarray_like, optional

shape=(2,), dtype=float, default=[0.608, 0.630] masses of the double pendulum, [m1, m2], units=[kg]

lengtharray_like, optional

shape=(2,), dtype=float, default=[0.3, 0.2] link lengths of the double pendulum, [l1, l2], units=[m]

comarray_like, optional

shape=(2,), dtype=float, default=[0.275, 0.166] center of mass lengths of the double pendulum links [r1, r2], units=[m]

dampingarray_like, optional

shape=(2,), dtype=float, default=[0.081, 0.0] damping coefficients of the double pendulum actuators [b1, b2], units=[kg*m/s]

gravityfloat, optional

default=9.81 gravity acceleration (pointing downwards), units=[m/s²]

coulomb_fricarray_like, optional

shape=(2,), dtype=float, default=[0.093, 0.186] coulomb friction coefficients for the double pendulum actuators [cf1, cf2], units=[Nm]

inertiaarray_like, optional

shape=(2,), dtype=float, default=[0.05472, 0.02522] inertia of the double pendulum links [I1, I2], units=[kg*m²] if entry is None defaults to point mass m*l² inertia for the entry

torque_limitarray_like, optional

shape=(2,), dtype=float, default=[0.0, 6.0] torque limit of the motors [tl1, tl2], units=[Nm, Nm]

model_parsmodel_parameters object, optional

object of the model_parameters class, default=None Can be used to set all model parameters above If provided, the model_pars parameters overwrite the other provided parameters

set_parameters(N=1000, dt=0.005, max_iter=100, regu_init=100, max_regu=10000.0, min_regu=0.01, break_cost_redu=1e-06, integrator='runge_kutta')

set_parameters. Set parameters for the optimization

Parameters:
Nint

number of timesteps for horizon (Default value = 1000)

dtfloat

timestep for horizon (Default value = 0.005)

max_iterint

maximum of optimization iterations per step (Default value = 1)

regu_initfloat

inital regularization (Default value = 1.)

max_regufloat

maximum regularization (Default value = 10000.)

min_regufloat

minimum regularization (Default value = 0.01)

break_cost_redufloat
Stop the optimization at this cost reduction.

(Default value = 1e-6)

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

(Default value = “runge_kutta”)

set_start(x)

Set start state for the trajectory.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

double_pendulum.trajectory_optimization.ilqr.paropt

class double_pendulum.trajectory_optimization.ilqr.paropt.ilqr_trajopt_loss(bounds, loss_weights, start, goal, goal_weights=array([1., 1., 1., 1.]))

Bases: object

rescale_pars(pars)
set_model_parameters(mass=[0.608, 0.63], length=[0.3, 0.2], com=[0.275, 0.166], damping=[0.081, 0.0], coulomb_fric=[0.093, 0.186], gravity=9.81, inertia=[0.05472, 0.02522], torque_limit=[0.0, 6.0], model_pars=None)
set_parameters(N=1000, dt=0.005, max_iter=100, regu_init=100, max_regu=10000.0, min_regu=0.01, break_cost_redu=1e-06, integrator='runge_kutta')
unscale_pars(pars)