Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature migration to gymnasium #215

Merged
merged 42 commits into from
Jul 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
ace4dc8
first changes for migration to gymnasium, set all imports to gymnasium
KoehlerM173 May 6, 2023
76472cf
Working DC example
devarndt May 6, 2023
015d2a9
fixed synch motor. _dead_time doesn't exist
devarndt May 6, 2023
6b174d3
fixed external plot
KoehlerM173 May 6, 2023
c694250
updated all examples with new reset func
KoehlerM173 May 6, 2023
f5f5d2b
fixed classic_controllers.py, custom_classic_controllers_dc_motor_exa…
KoehlerM173 May 12, 2023
308eacb
Needs to be evaluated later
devarndt May 12, 2023
ae611c6
fixed faulty indexing in classic_controllers.py
KoehlerM173 May 13, 2023
760dee9
Merge branch 'feature_migration_to_gymnasium' of https://github.com/K…
KoehlerM173 May 26, 2023
9300b9e
reverted unwanted changes
KoehlerM173 May 26, 2023
78dcadc
realy reverted unwanted changes
KoehlerM173 May 26, 2023
8465e60
Working tests and examples:
devarndt May 29, 2023
75572bd
fixed precision warning in tests
devarndt May 29, 2023
095767f
get_figure() and save it to png file
devarndt Jun 16, 2023
9a16435
super.reset() was not in previous code
devarndt Jun 16, 2023
a4f360a
alignment of seeding with gymnasium
KoehlerM173 Jun 16, 2023
63dbe83
added default None to seeding in reset
KoehlerM173 Jun 16, 2023
5fdb095
Using the new seeding API
devarndt Jun 18, 2023
eef7a8c
changed done to terminated and truncated
KoehlerM173 Jun 18, 2023
c1acb3b
applying changes in .step() returns to test
KoehlerM173 Jun 18, 2023
0305a4e
render_mode human and None working
devarndt Jun 23, 2023
ba1f9d7
Merge commit 'c1acb3bc62f5b4e5c3f77b07980cf3666f8f03b7' into feature_…
devarndt Jun 23, 2023
e8ea66a
render_mode "file" is working
devarndt Jun 23, 2023
6b6267f
customizable filename prefix for "file" mode
devarndt Jun 23, 2023
ad70e31
create a output folder "plots" for saved figs
devarndt Jun 23, 2023
d0322ff
removed render() call
devarndt Jun 23, 2023
3c64ec8
alignment of y-labels in plot added
KoehlerM173 Jun 23, 2023
9b988be
Merge branch 'feature_migration_to_gymnasium' of https://github.com/K…
KoehlerM173 Jun 23, 2023
0594432
possibility to save a file after plot
devarndt Jun 30, 2023
747a974
renamed render modes
devarndt Jun 30, 2023
dfe53a3
Fixed keyword argument passthrough
devarndt Jul 1, 2023
055567b
Fix for other render modes
devarndt Jul 1, 2023
7d35b26
Fixed keyword argument passthrough for other envs
devarndt Jul 1, 2023
44482e1
Latex figure mode with saving as pdf
devarndt Jul 1, 2023
9710ca8
new integration test draft
KoehlerM173 Jul 1, 2023
421c2ad
Merge branch 'feature_migration_to_gymnasium' of https://github.com/K…
KoehlerM173 Jul 1, 2023
2203317
added auto-scaling for integrationtest
KoehlerM173 Jul 8, 2023
fb084ba
updated examples according to new render_modes
KoehlerM173 Jul 15, 2023
1f527a0
updated to fit code after migration to gymnasium
KoehlerM173 Jul 15, 2023
054f19b
removed first draft of integration test and renamend current
KoehlerM173 Jul 17, 2023
0e2e6f5
Updated with gymnasium
devarndt Jul 17, 2023
46b5e9e
Merge branch 'nightly' into feature_migration_to_gymnasium
wkirgsn Jul 17, 2023
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -30,3 +30,5 @@ examples/logs/
/my_examples/
.vscode/settings.json
.vscode/launch.json

