double_pendulum.model

Submodules

double_pendulum.model.friction_matrix

double_pendulum.model.friction_matrix.yb_friction_matrix(dq_vec)

matrix to be multiplied with damping/friction coefficients resulting in equation of motion contribution

Parameters:
dq_vecarray-like

shape=(2,), velocities of the double pendulum, order=[dq1, dq2], units=[m/s],

Returns:
numpy array

shape=(2,4) friction matrix

double_pendulum.model.model_parameters

class double_pendulum.model.model_parameters.model_parameters(mass=[0.608, 0.63], length=[0.3, 0.4], com=[0.275, 0.415], damping=[0.005, 0.005], cfric=[0.093, 0.14], gravity=9.81, inertia=[0.0475, 0.0798], motor_inertia=0.0, gear_ratio=6, torque_limit=[10.0, 10.0], dof=2, filepath=None, model_design=None, model_id=None, robot='double_pendulum')

Bases: object

Double pendulum plant parameters

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.4] link lengths of the double pendulum, [l1, l2], units=[m]

comarray_like, optional

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

dampingarray_like, optional

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

cfricarray_like, optional

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

inertiaarray_like, optional

shape=(2,), dtype=float, default=[0.0475, 0.0798] 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=[10.0, 10.0] torque limit of the motors [tl1, tl2], units=[Nm, Nm]

dofint, optional

degrees of freedom of the double pendulum, default=2 does not make sense to change

filepathstring or path object, optional

path to yaml file containing the the above parameters, if provided, the parameters from the yaml file will overwrite the other specified parameters default = None

model_designstring, optional

string description of the design to set the parameters for that specific design. model_design and model_id have to be set together. Options:

  • “A.0”

  • “B.0”

  • “C.0”

  • “hD.0”

default=None

model_idstring, optional

string description of the model parameters for a design. Parameters for the specific model of the design will be loaded. model_design and model_id have to be set together. Options:

  • “1.0”

  • “1.1”

  • “2.0”

default=None

robotstring, optional

string describing the robot. Used to set the torque_limit when using model_design and model_id. Options:

  • “double_pendulum”

  • “acrobot”

  • “pendubot”

default=”double_pendulum”

get_dict()

get dictionary with all parameters

load_dict(mpar_dict)

load parameters from a dictionary

Parameters:
mpar_dictdict

dictionary containing the parameters keys which are looked for are:

  • m1, m2

  • l1, l2

  • r1, r2

  • b1, b2

  • cf1, cf2

  • g

  • I1, I2

  • Ir

  • gr

  • tl1, tl2

load_model(model_design, model_id, robot)
load_yaml(file_path)

load parameters from a yaml file

Parameters:
file_pathstring or path object

path to yaml file containing the the above parameters, if provided, the parameters from the yaml file will overwrite the other specified parameters

save_dict(save_path)

save all parameters in a yaml file keys used are:

  • m1, m2

  • l1, l2

  • r1, r2

  • b1, b2

  • cf1, cf2

  • g

  • I1, I2

  • Ir

  • gr

  • tl1, tl2

Parameters:
save_pathstring or path object

path where the yaml file will be stored

set_cfric(cfric)

setter function for coulomb friction

Parameters:
cfricarray_like, optional

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

set_com(com)

setter function for com

Parameters:
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]

set_damping(damping)

setter function for damping

Parameters:
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]

set_dof(dof)

setter function for degrees of freedom

Parameters:
dofint, optional

degrees of freedom of the double pendulum, default=2 does not make sense to change

set_gear_ratio(gear_ratio)

setter function for gear ratio

Parameters:
gear_ratioint, optional

gear ratio of the motors, default=6

set_gravity(gravity)

setter function for gravity

Parameters:
gravityfloat, optional

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

set_inertia(inertia)

setter function for inertia

Parameters:
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

set_length(length)

setter function for length

Parameters:
lengtharray_like, optional

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

set_mass(mass)

