double_pendulum.simulation

Submodules

double_pendulum.simulation.gym_env

class double_pendulum.simulation.gym_env.CustomEnv(dynamics_func, reward_func, terminated_func, reset_func, obs_space=Box(-1.0, 1.0, (4,), float32), act_space=Box(-1.0, 1.0, (2,), float32), max_episode_steps=1000, scaling=True)

Bases: Env

action_space: spaces.Space[ActType]
observation_space: spaces.Space[ObsType]
render(mode='human')

Compute the render frames as specified by render_mode during the initialization of the environment.

The environment’s metadata render modes (env.metadata[“render_modes”]) should contain the possible ways to implement the render modes. In addition, list versions for most render modes is achieved through gymnasium.make which automatically applies a wrapper to collect rendered frames.

Note

As the render_mode is known during __init__, the objects used to render the environment state should be initialised in __init__.

By convention, if the render_mode is:

  • None (default): no render is computed.

  • “human”: The environment is continuously rendered in the current display or terminal, usually for human consumption. This rendering should occur during step() and render() doesn’t need to be called. Returns None.

  • “rgb_array”: Return a single frame representing the current state of the environment. A frame is a np.ndarray with shape (x, y, 3) representing RGB values for an x-by-y pixel image.

  • “ansi”: Return a strings (str) or StringIO.StringIO containing a terminal-style text representation for each time step. The text can include newlines and ANSI escape sequences (e.g. for colors).

  • “rgb_array_list” and “ansi_list”: List based version of render modes are possible (except Human) through the wrapper, gymnasium.wrappers.RenderCollection that is automatically applied during gymnasium.make(..., render_mode="rgb_array_list"). The frames collected are popped after render() is called or reset().

Note

Make sure that your class’s metadata "render_modes" key includes the list of supported modes.

Changed in version 0.25.0: The render function was changed to no longer accept parameters, rather these parameters should be specified in the environment initialised, i.e., gymnasium.make("CartPole-v1", render_mode="human")

reset(seed=None, options=None)

Resets the environment to an initial internal state, returning an initial observation and info.

This method generates a new starting state often with some randomness to ensure that the agent explores the state space and learns a generalised policy about the environment. This randomness can be controlled with the seed parameter otherwise if the environment already has a random number generator and reset() is called with seed=None, the RNG is not reset.

Therefore, reset() should (in the typical use case) be called with a seed right after initialization and then never again.

For Custom environments, the first line of reset() should be super().reset(seed=seed) which implements the seeding correctly.

Changed in version v0.25: The return_info parameter was removed and now info is expected to be returned.

Parameters:
  • seed (optional int) – The seed that is used to initialize the environment’s PRNG (np_random). If the environment does not already have a PRNG and seed=None (the default option) is passed, a seed will be chosen from some source of entropy (e.g. timestamp or /dev/urandom). However, if the environment already has a PRNG and seed=None is passed, the PRNG will not be reset. If you pass an integer, the PRNG will be reset even if it already exists. Usually, you want to pass an integer right after the environment has been initialized and then never again. Please refer to the minimal example above to see this paradigm in action.

  • options (optional dict) – Additional information to specify how the environment is reset (optional, depending on the specific environment)

Returns:

Observation of the initial state. This will be an element of observation_space

(typically a numpy array) and is analogous to the observation returned by step().

info (dictionary): This dictionary contains auxiliary information complementing observation. It should be analogous to

the info returned by step().

Return type:

observation (ObsType)

step(action)

Run one timestep of the environment’s dynamics using the agent actions.

When the end of an episode is reached (terminated or truncated), it is necessary to call reset() to reset this environment’s state for the next episode.

Changed in version 0.26: The Step API was changed removing done in favor of terminated and truncated to make it clearer to users when the environment had terminated or truncated which is critical for reinforcement learning bootstrapping algorithms.

Parameters:

action (ActType) – an action provided by the agent to update the environment state.

Returns:

An element of the environment’s observation_space as the next observation due to the agent actions.

An example is a numpy array containing the positions and velocities of the pole in CartPole.