plots/
1 change: 0 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ if __name__ == '__main__':
env = gem.make("Finite-CC-PMSM-v0") # instantiate a discretely controlled PMSM
env.reset()
for _ in range(10000):
env.render() # visualize environment
(states, references), rewards, done, _ =\
env.step(env.action_space.sample()) # pick random control actions
if done:
Expand Down
69 changes: 47 additions & 22 deletions examples/classic_controllers/classic_controllers.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from gym.spaces import Discrete, Box, MultiDiscrete
from gymnasium.spaces import Discrete, Box, MultiDiscrete
from gym_electric_motor.physical_systems import SynchronousMotorSystem, DcMotorSystem, DcSeriesMotor, \
DcExternallyExcitedMotor, DoublyFedInductionMotorSystem, SquirrelCageInductionMotorSystem
from gym_electric_motor.reference_generators import MultipleReferenceGenerator, SwitchedReferenceGenerator
Expand Down Expand Up @@ -347,27 +347,52 @@ def automated_gain(environment, stages, controller_type, _controllers, **control
elif _controllers[controller_type][0] == CascadedController:

for i in range(len(stages)):
if _controllers[stages_a[i]['controller_type']][1] == ContinuousController:

if i == 0:
p_gain = mp['l'] / (environment.physical_system.tau * a) / u_a_lim * i_a_lim
i_gain = p_gain / (environment.physical_system.tau * a ** 2)

if _controllers[stages_a[i]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i]['d_gain'] = stages_a[i].get('d_gain', d_gain)

elif i == 1:
t_n = environment.physical_system.tau * a ** 2
p_gain = environment.physical_system.mechanical_load.j_total / (
a * t_n) / i_a_lim * omega_lim
i_gain = p_gain / (a * t_n)
if _controllers[stages_a[i]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i]['d_gain'] = stages_a[i].get('d_gain', d_gain)

stages_a[i]['p_gain'] = stages_a[i].get('p_gain', p_gain)
stages_a[i]['i_gain'] = stages_a[i].get('i_gain', i_gain)
if type(stages_a[i]) is list:
if _controllers[stages_a[i][0]['controller_type']][1] == ContinuousController: #had to add [0] to make dict in list acessable

if i == 0:
p_gain = mp['l'] / (environment.physical_system.tau * a) / u_a_lim * i_a_lim
i_gain = p_gain / (environment.physical_system.tau * a ** 2)

if _controllers[stages_a[i][0]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i][0]['d_gain'] = stages_a[i][0].get('d_gain', d_gain)

elif i == 1:
t_n = environment.physical_system.tau * a ** 2
p_gain = environment.physical_system.mechanical_load.j_total / (
a * t_n) / i_a_lim * omega_lim
i_gain = p_gain / (a * t_n)
if _controllers[stages_a[i][0]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i][0]['d_gain'] = stages_a[i][0].get('d_gain', d_gain)

stages_a[i][0]['p_gain'] = stages_a[i][0].get('p_gain', p_gain)#?
stages_a[i][0]['i_gain'] = stages_a[i][0].get('i_gain', i_gain)#?

elif type(stages_a[i]) is dict:
if _controllers[stages_a[i]['controller_type']][1] == ContinuousController: #had to add [0] to make dict in list acessable

if i == 0:
p_gain = mp['l'] / (environment.physical_system.tau * a) / u_a_lim * i_a_lim
i_gain = p_gain / (environment.physical_system.tau * a ** 2)

if _controllers[stages_a[i]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i]['d_gain'] = stages_a[i].get('d_gain', d_gain)

elif i == 1:
t_n = environment.physical_system.tau * a ** 2
p_gain = environment.physical_system.mechanical_load.j_total / (
a * t_n) / i_a_lim * omega_lim
i_gain = p_gain / (a * t_n)
if _controllers[stages_a[i]['controller_type']][2] == PIDController:
d_gain = p_gain * environment.physical_system.tau
stages_a[i]['d_gain'] = stages_a[i].get('d_gain', d_gain)

stages_a[i]['p_gain'] = stages_a[i].get('p_gain', p_gain)#?
stages_a[i]['i_gain'] = stages_a[i].get('i_gain', i_gain)#?


stages = stages_a if not stages_e else [stages_a, stages_e]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,29 +38,27 @@
external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states]

# initialize the gym-electric-motor environment
env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots))

env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots), render_mode="figure_once")
"""
initialize the controller

Args:
environment gym-electric-motor environment
external_ref_plots (optional) plots of the environment, to plot all reference values
stages (optional) structure of the controller
automated_gain (optional) if True (default), the controller will be tune automatically
automated_gain (optional) if True (default), the controller will be tuned automatically
a (optional) tuning parameter of the symmetrical optimum (default: 4)

"""
visualization = MotorDashboard(additional_plots=external_ref_plots)
controller = Controller.make(env, external_ref_plots=external_ref_plots)