setter function for mass

Parameters:
massarray_like, optional

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

set_motor_inertia(motor_inertia)

setter function for motor inertia

Parameters:
motor_inertiafloat, optional

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

set_torque_limit(torque_limit)

setter function for torque limit

Parameters:
torque_limitarray_like, optional

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

double_pendulum.model.plant

class double_pendulum.model.plant.DoublePendulumPlant(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: object

Double pendulum plant The double pendulum plant class calculates:

  • forward kinematics

  • forward dynamics

  • dynamics matrices (mass, coriolis, gravity, friction)

  • state dynamics matrices (mass, coriolis, gravity, friction)

  • linearized dynamics

  • kinetic, potential, total energy

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

coriolis_matrix(x)

coriolis matrix from the equations of motion

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

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

Returns:
numpy array, shape=(2,2),

coriolis matrix

coulomb_vector(x)

coulomb vector from the equations of motion

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

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

Returns:
numpy array, shape=(2,),

coulomb vector

forward_dynamics(x, tau)

forward dynamics of the double pendulum

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
numpy array, shape=(2,)

joint acceleration, [acc1, acc2], units=[m/s²]

forward_kinematics(pos)

forward kinematics, origin at fixed point

Parameters:
posarray_like, shape=(2,), dtype=float,

positions of the double pendulum, order=[angle1, angle2], units=[rad]

Returns:
list of 2 lists=[[x1, y1], [x2, y2]]

cartesian coordinates of the link end points units=[m]

get_Alin(x, u)

A-matrix of the linearized dynamics (xd = Ax+Bu)

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

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

uarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
array_like

shape=(4,4), A-matrix

get_Blin(x, u)

B-matrix of the linearized dynamics (xd = Ax+Bu)

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

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

uarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
array_like

shape=(4,2), B-matrix

get_Cx(x, tau)

state derivative of coriolis matrix

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm] not used

Returns:
numpy array

shape=(4, 2, 2) derivative of coriolis matrix, Cx[i]=del(C)/del(x_i)

get_Fx(x, tau)

state derivative of coulomb vector

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm] not used

Returns:
numpy array

shape=(2, 4) derivative of coulomb vector, Fx[:, i]=del(F)/del(x_i)

get_Gx(x, tau)

state derivative of gravity vector

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm] not used

Returns:
numpy array

shape=(2, 4) derivative of gravity vector, Gx[:, i]=del(G)/del(x_i)

get_Minvx(x, tau)

state derivative of inverse mass matrix

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm] not used

Returns:
numpy array

shape=(4, 2, 2) derivative of inverse mass matrix, Minvx[i]=del(Minv)/del(x_i)

get_Mx(x, tau)

state derivative of mass matrix

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

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm] not used

Returns:
numpy array

shape=(4, 2, 2) derivative of mass matrix, Mx[i]=del(M)/del(x_i)

gravity_vector(x)

gravity vector from the equations of motion

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

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

Returns:
numpy array, shape=(2,),

gravity vector

kinetic_energy(x)

kinetic energy of the double pendulum

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

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

Returns:
float

kinetic energy, units=[J]

linear_matrices(x0, u0)

get A- and B-matrix of the linearized dynamics (xd = Ax+Bu)

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

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

u0array_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
array_like

shape=(4,4), A-matrix

array_like

shape=(4,2), B-matrix

mass_matrix(x)

mass matrix from the equations of motion

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

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

Returns:
numpy array, shape=(2,2),

mass matrix

potential_energy(x)

potential energy of the double pendulum

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

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

Returns:
float

potential energy, units=[J]

rhs(t, state, tau)

integrand of the equations of motion

Parameters:
tfloat,

time, units=[s], not used

statearray_like, shape=(4,), dtype=float,

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

tauarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
numpy array

shape=(4,), dtype=float integrand, [vel1, vel2, acc1, acc2]

total_energy(x)

total energy of the double pendulum

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

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