reward (SupportsFloat): The reward as a result of taking the action. terminated (bool): Whether the agent reaches the terminal state (as defined under the MDP of the task)

which can be positive or negative. An example is reaching the goal state or moving into the lava from the Sutton and Barton, Gridworld. If true, the user needs to call reset().

truncated (bool): Whether the truncation condition outside the scope of the MDP is satisfied.

Typically, this is a timelimit, but could also be used to indicate an agent physically going out of bounds. Can be used to end the episode prematurely before a terminal state is reached. If true, the user needs to call reset().

info (dict): Contains auxiliary diagnostic information (helpful for debugging, learning, and logging).

This might, for instance, contain: metrics that describe the agent’s performance state, variables that are hidden from observations, or individual reward terms that are combined to produce the total reward. In OpenAI Gym <v26, it contains “TimeLimit.truncated” to distinguish truncation and termination, however this is deprecated in favour of returning terminated and truncated variables.

done (bool): (Deprecated) A boolean value for if the episode has ended, in which case further step() calls will

return undefined results. This was removed in OpenAI Gym v26 in favor of terminated and truncated attributes. A done signal may be emitted for different reasons: Maybe the task underlying the environment was solved successfully, a certain timelimit was exceeded, or the physics simulation has entered an invalid state.

Return type:

observation (ObsType)

class double_pendulum.simulation.gym_env.double_pendulum_dynamics_func(simulator, dt=0.01, integrator='runge_kutta', robot='double_pendulum', state_representation=2, max_velocity=20.0, torque_limit=[5.0, 5.0], scaling=True)

Bases: object

integration(x, u)
normalize_state(state)

rescale state: [-limit, limit] -> [-1, 1]

unscale_action(action)

scale the action [-1, 1] -> [-limit, +limit]

unscale_state(observation)

scale the state [-1, 1] -> [-limit, +limit]

double_pendulum.simulation.simulation

class double_pendulum.simulation.simulation.Simulator(plant)

Bases: object

Simulator class simulates and optionally animates the double pendulum motion. Animation is done with matplotlib Funcanimation.

Parameters:
plantSymbolicDoublePendulum or DoublePendulumPlant object

A plant object containing the kinematics and dynamics of the double pendulum

controller_step(dt, controller=None, integrator='runge_kutta')
Perform a full simulation step including
  • get measurement

  • filter measurement

  • get controller signal

  • calculate actual applied torques

  • integrate the eom

Parameters:
dtfloat

timestep, unit=[s]

controllerController object

Controller whose control signal is used If None, motir torques are set to 0.

(Default value = None)

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

(Default value = “runge_kutta”)

Returns:
bool

Flag stating real time calculation True: The calculation was performed in real time False: The calculation was not performed in real time

euler_integrator(y, dt, t, tau)

Performs a Euler integration step

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

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

dtfloat

timestep, unit=[s]

tfloat

time, unit=[s]

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

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

Returns:
numpy_array

shape=(4,), dtype=float, new state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

filter_measurement(x)

Filter a measured state.

(parameters set in set_filter_parameters)

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=(4,), dtype=float, filters state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

get_control_u(controller, x, t, dt)

Get the control signal from the controller

Parameters:
controllerController object

Controller whose control signal is used If None, motir torques are set to 0.

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

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

tfloat,

time, units=[s], not used

dtfloat

timestep, unit=[s]

Returns:
numpy_array

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

bool

Flag stating real time calculation True: The calculation was performed in real time False: The calculation was not performed in real time

get_measurement(dt)

Get a measurement from the internal state

The state measurement is described by x_meas(t) = C*x(t-delay) + D*u(t-delay) + N(sigma)

(parameters set by set_measurement_parameters)

Parameters:
dtfloat

timestep, unit=[s]

Returns:
numpy_array

shape=(4,), dtype=float, measured state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

get_real_applied_u(u)

Get the torque that the motor actually applies.

The applied motor torque (u_out) is related to the commanded torque (u) and the last torque output (u_last) via

