double_pendulum.controller.partial_feedback_linearization

Submodules

double_pendulum.controller.partial_feedback_linearization.pfl

class double_pendulum.controller.partial_feedback_linearization.pfl.EnergyShapingPFLAndLQRController(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], torque_limit=[inf, inf])

Bases: AbstractController

Controller based on partial feedback linearization which controls the nergy of the double pendulum. If the LQR controller returns a feasible value the control switches to LQR control.

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

torque_limitarray_like, optional

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

get_control_output_(x, t=None, verbose=False)

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)

verbosebool

Whether to print when the active controller is switched. (Default value = False)

Returns:
array_like

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

init_()

Initialize the PFL and LQR controller.

set_cost_parameters_(pars=[0.3, 0.005, 1.0])

Set controller gains for the PFL controller with a list.

Parameters:
parslist

shape=(3,) list containing the controller gains in the order [kpos, kvel, ken] (Default value = [0.3, 0.005, 1.0])

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]

class double_pendulum.controller.partial_feedback_linearization.pfl.EnergyShapingPFLController(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], torque_limit=[inf, inf])

Bases: AbstractController

Controller based on partial feedback linearization (PFL) which controls the nergy of the double pendulum. Uses collocated pfl for the acrobot. For non-collocated pfl and/or the pendubot use the SymbolicPFLController. It is based in these papers by Spong:

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

torque_limitarray_like, optional

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

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]

save_(save_dir)

Save controller parameters

Parameters:
save_dirstring or path object

directory where the parameters will be saved

set_cost_parameters(kpos=0.3, kvel=0.005, ken=1.0)

Set controller gains

Parameters:
kposfloat

Gain for position error (Default value = 0.3)

kvelfloat

Gain for velocity error (Default value = 0.005)

kenfloat

Gain for energy error (Default value = 1.0)

set_cost_parameters_(pars=[0.3, 0.005, 1.0])

Set controller gains with a list. (Useful for parameter optimization)

Parameters:
parslist

shape=(3,) list containing the controller gains in the order [kpos, kvel, ken] (Default value = [0.3, 0.005, 1.0])

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]

double_pendulum.controller.partial_feedback_linearization.symbolic_pfl

class double_pendulum.controller.partial_feedback_linearization.symbolic_pfl.SymbolicPFLAndLQRController(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], torque_limit=[inf, inf], model_pars=None, robot='acrobot', pfl_method='collocated', reference='energy')

Bases: AbstractController

Controller based on partial feedback linearization (PFL) which controls the nergy of the double pendulum. Can be used for collocated and non-collocated pfl and for acrobot and pendubot. If the LQR controller returns a feasible value the control switches to LQR control.

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

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

robotstring
the system to be used
  • “acrobot”

  • “pendubot”

(Default value=”acrobot”)

pfl_methodstring
the PFL method to be used
  • “collocated”

  • “noncollocated”

(Default value=”collocated”)

referencestring
the property to be controlled
  • “energy”

  • “energysat”

  • “q1sat”

  • “q1”

(Default value=”energy”)

get_control_output_(x, t=None, verbose=False)

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)

verbosebool

Whether to print when the active controller is switched. (Default value = False)

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_cost_parameters_(pars=[0.3, 0.005, 1.0])

Set PFL controller gains with a list. (Useful for parameter optimization)

Parameters:
parslist

shape=(3,) list containing the controller gains in the order [kpos, kvel, ken] (Default value = [0.3, 0.005, 1.0])

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]

class double_pendulum.controller.partial_feedback_linearization.symbolic_pfl.SymbolicPFLController(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], torque_limit=[inf, inf], model_pars=None, robot='acrobot', pfl_method='collocated', reference='energy')

Bases: AbstractController

Controller based on partial feedback linearization (PFL) which controls the nergy of the double pendulum. Can be used for collocated and non-collocated pfl and for acrobot and pendubot. It is based in these papers by Spong:

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

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

robotstring
the system to be used
  • “acrobot”

  • “pendubot”

(Default value=”acrobot”)

pfl_methodstring
the PFL method to be used
  • “collocated”

  • “noncollocated”

(Default value=”collocated”)

referencestring
the property to be controlled
  • “energy”

  • “energysat”

  • “q1sat”

  • “q1”

(Default value=”energy”)

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_cost_parameters(kpos=0.3, kvel=0.005, ken=1.0)

Set controller gains

Parameters:
kposfloat

Gain for position error (Default value = 0.3)

kvelfloat

Gain for velocity error (Default value = 0.005)

kenfloat

Gain for energy error (Default value = 1.0)

set_cost_parameters_(pars=[0.3, 0.005, 1.0])

Set controller gains with a list. (Useful for parameter optimization)

Parameters:
parslist

shape=(3,) list containing the controller gains in the order [kpos, kvel, ken] (Default value = [0.3, 0.005, 1.0])

set_goal(x=[3.141592653589793, 0.0, 0.0, 0.0])

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] (Default value=[np.pi, 0., 0., 0.])