Returns:
float

total energy, units=[J]

double_pendulum.model.symbolic_plant

class double_pendulum.model.symbolic_plant.SymbolicDoublePendulum(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: object

Symbolic double pendulum plant The double pendulum plant class calculates:

  • forward kinematics

  • forward/inverse dynamics

  • dynamics matrices (mass, coriolis, gravity, friction)

  • state dynamics matrices (mass, coriolis, gravity, friction)

  • linearized dynamics

  • kinetic, potential, total energy

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

I1 = I1
I2 = I2
Ir_sym = Ir
angular_momentum_base(x)

angular momentum at the base

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

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

Returns:
float

angular momentum, unit=[kg*m²/s]

angular_momentum_ddot_base(x)

second time derivative of the angular momentum at the base

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

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

Returns:
float

second time derivative of the angular momentum, unit=[kg*m²/s³]

angular_momentum_dot_base(x)

first time derivative of the angular momentum at the base

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

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

Returns:
float

first time derivative of the angular momentum, unit=[kg*m²/s²]

b1 = b1
b2 = b2
base = [0, 0]
center_of_mass(pos)

calculate the center of mass of the whole system

Parameters:
posarray_like, shape=(2,), dtype=float,

positions of the double pendulum, order=[angle1, angle2], units=[rad]

Returns:
list

shape=(2,) cartesian coordinates of the center of mass, units=[m]

cf1 = cf1
cf2 = cf2
com_dot(x)

calculate the time derivative of the center of mass of the whole system

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

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

Returns:
list

shape=(2,) center of mass time derivative, units=[m/s]

coriolis_matrix(x)

coriolis matrix from the equations of motion

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

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

Returns:
numpy array, shape=(2,2),

coriolis matrix

coulomb_vector(x)

coulomb vector from the equations of motion

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

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

Returns:
numpy array, shape=(1,2),

coulomb vector

dof = 2
equation_of_motion(order='2nd')

symbolic equation of motion

Parameters:
orderstring

string specifying the order of the eom (“1st” or “2nd”) default=”2nd”

Returns:
sympy matrix
if order==”1st”

returns f from f=[qd, qdd] in the eom

if order==”2nd”

returns f from f=qdd in the eom

forward_dynamics(x, u)

forward dynamics of the double pendulum

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

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

uarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
numpy array, shape=(2,)

joint acceleration, [acc1, acc2], units=[m/s²]

forward_kinematics(pos)

forward kinematics, origin at fixed point

Parameters:
posarray_like, shape=(2,), dtype=float,

positions of the double pendulum, order=[angle1, angle2], units=[rad]

Returns:
list of 2 lists=[[x1, y1], [x2, y2]]

cartesian coordinates of the link end points units=[m]

g_sym = g
gr_sym = gr
gravity_vector(x)

gravity vector from the equations of motion

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

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

Returns:
numpy array, shape=(1,2),

gravity vector

inverse_dynamics(x, acc)

inverse dynamics of the double pendulum

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

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

accarray_like, shape=(2,), dtype=float

joint acceleration, order=[acc1, acc2], units=[rad/s²]

Returns:
array_like

shape=(2,) actuation input/motor torque units=[Nm]

kinetic_energy(x)

kinetic energy of the double pendulum

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

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

Returns:
float

kinetic energy, units=[J]

l1 = l1
l2 = l2
lambdify_matrices()

function to lambdify the symbolic matrices of this plant to make them functions of state x and actuation u

linear_matrices(x0, u0)

get A- and B-matrix of the linearized dynamics (xd = Ax+Bu)

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

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

u0array_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
array_like

shape=(4,4), A-matrix

array_like

shape=(4,2), B-matrix

linear_matrices_discrete(x0, u0, dt)

get discrete A- and B-matrix of the linearized dynamics (xd = Ax+Bu)

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

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

u0array_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
array_like

shape=(4,4), A-matrix

array_like

shape=(4,2), B-matrix

m1 = m1
m2 = m2
mass_matrix(x)

mass matrix from the equations of motion

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

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

Returns:
numpy array, shape=(2,2),

mass matrix

n_actuators = 2
potential_energy(x)

potential energy of the double pendulum

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

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

Returns:
float

potential energy, units=[J]

q = Matrix([ [q1], [q2]])
q01 = \hat{q}_1
q02 = \hat{q}_2
q0d1 = \hat{\dot{q}}_1
q0d2 = \hat{\dot{q}}_2
q1 = q1
q2 = q2
qd = Matrix([ [\dot{q}_1], [\dot{q}_2]])
qd1 = \dot{q}_1
qd2 = \dot{q}_2
qdd = Matrix([ [\ddot{q}_1], [\ddot{q}_2]])
qdd1 = \ddot{q}_1
qdd2 = \ddot{q}_2
r1 = r1
r2 = r2
replace_parameters(mat)

function to replace the symbolic system parameters in the input matrix with the actual values of this plant

Parameters:
matsympy matrix

matrix, where the symbolic parameters shall be replaced

Returns:
sympy matrix

matrix with replaced parameters

rhs(t, x, u)

integrand of the equations of motion

Parameters:
tfloat,

time, units=[s], not used

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

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

uarray_like, shape=(2,), dtype=float

actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
numpy array

shape=(4,), dtype=float integrand, [vel1, vel2, acc1, acc2]

symbolic_coriolis_matrix()

symbolic coriolis matrix from the equations of motion

Returns:
sympy Matrix

shape=(2,2) coriolis matrix

symbolic_coulomb_vector()

symbolic coulomb vector from the equations of motion

Returns:
sympy Matrix

shape=(1,2) coulomb vector

symbolic_gravity_vector()

symbolic gravity vector from the equations of motion

Returns:
sympy Matrix

shape=(1,2) gravity vector

symbolic_kinetic_energy()

symbolic kinetic energy of the double pendulum

symbolic_linear_matrices()

symbolic A- and B-matrix of the linearized dynamics (xd = Ax+Bu)

symbolic_mass_matrix()

symbolic mass matrix from the equations of motion

Returns:
sympy Matrix

shape=(2,2) mass matrix

symbolic_potential_energy()

symbolic potential energy of the double pendulum

symbolic_total_energy()

symbolic total energy of the double pendulum

tl1 = tl1
tl2 = tl2
total_energy(x)

total energy of the double pendulum

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

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

Returns:
float

total energy, units=[J]

u = Matrix([ [u1], [u2]])
u0 = Matrix([ [\hat{u}_1], [\hat{u}_2]])
u01 = \hat{u}_1
u02 = \hat{u}_2
u1 = u1
u2 = u2
x = Matrix([ [       q1], [       q2], [\dot{q}_1], [\dot{q}_2]])
x0 = Matrix([ [      \hat{q}_1], [      \hat{q}_2], [\hat{\dot{q}}_1], [\hat{\dot{q}}_2]])
xd = Matrix([ [ \dot{q}_1], [ \dot{q}_2], [\ddot{q}_1], [\ddot{q}_2]])
double_pendulum.model.symbolic_plant.diff_to_matrix(diff)

function to convert a sympy derivative to a sympy matrix

Parameters:
diffsympy derivative
Returns:
sympy matrix
double_pendulum.model.symbolic_plant.sub_symbols(mat, symbols, new_symbols)

substitute symbols with new symbols/values in mat

Parameters:
matsympy matrix

matrix where symbols shall be replaced

symbolslist of sympy variables

symbols to replace

new_symbolslist of sympy variables or floats

will replace the symbols

Returns:
sympy matrix

matrix with replaced symbols

double_pendulum.model.symbolic_plant.vector_mult(vec1, vec2)

scalar product of sympy vectors

Parameters:
vec1sympy vector
vec2sympy vector
Returns:
sympy variable

vec1*vec2