state, reference = env.reset()

state, reference = env.reset(seed = None)
# simulate the environment
for i in range(10001):
action = controller.control(state, reference)
env.render()
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@

# simulate the environment
for i in range(10001):
env.render()
action = controller.control(state, reference)
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()
env.close()
Original file line number Diff line number Diff line change
Expand Up @@ -54,10 +54,9 @@

# simulate the environment
for i in range(10001):
env.render()
action = controller.control(state, reference)
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()

Expand Down
10 changes: 6 additions & 4 deletions examples/classic_controllers/controllers/cascaded_controller.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from .continuous_controller import ContinuousController
from gym.spaces import Box, Discrete, MultiDiscrete
from gymnasium.spaces import Box, Discrete, MultiDiscrete
from gym_electric_motor.physical_systems import DcExternallyExcitedMotor
from .plot_external_data import plot

Expand All @@ -16,6 +16,7 @@ class CascadedController:

def __init__(self, environment, stages, _controllers, visualization, ref_states, external_ref_plots=(), **controller_kwargs):

self.env = environment
self.visualization = visualization
self.action_space = environment.action_space
self.state_space = environment.physical_system.state_space
Expand Down Expand Up @@ -171,9 +172,10 @@ def control(self, state, reference):
else:
action = np.array([action, action_u_e], dtype='object')

# Plot the external references
plot(external_reference_plots=self.external_ref_plots, state_names=self.state_names,
visualization=self.visualization, external_data=self.get_plot_data())
if self.env.render_mode != None:
# Plot the external references
plot(external_reference_plots=self.external_ref_plots, state_names=self.state_names,
visualization=self.visualization, external_data=self.get_plot_data())

return action

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
from .continuous_controller import ContinuousController
from .torque_to_current_conversion import TorqueToCurrentConversion
from .plot_external_data import plot
from gym.spaces import Box
from gymnasium.spaces import Box
import numpy as np


Expand Down Expand Up @@ -53,7 +53,7 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_

self.mp = environment.physical_system.electrical_motor.motor_parameter
self.psi_p = self.mp.get('psi_p', 0)
self.dead_time = 1.5 if environment.physical_system.converter._dead_time else 0.5
self.dead_time = 0.5
self.decoupling = controller_kwargs.get('decoupling', True)

self.ref_state_idx = [self.i_sq_idx, self.i_sd_idx]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from gym.spaces import Box
from gymnasium.spaces import Box
from gym_electric_motor.physical_systems import DcMotorSystem, DcExternallyExcitedMotor
from .plot_external_data import plot
import numpy as np
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from .plot_external_data import plot
from gym.spaces import Discrete, MultiDiscrete
from gymnasium.spaces import Discrete, MultiDiscrete
from gym_electric_motor.physical_systems import DcMotorSystem, DcExternallyExcitedMotor
import numpy as np

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from gym.spaces import Discrete, MultiDiscrete
from gymnasium.spaces import Discrete, MultiDiscrete


class DiscreteController:
Expand Down
2 changes: 1 addition & 1 deletion examples/classic_controllers/controllers/foc_controller.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from .plot_external_data import plot
from gym_electric_motor.physical_systems import SynchronousMotorSystem
from gym.spaces import Box
from gymnasium.spaces import Box
import numpy as np


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
from .induction_motor_torque_to_current_conversion import InductionMotorTorqueToCurrentConversion
from .flux_observer import FluxObserver
from .plot_external_data import plot
from gym.spaces import Box
from gymnasium.spaces import Box
import numpy as np


Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from .flux_observer import FluxObserver
from .plot_external_data import plot
from gym.spaces import Box
from gymnasium.spaces import Box
import numpy as np


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,12 @@ class TorqueToCurrentConversion:
This class represents the torque controller for cascaded control of synchronous motors. For low speeds only the
current limitation of the motor is important. The current vector to set a desired torque is selected so that the
amount of the current vector is minimum (Maximum Torque per Current). For higher speeds, the voltage limitation
of the synchronous motor or the actuator must also be taken into account. This is done by converting the
of the synchronous motor or the actuator must also be taken into account. This is terminated by converting the
available voltage to a speed-dependent maximum flux. An additional modulation controller is used for the flux
control. By limiting the flux and the maximum torque per flux (MTPF), an operating point for the flux and the
torque is obtained. This is then converted into a current operating point. The conversion can be done by
torque is obtained. This is then converted into a current operating point. The conversion can be terminated by
different methods (parameter torque_control). On the one hand, maps can be determined in advance by
interpolation or analytically, or the analytical determination can be done online.
interpolation or analytically, or the analytical determination can be terminated online.
For the visualization of the operating points, both for the current operating points as well as the flux and
torque operating points, predefined plots are available (plot_torque: default True). Also the values of the
modulation controller can be visualized (plot_modulation: default False).
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states]

