double_pendulum.controller.energy

Submodules

double_pendulum.controller.energy.energy_Xin

class double_pendulum.controller.energy.energy_Xin.EnergyController(mass=[1.0, 1.0], length=[0.5, 0.5], com=[0.5, 0.5], damping=[0.1, 0.1], gravity=9.81, coulomb_fric=[0.0, 0.0], inertia=[None, None], motor_inertia=0.0, gear_ratio=6, torque_limit=[inf, inf], model_pars=None)

Bases: AbstractController

Energy-based controller for acrobot swingup based on this paper: https://onlinelibrary.wiley.com/doi/abs/10.1002/rnc.1184

Parameters:
massarray_like, optional

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

lengtharray_like, optional

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

comarray_like, optional

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

dampingarray_like, optional

shape=(2,), dtype=float, default=[0.5, 0.5] 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.0, 0.0] coulomb friction coefficients for the double pendulum actuators [cf1, cf2], units=[Nm]

inertiaarray_like, optional

shape=(2,), dtype=float, default=[None, None] 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

motor_inertiafloat, optional

default=0.0 inertia of the actuators/motors [Ir1, Ir2], units=[kg*m²]

gear_ratioint, optional

gear ratio of the motors, default=6

torque_limitarray_like, optional

shape=(2,), dtype=float, default=[np.inf, np.inf] 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 (Default value=None)

check_parameters()

Check if the parameters fulfill the convergence conditions presented in the paper.

get_control_output_(x, t=None)

The function to compute the control input for the double pendulum’s actuator(s).

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

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

tfloat, optional

time, unit=[s] (Default value=None)

Returns:
array_like

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

init_()

Initialize the controller.

save_(save_dir)

Save controller parameters

Parameters:
save_dirstring or path object

directory where the parameters will be saved

set_goal(x)

set_goal. Set goal for the controller.

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

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

set_parameters(kp=1.0, kd=1.0, kv=1.0)

set_parameters. Set controller gains.

Parameters:
kpfloat

gain for position error

kdfloat

gain

kvfloat

gain for velocity error

double_pendulum.controller.energy.energy_Xin.kd_func(q2, a1, a2, a3, b1, b2, Er)

Function to check the convergence property of kd.

Parameters:
q2float
a1float
a2float
a3float
b1float
b2float
Erfloat