double_pendulum.controller.gravity_compensation

Submodules

double_pendulum.controller.gravity_compensation.PID_gravity_compensation_controller

class double_pendulum.controller.gravity_compensation.PID_gravity_compensation_controller.PIDGravityCompensationController(mass=[0.5, 0.6], length=[0.3, 0.2], com=[0.3, 0.2], damping=[0.1, 0.1], coulomb_fric=[0.0, 0.0], gravity=9.81, inertia=[None, None], torque_limit=[0.0, 1.0], model_pars=None, dt=0.01)

Bases: AbstractController

Controller to compensate the gravitational force and apply a PID controller on top.

Parameters:
massarray_like, optional

shape=(2,), dtype=float, default=[0.5, 0.6] 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.3, 0.2] center of mass lengths of the double pendulum links [r1, r2], units=[m]

dampingarray_like, optional

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

torque_limitarray_like, optional

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

dtfloat

timestep, unit=[s] (Default value=0.01)

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 controller. Initalizes Gravity compensation and PID controller.

save_(save_dir)

Save controller parameters

Parameters:
save_dirstring or path object

directory where the parameters will be saved

set_goal(x)

Set the desired state 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, Ki, Kd)

Set PID parameters.

Parameters:
Kpfloat

Gain proportional to position error

Kifloat

Gain proportional to integrated error

Kdfloat

Gain proportional to error derivative

double_pendulum.controller.gravity_compensation.gravity_compensation_controller

class double_pendulum.controller.gravity_compensation.gravity_compensation_controller.GravityCompensationController(mass=[0.5, 0.6], length=[0.3, 0.2], com=[0.3, 0.2], damping=[0.1, 0.1], coulomb_fric=[0.0, 0.0], gravity=9.81, inertia=[None, None], torque_limit=[0.0, 1.0], model_pars=None)

Bases: AbstractController

Controller to compensate the gravitational force.

Parameters:
massarray_like, optional

shape=(2,), dtype=float, default=[0.5, 0.6] 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.3, 0.2] center of mass lengths of the double pendulum links [r1, r2], units=[m]

dampingarray_like, optional

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

torque_limitarray_like, optional

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

get_control_output_(x, t=None)

The function to compute the control input for the double pendulum’s actuator(s) in order to compensate for the gravitational force.

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]

save_(save_dir)

Save controller parameters

Parameters:
save_dirstring or path object

directory where the parameters will be saved