u_out = u_responsiveness*u + (1-u_responsiveness)*u_last + N(sigma)

(parameters set in set_motor_parameters)

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

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

Returns:
array-like

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

get_state()

Get the double pendulum state

Returns:
float

time, unit=[s]

numpy_array

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

get_trajectory_data()

Get the rocrded trajectory data

Returns:
numpy_array

time points, unit=[s] shape=(N,)

numpy_array

shape=(N, 4) states, units=[rad, rad, rad/s, rad/s] order=[angle1, angle2, velocity1, velocity2]

numpy_array

shape=(N, 2) actuations/motor torques order=[u1, u2], units=[Nm]

init_filter(x0, dt, integrator)

Initialize the filter

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

reference state if a linearization is needed (Kalman filter), order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

dtfloat

timestep, unit=[s]

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

record_data(t, x, tau=None)

Record a data point in the simulator’s internal record

Parameters:
tfloat

time, units=[s]

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]

reset()

Reset the Simulator Resets

  • the internal data recorder

  • the filter + arguments

  • the process noise

  • the measurement parameters

  • the motor parameters

  • perturbations

reset_data_recorder()

Reset the internal data record of the simulator

runge_integrator(y, dt, t, tau)

Performs a Runge-Kutta integration step

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

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

dtfloat

timestep, unit=[s]

tfloat

time, unit=[s]

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

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

Returns:
numpy_array

shape=(4,), dtype=float, new state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

set_disturbances(perturbation_times=[], perturbation_taus=[])

Set disturbances (hits) happening during the simulation. (Not yet implemented)

Parameters:
perturbation_timesarray_like

(Default value = [])

perturbation_tausarray_like

(Default value = [])

set_filter_parameters(meas_noise_cut=0.0, meas_noise_vfilter='None', meas_noise_vfilter_args={'alpha': [1.0, 1.0, 1.0, 1.0]})

Set filter parameters for filtering raw measurments

Parameters:
meas_noise_cutfloat

measurements smaller than this value will be set to 0. (they are assumed to be noise) For meas_noise_cut==0.0, the measurement is not cut (Default value = 0.0)

meas_noise_vfilterstring

string determining the velocity noise filter “None”: No filter “lowpass”: lowpass filter “kalman”: kalman filter “unscented_kalman”: unscented kalman filter (Default value = “None”)

meas_noise_vfilter_argsdict

dictionary containing parameters for the velocity filter (Default value = {“alpha”: [1., 1., 1., 1.]})

set_measurement_parameters(C=array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]), D=array([[0., 0.], [0., 0.], [0., 0.], [0., 0.]]), meas_noise_sigmas=[0.0, 0.0, 0.0, 0.0], delay=0.0, delay_mode='None')

Set parameters for state measuremts

The state measurement is described by x_meas(t) = C*x(t-delay) + D*u(t-delay) + N(sigma)

Parameters:
Cnumpy_array

state-state measurement matrix (Default value = np.eye(4))

Dnumpy_array

