simple_pendulum.trajectory_optimization.ilqr
iLQR
Submodules
simple_pendulum.trajectory_optimization.ilqr.ilqr
iLQR Calculator
Large parts taken from Russ Tedrake.
- class simple_pendulum.trajectory_optimization.ilqr.ilqr.iLQR_Calculator(n_x=2, n_u=1)
Bases:
object
Class to calculate an optimal trajectory with an iterative linear quadratic regulator (iLQR). This implementation uses the pydrake symbolic library.
- init_derivatives()
Initialize the derivatives of the dynamics.
- run_ilqr(N=50, init_u_trj=None, init_x_trj=None, shift=False, max_iter=50, break_cost_redu=1e-06, regu_init=100)
Run the iLQR optimization and receive a optimal trajectory for the defined cost function.
- Parameters:
- Nint, default=50
The number of waypoints for the trajectory
- init_u_trjarray-like, default=None
initial guess for the control trajectory ignored if None
- init_x_trjarray_like, default=None
initial guess for the state space trajectory ignored if None
- shiftbool, default=False
whether to shift the initial guess trajectories by one entry (delete the first entry and duplicate the last entry)
- max_iterint, default=50
optimization iterations the alogrithm makes at every timestep
- break_cost_redufloat, default=1e-6
cost at which the optimization breaks off early
- regu_initfloat, default=100
initialization value for the regularizer
- Returns:
- x_trjarray-like
state space trajectory
- u_trjarray-like
control trajectory
- cost_tracearray-like
trace of the cost development during the optimization
- regu_tracearray-like
trace of the regularizer development during the optimization
- redu_ratio_tracearray-like
- trace of ratio of cost_reduction and expected cost reduction
during the optimization
- redu_tracearray-like
trace of the cost reduction development during the optimization
- set_discrete_dynamics(dynamics_func)
Sets the dynamics function for the iLQR calculation.
- Parameters:
- danamics_funcfunction
dynamics_func should be a function with inputs (x, u) and output xd
- set_final_cost(final_cost_func)
Set the final cost for the ilqr optimization.
- Parameters:
- final_cost_funcfunction
final_cost_func should be a function with inputs x and output cost
- set_stage_cost(stage_cost_func)
Set the stage cost (running cost) for the ilqr optimization.
- Parameters:
- stage_cost_funcfunction
stage_cost_func should be a function with inputs (x, u) and output cost
- set_start(x0)
Set the start state for the trajectory.
- Parameters:
- x0array-like
the start state. Should have the shape of (n_x,)
simple_pendulum.trajectory_optimization.ilqr.ilqr_sympy
Symbolic
Large parts taken from Russ Tedrake.
- class simple_pendulum.trajectory_optimization.ilqr.ilqr_sympy.iLQR_Calculator(n_x=2, n_u=1)
Bases:
object
Class to calculate an optimal trajectory with an iterative linear quadratic regulator (iLQR). This implementation uses sympy.
- Q_terms(l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u, V_x, V_xx)
- V_terms(Q_x, Q_u, Q_xx, Q_ux, Q_uu, K, k)
- backward_pass(x_trj, u_trj, regu)
- compute_final_cost_derivatives(x)
- compute_stage_cost_derivatives(x, u)
- cost_trj(x_trj, u_trj)
- expected_cost_reduction(Q_u, Q_uu, k)
- forward_pass(x_trj, u_trj, k_trj, K_trj)
- gains(Q_uu, Q_u, Q_ux)
- init_derivatives()
Initialize the derivatives of the dynamics.
- rollout(u_trj)
- run_ilqr(N=50, init_u_trj=None, init_x_trj=None, shift=False, max_iter=50, break_cost_redu=1e-06, regu_init=100)
Run the iLQR optimization and receive a optimal trajectory for the defined cost function.
- Parameters:
- Nint, default=50
The number of waypoints for the trajectory
- init_u_trjarray-like, default=None
initial guess for the control trajectory ignored if None
- init_x_trjarray_like, default=None
initial guess for the state space trajectory ignored if None
- shiftbool, default=False
whether to shift the initial guess trajectories by one entry (delete the first entry and duplicate the last entry)
- max_iterint, default=50
optimization iterations the alogrithm makes at every timestep
- break_cost_redufloat, default=1e-6
cost at which the optimization breaks off early
- regu_initfloat, default=100
initialization value for the regularizer
- Returns:
- x_trjarray-like
state space trajectory
- u_trjarray-like
control trajectory
- cost_tracearray-like
trace of the cost development during the optimization
- regu_tracearray-like
trace of the regularizer development during the optimization
- redu_ratio_tracearray-like
- trace of ratio of cost_reduction and expected cost reduction
during the optimization
- redu_tracearray-like
trace of the cost reduction development during the optimization
- set_discrete_dynamics(dynamics_func)
Sets the dynamics function for the iLQR calculation.
- Parameters:
- danamics_funcfunction
dynamics_func should be a function with inputs (x, u) and output xd
- set_final_cost(final_cost_func)
Set the final cost for the ilqr optimization.
- Parameters:
- final_cost_funcfunction
final_cost_func should be a function with inputs x and output cost
- set_stage_cost(stage_cost_func)
Set the stage cost (running cost) for the ilqr optimization.
- Parameters:
- stage_cost_funcfunction
stage_cost_func should be a function with inputs (x, u) and output cost
- set_start(x0)
Set the start state for the trajectory.
- Parameters:
- x0array-like
the start state. Should have the shape of (n_x,)
simple_pendulum.trajectory_optimization.ilqr.pendulum
Pendulum Dynamics
- simple_pendulum.trajectory_optimization.ilqr.pendulum.check_type(x)
checks the type of x and returns the suitable library (pydrake.symbolic, sympy or numpy) for furhter calculations on x.
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum3_discrete_dynamics_euler(x, u, dt, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81, inertia=0.125)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum3_discrete_dynamics_rungekutta(x, u, dt, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81, inertia=0.125)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum3_swingup_final_cost(x, goal=[-1, 0, 0], Cp=1000.0, Cv=10.0, Cen=0.0, m=0.57288, l=0.5, b=0.15, cf=0.0, g=9.81)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum3_swingup_stage_cost(x, u, goal=[-1, 0, 0], Cu=10.0, Cp=0.01, Cv=0.01, Cen=0.0, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum_continuous_dynamics(x, u, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81, inertia=0.125)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum_discrete_dynamics_euler(x, u, dt, m=0.57288, l=0.5, b=0.15, cf=0.0, g=9.81, inertia=0.125)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum_discrete_dynamics_rungekutta(x, u, dt, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81, inertia=0.125)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum_swingup_final_cost(x, goal=[3.141592653589793, 0], Cp=1000.0, Cv=10.0, Cen=0.0, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81)
- simple_pendulum.trajectory_optimization.ilqr.pendulum.pendulum_swingup_stage_cost(x, u, goal=[3.141592653589793, 0], Cu=10.0, Cp=0.01, Cv=0.01, Cen=0.0, m=0.5, l=0.5, b=0.15, cf=0.0, g=9.81)