# initialize the gym-electric-motor environment
env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots))
env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots), render_mode = 'figure')

"""
initialize the controller
Expand Down Expand Up @@ -74,9 +74,8 @@
# simulate the environment
for i in range(10001):
action = controller.control(state, reference)
env.render()
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,9 @@

# simulate the environment
for i in range(10001):
env.render()
action = controller.control(state, reference)
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()
env.close()
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@

# initialize the gym-electric-motor environment
env = gem.make(env_id, visualization=MotorDashboard(additional_plots=external_ref_plots),
motor=dict(limit_values=limit_values, nominal_values=nominal_values, motor_parameter=motor_parameter))
motor=dict(limit_values=limit_values, nominal_values=nominal_values, motor_parameter=motor_parameter),
render_mode = 'figure')

"""
initialize the controller
Expand Down Expand Up @@ -104,10 +105,9 @@

# simulate the environment
for i in range(10001):
env.render()
action = controller.control(state, reference)
(state, reference), reward, done, _ = env.step(action)
if done:
(state, reference), reward, terminated, truncated, _ = env.step(action)
if terminated:
env.reset()
controller.reset()

Expand Down
13 changes: 6 additions & 7 deletions examples/classic_controllers/external_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,13 @@ class ExternalPlot(TimePlot):
>>> # setting the labels of the plots
>>> external_plot.set_label({'y_label': 'y', 'state_label': '$state$', 'ref_label': '$reference$',
... 'add_label': ['$add_1$', '$add_2$']})
>>> done = True
>>> terminated = True
>>> for t in range(100000):
>>> if done:
>>> if terminated:
>>> state, reference = env.reset()
>>> env.render()
>>> data = [np.sin(t / 500), np.sin(t / 1000), np.sin(t / 1500), np.sin(t / 2000)]
>>> external_plot.add_data(data) # passing the data to the external plot
>>> (state, reference), reward, done, _ = env.step([0, 0])
>>> (state, reference), reward, terminated, truncated, _ = env.step([0, 0])
"""

def __init__(self, referenced=False, additional_lines=0, min=0, max=1):
Expand Down Expand Up @@ -111,7 +110,7 @@ def initialize(self, axis):
# If the state is referenced plot also the reference line
if self._referenced:
self._reference_line, = self._axis.plot(self._x_data, self._reference_data, **self._ref_line_config, zorder=self.add_lines+1)
axis.lines = axis.lines[::-1]
#axis.lines = axis.lines[::-1]
self._lines.append(self._reference_line)

self._y_data = [self._state_data, self._reference_data]
Expand Down Expand Up @@ -149,8 +148,8 @@ def set_label(self, labels):
if 'add_label' in labels.keys():
self.add_labels = labels['add_label']

def on_step_end(self, k, state, reference, reward, done):
super().on_step_end(k, state, reference, reward, done)
def on_step_end(self, k, state, reference, reward, terminated):
super().on_step_end(k, state, reference, reward, terminated)
idx = self.data_idx
self._x_data[idx] = self._t

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,14 @@ class ExternallyReferencedStatePlot(StatePlot):
'DqCont-SC-PMSM-v0',
visualization=dict(additional_plots=(my_externally_referenced_plot,),
)
done = True
terminated = True
for _ in range(10000):
if done:
if terminated:
state, reference = env.reset()
external_reference_value = my_external_isd_reference_generator.get_reference()
my_externally_referenced_plot.external_reference(external_reference_value)
env.render()
action = env.action_space.sample()
(state, reference), reward, done, _ = env.step(action)
(state, reference), reward, terminated, truncated, _ = env.step(action)
"""

def __init__(self, state):
Expand Down
Loading