state-torque measurement matrix (Default value = np.zeros((4, 2))

meas_noise_sigmasarray_like

Standard deviations of Gaussian measurement noise (Default value = [0., 0., 0., 0.])

delayfloat
time delay of measurements, unit=[s]

(Default value = 0.0)

delay_modestring

string determining what state variables are delayed: “None”: no delay “vel”: velocity measurements are delayed “posvel”: position and velocity measurements are delayed

(Default value = “None”)

set_motor_parameters(u_noise_sigmas=[0.0, 0.0], u_responsiveness=1.0)

Set parameters for the motors

The applied motor torque (u_out) is related to the commanded torque (u) and the last torque output (u_last) via

u_out = u_responsiveness*u + (1-u_responsiveness)*u_last + N(sigma)

Parameters:
u_noise_sigmasarray_like

shape=(2,) Standard deviation of the gaussian noise for the torque produced by the motors (Default value = [0., 0.])

u_responsivenessfloat

resonsiveness of the motors (Default value = 1.)

set_process_noise(process_noise_sigmas=[0.0, 0.0, 0.0, 0.0])

Set parameters for process noise (Gaussian)

Parameters:
process_noise_sigmasarray_like

shape=(4,) Gaussian standard deviations for the process noise. Each entry in the list corresponds to a state variable. (Default value = [0., 0., 0., 0.])

set_state(t, x)

Set the time and state of the double pendulum

Parameters:
tfloat

time, units=[s]

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

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

simulate(t0, x0, tf, dt, controller=None, integrator='runge_kutta')

Simulate the double pendulum for a time period under the control of a controller

Parameters:
t0float,

start time, units=[s]

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

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

tffloat

final time, units=[s]

dtfloat

timestep, unit=[s]

controllerController object

Controller whose control signal is used If None, motir torques are set to 0.

(Default value = None)

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

(Default value = “runge_kutta”)

Returns:
list

time points, unit=[s] shape=(N,)

list

shape=(N, 4) states, units=[rad, rad, rad/s, rad/s] order=[angle1, angle2, velocity1, velocity2]

list

shape=(N, 2) actuations/motor torques order=[u1, u2], units=[Nm]

simulate_and_animate(t0, x0, tf, dt, controller=None, integrator='runge_kutta', plot_inittraj=False, plot_forecast=False, plot_trail=True, phase_plot=False, save_video=False, video_name='pendulum_swingup.mp4', anim_dt=0.02, plot_horizontal_line=False, horizontal_line_height=0.0, scale=1.0)

Simulate and animate the double pendulum for a time period under the control of a controller. The animation is only implemented for 2d serial chains.

Parameters:
t0float,

start time, units=[s]

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

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

tffloat

final time, units=[s]

dtfloat

timestep, unit=[s]

controllerController object

Controller whose control signal is used If None, motir torques are set to 0. (Default value = None)

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

(Default value = “runge_kutta”)

plot_inittrajbool

Whether to plot an initial (reference) trajectory (Default value = False)

plot_forecastbool

Whether to plot a forcasted trajectory (Default value = False)

plot_trailbool

Whether to plot a trail for the masses (Default value = True)

phase_plotbool

not used (Default value = False)

save_videobool

Whether to render and save a video of the animation. Will be saved to video_name (Default value = False)

video_namestring

filepath where a video of the animation is stored if save_video==True (Default value = “pendulum_swingup.mp4”)

anim_dtfloat

timestep used for the animation, unit=[s] (Default value = 0.02)

Returns:
list

time points, unit=[s] shape=(N,)

list

shape=(N, 4) states, units=[rad, rad, rad/s, rad/s] order=[angle1, angle2, velocity1, velocity2]

list

shape=(N, 2) actuations/motor torques order=[u1, u2], units=[Nm]

step(tau, dt, integrator='runge_kutta')

Performs a simulation step with the specified integrator. Also adds process noise to the integration result. Uses and updates the internal state

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

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

dtfloat

timestep, unit=[s]

integratorstring

string determining the integration method “euler” : Euler integrator “runge_kutta” : Runge Kutta integrator

(Default value = “runge_kutta”)

double_pendulum.simulation.visualization

double_pendulum.simulation.visualization.get_arrow(radius, centX, centY, angle_, theta2_, color_='black')

Get circular arrow for visualizing motir torque.

Parameters:
radiusfloat

radius, unit=[m]

centXfloat

arrow center x-coordintate

centYfloat

arrow center y-coordintate

angle_float

orientation of the arrow

theta2_float

the arrow does extend over this angle

color_string or matplotlib color object
color of the arrow

(Default value = ‘black’)

Returns:
matplotlib.patches.Arc

Arrow arc

matplotlib.patches.RegularPolygon

Arrow head

double_pendulum.simulation.visualization.set_arrow_properties(arc, head, tau, x, y)

Set arrow properties

Changes are made directly in the provided arc and head objects

Parameters:
arcmatplotlib.patches.Arc

Arrow arc

headmatplotlib.patches.RegularPolygon

Arrow head

taufloat

motor torque the arrow is supposed to visualize

xfloat

x-coordinate

yfloat

y-coordinate