diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 9760afc9..86eb8cff 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -15,7 +15,7 @@ jobs: strategy: fail-fast: false matrix: - python-version: [3.8, 3.9, "3.10"] + python-version: [3.9, "3.10", "3.11", "3.12", "3.13"] steps: - uses: actions/checkout@v3 @@ -32,16 +32,15 @@ jobs: env: PY_VER: ${{ matrix.python-version }} run: | - if [[ "$PY_VER" = "3.7" ]]; then pytest --cov=gym_electric_motor tests/; else pytest; fi - if [[ "$PY_VER" = "3.7" ]]; then bash <(curl -s https://codecov.io/bash); fi # code coverage report upload + pytest build-doc: runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 - name: Build Sphinx documentation - uses: ammaraskar/sphinx-action@master + uses: nicholasphair/sphinx-action@7.0.0 with: - pre-build-command: "python -m pip install sphinx m2r2 sphinx_rtd_theme && python -m pip install -r requirements.txt & python -m pip install ." + pre-build-command: "python -m pip install sphinx m2r2 sphinx_rtd_theme==1.3.0 && python -m pip install -r requirements.txt && python -m pip install ." docs-folder: "docs/" # Publish built docs to gh-pages branch. # =============================== diff --git a/.gitignore b/.gitignore index 180017c8..be0750cb 100644 --- a/.gitignore +++ b/.gitignore @@ -30,4 +30,5 @@ examples/logs/ /my_examples/ .vscode/settings.json .vscode/launch.json -plots/ \ No newline at end of file +plots/ +saved_plots/ \ No newline at end of file diff --git a/CHANGELOG.md b/CHANGELOG.md index 0150ba1a..cd80819f 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -9,6 +9,26 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ## Changed ## Fixed +## [3.0.0] - Unreleased +## Added +- Support for Python 3.11, 3.12, 3.13 +- Ruff: Python linter & formatter (see [DEVELOPMENT.md](DEVELOPMENT.md)) +- StateObserver: An easy way to get state values with error checking [example](examples/observers/state_observer_example.py) +- Integrated gem_controls repository into gem. classic_controllers will be removed in further version +- Using pyproject.toml, dropping deprecated setup.py +- Enabled Gymnasium env checker [see here](https://gymnasium.farama.org/api/experimental/wrappers/#gymnasium.experimental.wrappers.PassiveEnvCheckerV0) +## Changed +- Dropped support for Python 3.8 +- Linted and formatted all files +- Changed max. steps in some test files to improve test speed by 30% +- Changed the syntax from gem_controller.py to be compatible with the gymnasium interface +## Fixed +- #244 Sphinx docu build +- #233 EESM ODE update +- #224 DqToAbcActionProcessor uses now the correct angle to apply the dq to abc transformation +- #223 CosSinProcessor uses now the denormalized angel for calculating the sin and cos +- #253 #256 all examples to the current syntax + ## [2.0.0] - 2023-08-15 ## Added - Support for Python 3.10 diff --git a/DEVELOPMENT.md b/DEVELOPMENT.md new file mode 100644 index 00000000..4c1f38c0 --- /dev/null +++ b/DEVELOPMENT.md @@ -0,0 +1,41 @@ +# Packaging +Update build tool: `python -m pip install --upgrade build` + +Build: `python -m build` + +# Testing +Run: `pytest --sw` +> --sw, --stepwise Exit on test failure and continue from last failing test next time + +Warning as error: +> python -W error -m pytest --sw -v + +# Linter and Formater +Ruff: https://docs.astral.sh/ruff/installation/ + +Use `ruff check src/` for linting +or `ruff format src/` for formatting + + +# Install package for local development +Run: `pip install -e .` +> -e, --editable Install a project in editable mode (i.e. setuptools "develop mode") from a local project path or a VCS url + +Check correct package install directory with python interpreter +Run: `python` + +``` +>>> import gym_electric_motor as gem +>>> gem + +``` + +# Sidenotes +``` +python -V +Python 3.10.13 +``` + + +## No poetry +Some complex dependency systems don't work good with poetry (e.g. pytorch) (https://python-poetry.org/) \ No newline at end of file diff --git a/README.md b/README.md index c0eb937d..b92a5874 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,7 @@ [**Overview paper**](https://joss.theoj.org/papers/10.21105/joss.02498) | [**Reinforcement learning paper**](https://arxiv.org/abs/1910.09434) +| [**GEM control paper**](https://ieeexplore.ieee.org/document/10239044) | [**Quickstart**](#getting-started) | [**Install guide**](#installation) | [**Reference docs**](https://upb-lea.github.io/gym-electric-motor/) @@ -18,14 +19,15 @@ ## Overview The gym-electric-motor (GEM) package is a Python toolbox for the simulation and control of various electric motors. -It is built upon [Faram Gymnasium Environments](https://gym.openai.com/), and, therefore, can be used for both, classical control simulation and [reinforcement learning](https://github.com/upb-lea/reinforcement_learning_course_materials) experiments. It allows you to construct a typical drive train with the usual building blocks, i.e., supply voltages, converters, electric motors and load models, and obtain not only a closed-loop simulation of this physical structure, but also a rich interface for plugging in any decision making algorithm, from linear feedback control to [Deep Deterministic Policy Gradient](https://spinningup.openai.com/en/latest/algorithms/ddpg.html) agents. +It is built upon [Faram Gymnasium Environments](https://gymnasium.farama.org/), and, therefore, can be used for both, classical control simulation and [reinforcement learning](https://github.com/upb-lea/reinforcement_learning_course_materials) experiments. It allows you to construct a typical drive train with the usual building blocks, i.e., supply voltages, converters, electric motors and load models, and obtain not only a closed-loop simulation of this physical structure, but also a rich interface for plugging in any decision making algorithm, from linear feedback control to [Deep Deterministic Policy Gradient](https://spinningup.openai.com/en/latest/algorithms/ddpg.html) agents. +In addition, an automated framework for classical control structures based on PI controllers is provided. ## Getting Started An easy way to get started with GEM is by playing around with the following interactive notebooks in Google Colaboratory. Most important features of GEM as well as application demonstrations are showcased, and give a kickstart for engineers in industry and academia. * [GEM cookbook](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master//examples/environment_features/GEM_cookbook.ipynb) -* [Keras-rl2 example](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master/examples/reinforcement_learning_controllers/keras_rl2_dqn_disc_pmsm_example.ipynb) -* [Stable-baselines3 example](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master/examples/reinforcement_learning_controllers/stable_baselines3_dqn_disc_pmsm_example.ipynb) +* [Stable-baselines3 DDPG example](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master/examples/reinforcement_learning_controllers/stable_baselines3_ddpg_pmsm_dq_current_control.ipynb) +* [Stable-baselines3 DQN example](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master/examples/reinforcement_learning_controllers/stable_baselines3_dqn_disc_pmsm_example.ipynb) * [MPC example](https://colab.research.google.com/github/upb-lea/gym-electric-motor/blob/master/examples/model_predictive_controllers/pmsm_mpc_dq_current_control.ipynb) There is a list of [standalone example scripts](examples/) as well for minimalistic demonstrations. @@ -68,7 +70,7 @@ pip install -e . ## Building Blocks A GEM environment consists of following building blocks: - Physical structure: - - Supply voltage + - Voltage supply - Converter - Electric motor - Load model @@ -78,8 +80,9 @@ A GEM environment consists of following building blocks: ![](docs/plots/SCML_Overview.png) Among various DC-motor models, the following AC motors - together with their power electronic counterparts - are available: -- Permanent magnet synchronous motor (PMSM), +- Permanent magnet synchronous motor (PMSM) - Synchronous reluctance motor (SynRM) +- Externally exited synchronous motor (EESM) - Squirrel cage induction motor (SCIM) - Doubly-fed induction motor (DFIM) @@ -116,6 +119,19 @@ A white paper for the utilization of this framework within reinforcement learnin doi={10.1109/TNNLS.2020.3029573}} ``` +A white paper for the classical control approaches of gym-electric-motor control is available at [IEEE-Xplore](https://ieeexplore.ieee.org/document/10239044). Please use the following BibTeX entry for citing it: +``` +@INPROCEEDINGS{10239044, + author={Book, Felix and Traue, Arne and Schenke, Maximilian and Haucke-Korber, Barnabas and Wallscheid, Oliver}, + booktitle={2023 IEEE International Electric Machines & Drives Conference (IEMDC)}, + title={Gym-Electric-Motor (GEM) Control: An Automated Open-Source Controller Design Suite for Drives}, + year={2023}, + volume={}, + number={}, + pages={1-7}, + doi={10.1109/IEMDC55163.2023.10239044}} +``` + ### Running Unit Tests with Pytest To run the unit tests ''pytest'' is required. All tests can be found in the ''tests'' folder. diff --git a/examples/classic_controllers/classic_controllers.py b/examples/classic_controllers/classic_controllers.py index e18b3f4b..9ade5e6b 100644 --- a/examples/classic_controllers/classic_controllers.py +++ b/examples/classic_controllers/classic_controllers.py @@ -1,30 +1,38 @@ -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 -from gym_electric_motor.visualization import MotorDashboard -from gym_electric_motor import envs - -from controllers.continuous_controller import ContinuousController -from controllers.pi_controller import PIController -from controllers.pid_controller import PIDController - -from controllers.discrete_controller import DiscreteController -from controllers.on_off_controller import OnOffController -from controllers.three_point_controller import ThreePointController - +import numpy as np +from controllers.cascaded_controller import CascadedController +from controllers.cascaded_foc_controller import CascadedFieldOrientedController from controllers.continuous_action_controller import ContinuousActionController +from controllers.continuous_controller import ContinuousController from controllers.dicrete_action_controller import DiscreteActionController -from controllers.cascaded_controller import CascadedController +from controllers.discrete_controller import DiscreteController from controllers.foc_controller import FieldOrientedController -from controllers.cascaded_foc_controller import CascadedFieldOrientedController +from controllers.induction_motor_cascaded_foc import ( + InductionMotorCascadedFieldOrientedController, +) from controllers.induction_motor_foc import InductionMotorFieldOrientedController -from controllers.induction_motor_cascaded_foc import InductionMotorCascadedFieldOrientedController - -from externally_referenced_state_plot import ExternallyReferencedStatePlot +from controllers.on_off_controller import OnOffController +from controllers.pi_controller import PIController +from controllers.pid_controller import PIDController +from controllers.three_point_controller import ThreePointController from external_plot import ExternalPlot +from externally_referenced_state_plot import ExternallyReferencedStatePlot +from gymnasium.spaces import Box, Discrete, MultiDiscrete + +from gym_electric_motor import envs +from gym_electric_motor.physical_systems import ( + DcExternallyExcitedMotor, + DcMotorSystem, + DcSeriesMotor, + DoublyFedInductionMotorSystem, + SquirrelCageInductionMotorSystem, + SynchronousMotorSystem, +) +from gym_electric_motor.reference_generators import ( + MultipleReferenceGenerator, + SwitchedReferenceGenerator, +) +from gym_electric_motor.visualization import MotorDashboard -import numpy as np class Controller: """This is the base class for every controller along with the motor environments.""" @@ -47,22 +55,34 @@ def make(cls, environment, stages=None, **controller_kwargs): """ _controllers = { - 'pi_controller': [ContinuousActionController, ContinuousController, PIController], - 'pid_controller': [ContinuousActionController, ContinuousController, PIDController], - 'on_off': [DiscreteActionController, DiscreteController, OnOffController], - 'three_point': [DiscreteActionController, DiscreteController, ThreePointController], - 'cascaded_controller': [CascadedController], - 'foc_controller': [FieldOrientedController], - 'cascaded_foc_controller': [CascadedFieldOrientedController], - 'foc_rotor_flux_observer': [InductionMotorFieldOrientedController], - 'cascaded_foc_rotor_flux_observer': [InductionMotorCascadedFieldOrientedController], - } + "pi_controller": [ + ContinuousActionController, + ContinuousController, + PIController, + ], + "pid_controller": [ + ContinuousActionController, + ContinuousController, + PIDController, + ], + "on_off": [DiscreteActionController, DiscreteController, OnOffController], + "three_point": [ + DiscreteActionController, + DiscreteController, + ThreePointController, + ], + "cascaded_controller": [CascadedController], + "foc_controller": [FieldOrientedController], + "cascaded_foc_controller": [CascadedFieldOrientedController], + "foc_rotor_flux_observer": [InductionMotorFieldOrientedController], + "cascaded_foc_rotor_flux_observer": [InductionMotorCascadedFieldOrientedController], + } controller_kwargs = cls.reference_states(environment, **controller_kwargs) controller_kwargs = cls.get_visualization(environment, **controller_kwargs) if stages is not None: controller_type, stages = cls.find_controller_type(environment, stages, **controller_kwargs) - assert controller_type in _controllers.keys(), f'Controller {controller_type} unknown' + assert controller_type in _controllers.keys(), f"Controller {controller_type} unknown" stages = cls.automated_gain(environment, stages, controller_type, _controllers, **controller_kwargs) controller = _controllers[controller_type][0](environment, stages, _controllers, **controller_kwargs) @@ -75,92 +95,91 @@ def make(cls, environment, stages=None, **controller_kwargs): @staticmethod def get_visualization(environment, **controller_kwargs): """This method separates external_plots and external_ref_plots. It also checks if a MotorDashboard is used.""" - if 'external_plot' in controller_kwargs.keys(): + if "external_plot" in controller_kwargs.keys(): ext_plot = [] ref_plot = [] - for external_plots in controller_kwargs['external_plot']: + for external_plots in controller_kwargs["external_plot"]: if isinstance(external_plots, ExternalPlot): ext_plot.append(external_plots) elif isinstance(external_plots, ExternallyReferencedStatePlot): ref_plot.append(external_plots) - controller_kwargs['external_plot'] = ext_plot - controller_kwargs['external_ref_plots'] = ref_plot + controller_kwargs["external_plot"] = ext_plot + controller_kwargs["external_ref_plots"] = ref_plot - for visualization in environment.visualizations: + for visualization in environment.unwrapped.visualizations: if isinstance(visualization, MotorDashboard): - controller_kwargs['update_interval'] = visualization.update_interval - controller_kwargs['visualization'] = True + controller_kwargs["update_interval"] = visualization.update_interval + controller_kwargs["visualization"] = True return controller_kwargs - controller_kwargs['visualization'] = False + controller_kwargs["visualization"] = False return controller_kwargs @staticmethod def reference_states(environment, **controller_kwargs): """This method searches the environment for all referenced states and writes them to an array.""" ref_states = [] - if isinstance(environment.reference_generator, MultipleReferenceGenerator): - - for rg in environment.reference_generator._sub_generators: + if isinstance(environment.unwrapped.reference_generator, MultipleReferenceGenerator): + for rg in environment.unwrapped.reference_generator._sub_generators: if isinstance(rg, SwitchedReferenceGenerator): ref_states.append(rg._sub_generators[0]._reference_state) else: ref_states.append(rg._reference_state) - elif isinstance(environment.reference_generator, SwitchedReferenceGenerator): - ref_states.append(environment.reference_generator._sub_generators[0]._reference_state) + elif isinstance(environment.unwrapped.reference_generator, SwitchedReferenceGenerator): + ref_states.append(environment.unwrapped.reference_generator._sub_generators[0]._reference_state) else: - ref_states.append(environment.reference_generator._reference_state) - controller_kwargs['ref_states'] = np.array(ref_states) + ref_states.append(environment.unwrapped.reference_generator._reference_state) + controller_kwargs["ref_states"] = np.array(ref_states) return controller_kwargs @staticmethod def find_controller_type(environment, stages, **controller_kwargs): _stages = stages - if isinstance(environment.physical_system.unwrapped, DcMotorSystem): + if isinstance(environment.unwrapped.physical_system, DcMotorSystem): if type(stages) is list: if len(stages) > 1: if type(stages[0]) is list: stages = stages[0] if len(stages) > 1: - controller_type = 'cascaded_controller' + controller_type = "cascaded_controller" else: - controller_type = stages[0]['controller_type'] + controller_type = stages[0]["controller_type"] else: - controller_type = stages[0]['controller_type'] + controller_type = stages[0]["controller_type"] else: if type(stages) is dict: - controller_type = stages['controller_type'] + controller_type = stages["controller_type"] _stages = [stages] else: controller_type = stages - _stages = [{'controller_type': stages}] + _stages = [{"controller_type": stages}] elif isinstance(environment.physical_system.unwrapped, SynchronousMotorSystem): if len(stages) == 2: - if len(stages[1]) == 1 and 'i_sq' in controller_kwargs['ref_states']: - controller_type = 'foc_controller' + if len(stages[1]) == 1 and "i_sq" in controller_kwargs["ref_states"]: + controller_type = "foc_controller" else: - controller_type = 'cascaded_foc_controller' + controller_type = "cascaded_foc_controller" else: - controller_type = 'cascaded_foc_controller' + controller_type = "cascaded_foc_controller" elif isinstance(environment.physical_system.unwrapped, SquirrelCageInductionMotorSystem): if len(stages) == 2: - if len(stages[1]) == 1 and 'i_sq' in controller_kwargs['ref_states']: - controller_type = 'foc_rotor_flux_observer' + if len(stages[1]) == 1 and "i_sq" in controller_kwargs["ref_states"]: + controller_type = "foc_rotor_flux_observer" else: - controller_type = 'cascaded_foc_rotor_flux_observer' + controller_type = "cascaded_foc_rotor_flux_observer" else: - controller_type = 'cascaded_foc_rotor_flux_observer' + controller_type = "cascaded_foc_rotor_flux_observer" elif isinstance(environment.physical_system.unwrapped, DoublyFedInductionMotorSystem): if len(stages) == 2: - if len(stages[1]) == 1 and 'i_sq' in controller_kwargs['ref_states']: - controller_type = 'foc_rotor_flux_observer' + if len(stages[1]) == 1 and "i_sq" in controller_kwargs["ref_states"]: + controller_type = "foc_rotor_flux_observer" else: - controller_type = 'cascaded_foc_rotor_flux_observer' + controller_type = "cascaded_foc_rotor_flux_observer" else: - controller_type = 'cascaded_foc_rotor_flux_observer' + controller_type = "cascaded_foc_rotor_flux_observer" return controller_type, _stages @@ -169,150 +188,188 @@ def automated_controller_design(environment, **controller_kwargs): """This method automatically designs the controller based on the given motor environment and control task.""" action_space_type = type(environment.action_space) - ref_states = controller_kwargs['ref_states'] + ref_states = controller_kwargs["ref_states"] stages = [] - if isinstance(environment.physical_system.unwrapped, DcMotorSystem): # Checking type of motor - - if 'omega' in ref_states or 'torque' in ref_states: # Checking control task - controller_type = 'cascaded_controller' + if isinstance(environment.unwrapped.physical_system.unwrapped, DcMotorSystem): # Checking type of motor + if "omega" in ref_states or "torque" in ref_states: # Checking control task + controller_type = "cascaded_controller" for i in range(len(stages), 2): if i == 0: if action_space_type is Box: # Checking type of output stage (finite / cont) - stages.append({'controller_type': 'pi_controller'}) + stages.append({"controller_type": "pi_controller"}) else: - stages.append({'controller_type': 'three_point'}) + stages.append({"controller_type": "three_point"}) else: - stages.append({'controller_type': 'pi_controller'}) # Adding PI-Controller for overlaid stages + stages.append({"controller_type": "pi_controller"}) # Adding PI-Controller for overlaid stages - elif 'i' in ref_states or 'i_a' in ref_states: + elif "i" in ref_states or "i_a" in ref_states: # Checking type of output stage (finite / cont) if action_space_type is Discrete or action_space_type is MultiDiscrete: - stages.append({'controller_type': 'three_point'}) + stages.append({"controller_type": "three_point"}) elif action_space_type is Box: - stages.append({'controller_type': 'pi_controller'}) - controller_type = stages[0]['controller_type'] + stages.append({"controller_type": "pi_controller"}) + controller_type = stages[0]["controller_type"] # Add stage for i_e current of the ExtExDC - if isinstance(environment.physical_system.electrical_motor, DcExternallyExcitedMotor): + if isinstance(environment.unwrapped.physical_system.electrical_motor, DcExternallyExcitedMotor): if action_space_type is Box: - stages = [stages, [{'controller_type': 'pi_controller'}]] + stages = [stages, [{"controller_type": "pi_controller"}]] else: - stages = [stages, [{'controller_type': 'three_point'}]] + stages = [stages, [{"controller_type": "three_point"}]] - elif isinstance(environment.physical_system.unwrapped, SynchronousMotorSystem): - if 'i_sq' in ref_states or 'torque' in ref_states: # Checking control task - controller_type = 'foc_controller' if 'i_sq' in ref_states else 'cascaded_foc_controller' + elif isinstance(environment.unwrapped.physical_system.unwrapped, SynchronousMotorSystem): + if "i_sq" in ref_states or "torque" in ref_states: # Checking control task + controller_type = "foc_controller" if "i_sq" in ref_states else "cascaded_foc_controller" if action_space_type is Discrete: - stages = [[{'controller_type': 'on_off'}], [{'controller_type': 'on_off'}], - [{'controller_type': 'on_off'}]] + stages = [ + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + ] else: - stages = [[{'controller_type': 'pi_controller'}, {'controller_type': 'pi_controller'}]] - elif 'omega' in ref_states: - controller_type = 'cascaded_foc_controller' + stages = [ + [ + {"controller_type": "pi_controller"}, + {"controller_type": "pi_controller"}, + ] + ] + elif "omega" in ref_states: + controller_type = "cascaded_foc_controller" if action_space_type is Discrete: - stages = [[{'controller_type': 'on_off'}], [{'controller_type': 'on_off'}], - [{'controller_type': 'on_off'}], [{'controller_type': 'pi_controller'}]] + stages = [ + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "pi_controller"}], + ] else: - stages = [[{'controller_type': 'pi_controller'}, - {'controller_type': 'pi_controller'}], [{'controller_type': 'pi_controller'}]] - - elif isinstance(environment.physical_system.unwrapped, (SquirrelCageInductionMotorSystem, DoublyFedInductionMotorSystem)): - if 'i_sq' in ref_states or 'torque' in ref_states: - controller_type = 'foc_rotor_flux_observer' if 'i_sq' in ref_states else 'cascaded_foc_rotor_flux_observer' + stages = [ + [ + {"controller_type": "pi_controller"}, + {"controller_type": "pi_controller"}, + ], + [{"controller_type": "pi_controller"}], + ] + + elif isinstance( + environment.physical_system.unwrapped, + (SquirrelCageInductionMotorSystem, DoublyFedInductionMotorSystem), + ): + if "i_sq" in ref_states or "torque" in ref_states: + controller_type = ( + "foc_rotor_flux_observer" if "i_sq" in ref_states else "cascaded_foc_rotor_flux_observer" + ) if action_space_type is Discrete: - stages = [[{'controller_type': 'on_off'}], [{'controller_type': 'on_off'}], - [{'controller_type': 'on_off'}]] + stages = [ + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + ] else: - stages = [[{'controller_type': 'pi_controller'}, {'controller_type': 'pi_controller'}]] - elif 'omega' in ref_states: - controller_type = 'cascaded_foc_rotor_flux_observer' + stages = [ + [ + {"controller_type": "pi_controller"}, + {"controller_type": "pi_controller"}, + ] + ] + elif "omega" in ref_states: + controller_type = "cascaded_foc_rotor_flux_observer" if action_space_type is Discrete: - stages = [[{'controller_type': 'on_off'}], [{'controller_type': 'on_off'}], - [{'controller_type': 'on_off'}], [{'controller_type': 'pi_controller'}]] + stages = [ + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "on_off"}], + [{"controller_type": "pi_controller"}], + ] else: - stages = [[{'controller_type': 'pi_controller'}, - {'controller_type': 'pi_controller'}], [{'controller_type': 'pi_controller'}]] + stages = [ + [ + {"controller_type": "pi_controller"}, + {"controller_type": "pi_controller"}, + ], + [{"controller_type": "pi_controller"}], + ] else: - controller_type = 'foc_controller' + controller_type = "foc_controller" return controller_type, stages @staticmethod def automated_gain(environment, stages, controller_type, _controllers, **controller_kwargs): """ - This method automatically parameterizes a given controller design if the parameter automated_gain is True - (default True), based on the design according to the symmetric optimum (SO). Further information about the - design according to the SO can be found in the following paper (https://ieeexplore.ieee.org/document/55967). - - Args: - environment: gym-electric-motor environment - stages: list of the stages of the controller - controller_type: string of the used controller type from the dictionary _controllers - _controllers: dictionary of all possible controllers and controller stages - controller_kwargs: further arguments of the controller - - Returns: - list of stages, which are completely parameterized + This method automatically parameterizes a given controller design if the parameter automated_gain is True + (default True), based on the design according to the symmetric optimum (SO). Further information about the + design according to the SO can be found in the following paper (https://ieeexplore.ieee.org/document/55967). + + Args: + environment: gym-electric-motor environment + stages: list of the stages of the controller + controller_type: string of the used controller type from the dictionary _controllers + _controllers: dictionary of all possible controllers and controller stages + controller_kwargs: further arguments of the controller + + Returns: + list of stages, which are completely parameterized """ - ref_states = controller_kwargs['ref_states'] - mp = environment.physical_system.electrical_motor.motor_parameter - limits = environment.physical_system.limits - omega_lim = limits[environment.state_names.index('omega')] - if isinstance(environment.physical_system.unwrapped, DcMotorSystem): - i_a_lim = limits[environment.physical_system.CURRENTS_IDX[0]] - i_e_lim = limits[environment.physical_system.CURRENTS_IDX[-1]] - u_a_lim = limits[environment.physical_system.VOLTAGES_IDX[0]] - u_e_lim = limits[environment.physical_system.VOLTAGES_IDX[-1]] + ref_states = controller_kwargs["ref_states"] + mp = environment.unwrapped.physical_system.electrical_motor.motor_parameter + limits = environment.unwrapped.physical_system.limits + omega_lim = limits[environment.unwrapped.state_names.index("omega")] + if isinstance(environment.unwrapped.physical_system.unwrapped, DcMotorSystem): + i_a_lim = limits[environment.unwrapped.physical_system.CURRENTS_IDX[0]] + i_e_lim = limits[environment.unwrapped.physical_system.CURRENTS_IDX[-1]] + u_a_lim = limits[environment.unwrapped.physical_system.VOLTAGES_IDX[0]] + u_e_lim = limits[environment.unwrapped.physical_system.VOLTAGES_IDX[-1]] elif isinstance(environment.physical_system.unwrapped, SynchronousMotorSystem): - i_sd_lim = limits[environment.state_names.index('i_sd')] - i_sq_lim = limits[environment.state_names.index('i_sq')] - u_sd_lim = limits[environment.state_names.index('u_sd')] - u_sq_lim = limits[environment.state_names.index('u_sq')] - torque_lim = limits[environment.state_names.index('torque')] + i_sd_lim = limits[environment.state_names.index("i_sd")] + i_sq_lim = limits[environment.state_names.index("i_sq")] + u_sd_lim = limits[environment.state_names.index("u_sd")] + u_sq_lim = limits[environment.state_names.index("u_sq")] + torque_lim = limits[environment.state_names.index("torque")] else: - i_sd_lim = limits[environment.state_names.index('i_sd')] - i_sq_lim = limits[environment.state_names.index('i_sq')] - u_sd_lim = limits[environment.state_names.index('u_sd')] - u_sq_lim = limits[environment.state_names.index('u_sq')] - torque_lim = limits[environment.state_names.index('torque')] + i_sd_lim = limits[environment.state_names.index("i_sd")] + i_sq_lim = limits[environment.state_names.index("i_sq")] + u_sd_lim = limits[environment.state_names.index("u_sd")] + u_sq_lim = limits[environment.state_names.index("u_sq")] + torque_lim = limits[environment.state_names.index("torque")] # The parameter a is a design parameter when designing a controller according to the SO - a = controller_kwargs.get('a', 4) - automated_gain = controller_kwargs.get('automated_gain', True) + a = controller_kwargs.get("a", 4) + automated_gain = controller_kwargs.get("automated_gain", True) - if isinstance(environment.physical_system.electrical_motor, DcSeriesMotor): - mp['l'] = mp['l_a'] + mp['l_e'] - elif isinstance(environment.physical_system.unwrapped, DcMotorSystem): - mp['l'] = mp['l_a'] + if isinstance(environment.unwrapped.physical_system.electrical_motor, DcSeriesMotor): + mp["l"] = mp["l_a"] + mp["l_e"] + elif isinstance(environment.unwrapped.physical_system.unwrapped, DcMotorSystem): + mp["l"] = mp["l_a"] - if 'automated_gain' not in controller_kwargs.keys() or automated_gain: + if "automated_gain" not in controller_kwargs.keys() or automated_gain: cont_extex_envs = ( envs.ContSpeedControlDcExternallyExcitedMotorEnv, envs.ContCurrentControlDcExternallyExcitedMotorEnv, - envs.ContTorqueControlDcExternallyExcitedMotorEnv + envs.ContTorqueControlDcExternallyExcitedMotorEnv, ) finite_extex_envs = ( envs.FiniteTorqueControlDcExternallyExcitedMotorEnv, envs.FiniteSpeedControlDcExternallyExcitedMotorEnv, - envs.FiniteCurrentControlDcExternallyExcitedMotorEnv + envs.FiniteCurrentControlDcExternallyExcitedMotorEnv, ) if type(environment) in cont_extex_envs: stages_a = stages[0] stages_e = stages[1] - p_gain = mp['l_e'] / (environment.physical_system.tau * a) / u_e_lim * i_e_lim - i_gain = p_gain / (environment.physical_system.tau * a ** 2) + p_gain = mp["l_e"] / (environment.physical_system.tau * a) / u_e_lim * i_e_lim + i_gain = p_gain / (environment.physical_system.tau * a**2) - stages_e[0]['p_gain'] = stages_e[0].get('p_gain', p_gain) - stages_e[0]['i_gain'] = stages_e[0].get('i_gain', i_gain) + stages_e[0]["p_gain"] = stages_e[0].get("p_gain", p_gain) + stages_e[0]["i_gain"] = stages_e[0].get("i_gain", i_gain) - if stages_e[0]['controller_type'] == PIDController: + if stages_e[0]["controller_type"] == PIDController: d_gain = p_gain * environment.physical_system.tau - stages_e[0]['d_gain'] = stages_e[0].get('d_gain', d_gain) + stages_e[0]["d_gain"] = stages_e[0].get("d_gain", d_gain) elif type(environment) in finite_extex_envs: stages_a = stages[0] stages_e = stages[1] @@ -321,78 +378,91 @@ def automated_gain(environment, stages, controller_type, _controllers, **control stages_e = False if _controllers[controller_type][0] == ContinuousActionController: - if 'i' in ref_states or 'i_a' in ref_states or 'torque' in ref_states: - 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 "i" in ref_states or "i_a" in ref_states or "torque" in ref_states: + 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) - stages_a[0]['p_gain'] = stages_a[0].get('p_gain', p_gain) - stages_a[0]['i_gain'] = stages_a[0].get('i_gain', i_gain) + stages_a[0]["p_gain"] = stages_a[0].get("p_gain", p_gain) + stages_a[0]["i_gain"] = stages_a[0].get("i_gain", i_gain) if _controllers[controller_type][2] == PIDController: d_gain = p_gain * environment.physical_system.tau - stages_a[0]['d_gain'] = stages_a[0].get('d_gain', d_gain) + stages_a[0]["d_gain"] = stages_a[0].get("d_gain", d_gain) - elif 'omega' in ref_states: - p_gain = environment.physical_system.mechanical_load.j_total * mp['r_a'] ** 2 / ( - a * mp['l']) / u_a_lim * omega_lim - i_gain = p_gain / (a * mp['l']) + elif "omega" in ref_states: + p_gain = ( + environment.physical_system.mechanical_load.j_total + * mp["r_a"] ** 2 + / (a * mp["l"]) + / u_a_lim + * omega_lim + ) + i_gain = p_gain / (a * mp["l"]) - stages_a[0]['p_gain'] = stages_a[0].get('p_gain', p_gain) - stages_a[0]['i_gain'] = stages_a[0].get('i_gain', i_gain) + stages_a[0]["p_gain"] = stages_a[0].get("p_gain", p_gain) + stages_a[0]["i_gain"] = stages_a[0].get("i_gain", i_gain) if _controllers[controller_type][2] == PIDController: d_gain = p_gain * environment.physical_system.tau - stages_a[0]['d_gain'] = stages_a[0].get('d_gain', d_gain) + stages_a[0]["d_gain"] = stages_a[0].get("d_gain", d_gain) elif _controllers[controller_type][0] == CascadedController: - for i in range(len(stages)): 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 ( + _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) + p_gain = mp["l"] / (environment.unwrapped.physical_system.tau * a) / u_a_lim * i_a_lim + i_gain = p_gain / (environment.unwrapped.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) + if _controllers[stages_a[i][0]["controller_type"]][2] == PIDController: + d_gain = p_gain * environment.unwrapped.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 + t_n = environment.unwrapped.physical_system.tau * a**2 + p_gain = ( + environment.unwrapped.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) + if _controllers[stages_a[i][0]["controller_type"]][2] == PIDController: + d_gain = p_gain * environment.unwrapped.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)#? + 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 ( + _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) + p_gain = mp["l"] / (environment.unwrapped.physical_system.tau * a) / u_a_lim * i_a_lim + i_gain = p_gain / (environment.unwrapped.physical_system.tau * a**2) - if _controllers[stages_a[i]['controller_type']][2] == PIDController: + 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]["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 + t_n = environment.unwrapped.physical_system.tau * a**2 + p_gain = ( + environment.unwrapped.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 _controllers[stages_a[i]["controller_type"]][2] == PIDController: + d_gain = p_gain * environment.unwrapped.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] @@ -400,68 +470,70 @@ def automated_gain(environment, stages, controller_type, _controllers, **control if type(environment.action_space) == Box: stage_d = stages[0][0] stage_q = stages[0][1] - if 'i_sq' in ref_states and _controllers[stage_q['controller_type']][1] == ContinuousController: - p_gain_d = mp['l_d'] / (1.5 * environment.physical_system.tau * a) / u_sd_lim * i_sd_lim - i_gain_d = p_gain_d / (1.5 * environment.physical_system.tau * a ** 2) + if "i_sq" in ref_states and _controllers[stage_q["controller_type"]][1] == ContinuousController: + p_gain_d = mp["l_d"] / (1.5 * environment.physical_system.tau * a) / u_sd_lim * i_sd_lim + i_gain_d = p_gain_d / (1.5 * environment.physical_system.tau * a**2) - p_gain_q = mp['l_q'] / (1.5 * environment.physical_system.tau * a) / u_sq_lim * i_sq_lim - i_gain_q = p_gain_q / (1.5 * environment.physical_system.tau * a ** 2) + p_gain_q = mp["l_q"] / (1.5 * environment.physical_system.tau * a) / u_sq_lim * i_sq_lim + i_gain_q = p_gain_q / (1.5 * environment.physical_system.tau * a**2) - stage_d['p_gain'] = stage_d.get('p_gain', p_gain_d) - stage_d['i_gain'] = stage_d.get('i_gain', i_gain_d) + stage_d["p_gain"] = stage_d.get("p_gain", p_gain_d) + stage_d["i_gain"] = stage_d.get("i_gain", i_gain_d) - stage_q['p_gain'] = stage_q.get('p_gain', p_gain_q) - stage_q['i_gain'] = stage_q.get('i_gain', i_gain_q) + stage_q["p_gain"] = stage_q.get("p_gain", p_gain_q) + stage_q["i_gain"] = stage_q.get("i_gain", i_gain_q) - if _controllers[stage_d['controller_type']][2] == PIDController: + if _controllers[stage_d["controller_type"]][2] == PIDController: d_gain_d = p_gain_d * environment.physical_system.tau - stage_d['d_gain'] = stage_d.get('d_gain', d_gain_d) + stage_d["d_gain"] = stage_d.get("d_gain", d_gain_d) - if _controllers[stage_q['controller_type']][2] == PIDController: + if _controllers[stage_q["controller_type"]][2] == PIDController: d_gain_q = p_gain_q * environment.physical_system.tau - stage_q['d_gain'] = stage_q.get('d_gain', d_gain_q) + stage_q["d_gain"] = stage_q.get("d_gain", d_gain_q) stages = [[stage_d, stage_q]] elif _controllers[controller_type][0] == CascadedFieldOrientedController: if type(environment.action_space) is Box: stage_d = stages[0][0] stage_q = stages[0][1] - if 'torque' not in controller_kwargs['ref_states']: + if "torque" not in controller_kwargs["ref_states"]: overlaid = stages[1] - p_gain_d = mp['l_d'] / (1.5 * environment.physical_system.tau * a) / u_sd_lim * i_sd_lim - i_gain_d = p_gain_d / (1.5 * environment.physical_system.tau * a ** 2) + p_gain_d = mp["l_d"] / (1.5 * environment.physical_system.tau * a) / u_sd_lim * i_sd_lim + i_gain_d = p_gain_d / (1.5 * environment.physical_system.tau * a**2) - p_gain_q = mp['l_q'] / (1.5 * environment.physical_system.tau * a) / u_sq_lim * i_sq_lim - i_gain_q = p_gain_q / (1.5 * environment.physical_system.tau * a ** 2) + p_gain_q = mp["l_q"] / (1.5 * environment.physical_system.tau * a) / u_sq_lim * i_sq_lim + i_gain_q = p_gain_q / (1.5 * environment.physical_system.tau * a**2) - stage_d['p_gain'] = stage_d.get('p_gain', p_gain_d) - stage_d['i_gain'] = stage_d.get('i_gain', i_gain_d) + stage_d["p_gain"] = stage_d.get("p_gain", p_gain_d) + stage_d["i_gain"] = stage_d.get("i_gain", i_gain_d) - stage_q['p_gain'] = stage_q.get('p_gain', p_gain_q) - stage_q['i_gain'] = stage_q.get('i_gain', i_gain_q) + stage_q["p_gain"] = stage_q.get("p_gain", p_gain_q) + stage_q["i_gain"] = stage_q.get("i_gain", i_gain_q) - if _controllers[stage_d['controller_type']][2] == PIDController: + if _controllers[stage_d["controller_type"]][2] == PIDController: d_gain_d = p_gain_d * environment.physical_system.tau - stage_d['d_gain'] = stage_d.get('d_gain', d_gain_d) + stage_d["d_gain"] = stage_d.get("d_gain", d_gain_d) - if _controllers[stage_q['controller_type']][2] == PIDController: + if _controllers[stage_q["controller_type"]][2] == PIDController: d_gain_q = p_gain_q * environment.physical_system.tau - stage_q['d_gain'] = stage_q.get('d_gain', d_gain_q) + stage_q["d_gain"] = stage_q.get("d_gain", d_gain_q) - if 'torque' not in controller_kwargs['ref_states'] and \ - _controllers[overlaid[0]['controller_type']][1] == ContinuousController: + if ( + "torque" not in controller_kwargs["ref_states"] + and _controllers[overlaid[0]["controller_type"]][1] == ContinuousController + ): t_n = p_gain_d / i_gain_d j_total = environment.physical_system.mechanical_load.j_total - p_gain = j_total / (a ** 2 * t_n) / torque_lim * omega_lim + p_gain = j_total / (a**2 * t_n) / torque_lim * omega_lim i_gain = p_gain / (a * t_n) - overlaid[0]['p_gain'] = overlaid[0].get('p_gain', p_gain) - overlaid[0]['i_gain'] = overlaid[0].get('i_gain', i_gain) + overlaid[0]["p_gain"] = overlaid[0].get("p_gain", p_gain) + overlaid[0]["i_gain"] = overlaid[0].get("i_gain", i_gain) - if _controllers[overlaid[0]['controller_type']][2] == PIDController: + if _controllers[overlaid[0]["controller_type"]][2] == PIDController: d_gain = p_gain * environment.physical_system.tau - overlaid[0]['d_gain'] = overlaid[0].get('d_gain', d_gain) + overlaid[0]["d_gain"] = overlaid[0].get("d_gain", d_gain) stages = [[stage_d, stage_q], overlaid] @@ -469,81 +541,87 @@ def automated_gain(environment, stages, controller_type, _controllers, **control stages = [[stage_d, stage_q]] else: - if 'omega' in ref_states and _controllers[stages[3][0]['controller_type']][1] == ContinuousController: - - p_gain = environment.physical_system.mechanical_load.j_total / ( - 1.5 * a ** 2 * mp['p'] * np.abs(mp['l_d'] - mp['l_q'])) / i_sq_lim * omega_lim + if ( + "omega" in ref_states + and _controllers[stages[3][0]["controller_type"]][1] == ContinuousController + ): + p_gain = ( + environment.physical_system.mechanical_load.j_total + / (1.5 * a**2 * mp["p"] * np.abs(mp["l_d"] - mp["l_q"])) + / i_sq_lim + * omega_lim + ) i_gain = p_gain / (1.5 * environment.physical_system.tau * a) - stages[3][0]['p_gain'] = stages[3][0].get('p_gain', p_gain) - stages[3][0]['i_gain'] = stages[3][0].get('i_gain', i_gain) + stages[3][0]["p_gain"] = stages[3][0].get("p_gain", p_gain) + stages[3][0]["i_gain"] = stages[3][0].get("i_gain", i_gain) - if _controllers[stages[3][0]['controller_type']][2] == PIDController: + if _controllers[stages[3][0]["controller_type"]][2] == PIDController: d_gain = p_gain * environment.physical_system.tau - stages[3][0]['d_gain'] = stages[3][0].get('d_gain', d_gain) + stages[3][0]["d_gain"] = stages[3][0].get("d_gain", d_gain) elif _controllers[controller_type][0] == InductionMotorFieldOrientedController: - - mp['l_s'] = mp['l_m'] + mp['l_sigs'] - mp['l_r'] = mp['l_m'] + mp['l_sigr'] - sigma = (mp['l_s'] * mp['l_r'] - mp['l_m'] ** 2) / (mp['l_s'] * mp['l_r']) - tau_sigma = (sigma * mp['l_s']) / (mp['r_s'] + mp['r_r'] * mp['l_m'] ** 2 / mp['l_r'] ** 2) - tau_r = mp['l_r'] / mp['r_r'] + mp["l_s"] = mp["l_m"] + mp["l_sigs"] + mp["l_r"] = mp["l_m"] + mp["l_sigr"] + sigma = (mp["l_s"] * mp["l_r"] - mp["l_m"] ** 2) / (mp["l_s"] * mp["l_r"]) + tau_sigma = (sigma * mp["l_s"]) / (mp["r_s"] + mp["r_r"] * mp["l_m"] ** 2 / mp["l_r"] ** 2) + tau_r = mp["l_r"] / mp["r_r"] p_gain = tau_r / tau_sigma i_gain = p_gain / tau_sigma - stages[0][0]['p_gain'] = stages[0][0].get('p_gain', p_gain) - stages[0][0]['i_gain'] = stages[0][0].get('i_gain', i_gain) - stages[0][1]['p_gain'] = stages[0][1].get('p_gain', p_gain) - stages[0][1]['i_gain'] = stages[0][1].get('i_gain', i_gain) + stages[0][0]["p_gain"] = stages[0][0].get("p_gain", p_gain) + stages[0][0]["i_gain"] = stages[0][0].get("i_gain", i_gain) + stages[0][1]["p_gain"] = stages[0][1].get("p_gain", p_gain) + stages[0][1]["i_gain"] = stages[0][1].get("i_gain", i_gain) - if _controllers[stages[0][0]['controller_type']][2] == PIDController: + if _controllers[stages[0][0]["controller_type"]][2] == PIDController: d_gain = p_gain * tau_sigma - stages[0][0]['d_gain'] = stages[0][0].get('d_gain', d_gain) + stages[0][0]["d_gain"] = stages[0][0].get("d_gain", d_gain) - if _controllers[stages[0][1]['controller_type']][2] == PIDController: + if _controllers[stages[0][1]["controller_type"]][2] == PIDController: d_gain = p_gain * tau_sigma - stages[0][1]['d_gain'] = stages[0][1].get('d_gain', d_gain) + stages[0][1]["d_gain"] = stages[0][1].get("d_gain", d_gain) elif _controllers[controller_type][0] == InductionMotorCascadedFieldOrientedController: - - if 'torque' not in controller_kwargs['ref_states']: + if "torque" not in controller_kwargs["ref_states"]: overlaid = stages[1] - mp['l_s'] = mp['l_m'] + mp['l_sigs'] - mp['l_r'] = mp['l_m'] + mp['l_sigr'] - sigma = (mp['l_s'] * mp['l_r'] - mp['l_m'] ** 2) / (mp['l_s'] * mp['l_r']) - tau_sigma = (sigma * mp['l_s']) / (mp['r_s'] + mp['r_r'] * mp['l_m'] ** 2 / mp['l_r'] ** 2) - tau_r = mp['l_r'] / mp['r_r'] + mp["l_s"] = mp["l_m"] + mp["l_sigs"] + mp["l_r"] = mp["l_m"] + mp["l_sigr"] + sigma = (mp["l_s"] * mp["l_r"] - mp["l_m"] ** 2) / (mp["l_s"] * mp["l_r"]) + tau_sigma = (sigma * mp["l_s"]) / (mp["r_s"] + mp["r_r"] * mp["l_m"] ** 2 / mp["l_r"] ** 2) + tau_r = mp["l_r"] / mp["r_r"] p_gain = tau_r / tau_sigma i_gain = p_gain / tau_sigma - stages[0][0]['p_gain'] = stages[0][0].get('p_gain', p_gain) - stages[0][0]['i_gain'] = stages[0][0].get('i_gain', i_gain) - stages[0][1]['p_gain'] = stages[0][1].get('p_gain', p_gain) - stages[0][1]['i_gain'] = stages[0][1].get('i_gain', i_gain) + stages[0][0]["p_gain"] = stages[0][0].get("p_gain", p_gain) + stages[0][0]["i_gain"] = stages[0][0].get("i_gain", i_gain) + stages[0][1]["p_gain"] = stages[0][1].get("p_gain", p_gain) + stages[0][1]["i_gain"] = stages[0][1].get("i_gain", i_gain) - if _controllers[stages[0][0]['controller_type']][2] == PIDController: + if _controllers[stages[0][0]["controller_type"]][2] == PIDController: d_gain = p_gain * tau_sigma - stages[0][0]['d_gain'] = stages[0][0].get('d_gain', d_gain) + stages[0][0]["d_gain"] = stages[0][0].get("d_gain", d_gain) - if _controllers[stages[0][1]['controller_type']][2] == PIDController: + if _controllers[stages[0][1]["controller_type"]][2] == PIDController: d_gain = p_gain * tau_sigma - stages[0][1]['d_gain'] = stages[0][1].get('d_gain', d_gain) + stages[0][1]["d_gain"] = stages[0][1].get("d_gain", d_gain) - if 'torque' not in controller_kwargs['ref_states'] and \ - _controllers[overlaid[0]['controller_type']][1] == ContinuousController: + if ( + "torque" not in controller_kwargs["ref_states"] + and _controllers[overlaid[0]["controller_type"]][1] == ContinuousController + ): t_n = p_gain / i_gain j_total = environment.physical_system.mechanical_load.j_total - p_gain = j_total / (a ** 2 * t_n) / torque_lim * omega_lim + p_gain = j_total / (a**2 * t_n) / torque_lim * omega_lim i_gain = p_gain / (a * t_n) - overlaid[0]['p_gain'] = overlaid[0].get('p_gain', p_gain) - overlaid[0]['i_gain'] = overlaid[0].get('i_gain', i_gain) + overlaid[0]["p_gain"] = overlaid[0].get("p_gain", p_gain) + overlaid[0]["i_gain"] = overlaid[0].get("i_gain", i_gain) - if _controllers[overlaid[0]['controller_type']][2] == PIDController: + if _controllers[overlaid[0]["controller_type"]][2] == PIDController: d_gain = p_gain * environment.physical_system.tau - overlaid[0]['d_gain'] = overlaid[0].get('d_gain', d_gain) + overlaid[0]["d_gain"] = overlaid[0].get("d_gain", d_gain) stages = [stages[0], overlaid] diff --git a/examples/classic_controllers/classic_controllers_dc_motor_example.py b/examples/classic_controllers/classic_controllers_dc_motor_example.py index 0ac6ef4d..85a0ddfc 100644 --- a/examples/classic_controllers/classic_controllers_dc_motor_example.py +++ b/examples/classic_controllers/classic_controllers_dc_motor_example.py @@ -1,10 +1,12 @@ from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot + import gym_electric_motor as gem +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from gym_electric_motor.visualization import MotorDashboard +from gym_electric_motor.visualization.render_modes import RenderMode -if __name__ == '__main__': - +if __name__ == "__main__": """ motor type: 'PermExDc' Permanently Excited DC Motor 'ExtExDc' Externally Excited MC Motor @@ -19,26 +21,29 @@ 'Finite' Discrete Action Space """ - motor_type = 'PermExDc' - control_type = 'TC' - action_type = 'Cont' + """ + motor_type = "PermExDc" + control_type = "TC" + action_type = "Cont" + """ + - motor = action_type + '-' + control_type + '-' + motor_type + '-v0' + motor = Motor( + MotorType.PermanentlyExcitedDcMotor, + ControlType.TorqueControl, + ActionType.Continuous, + ) - if motor_type in ['PermExDc', 'SeriesDc']: - states = ['omega', 'torque', 'i', 'u'] - elif motor_type == 'ShuntDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u'] - elif motor_type == 'ExtExDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u_a', 'u_e'] - else: - raise KeyError(motor_type + ' is not available') # definition of the plotted variables - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states] + external_ref_plots = [ExternallyReferencedStatePlot(state) for state in motor.states()] + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots, render_mode=RenderMode.Figure) # initialize the gym-electric-motor environment - env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots), render_mode="figure_once") + env = gem.make( + motor.env_id(), + visualization=motor_dashboard, + ) """ initialize the controller @@ -50,10 +55,10 @@ 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(seed = None) + (state, reference), _ = env.reset(seed=None) # simulate the environment for i in range(10001): action = controller.control(state, reference) @@ -62,4 +67,5 @@ env.reset() controller.reset() + motor_dashboard.show_and_hold() env.close() diff --git a/examples/classic_controllers/classic_controllers_ind_motor_example.py b/examples/classic_controllers/classic_controllers_ind_motor_example.py index 4370dc5b..074a1f21 100644 --- a/examples/classic_controllers/classic_controllers_ind_motor_example.py +++ b/examples/classic_controllers/classic_controllers_ind_motor_example.py @@ -1,13 +1,14 @@ +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot from external_plot import ExternalPlot import gym_electric_motor as gem + from gym_electric_motor.visualization import MotorDashboard from gym_electric_motor.physical_system_wrappers import FluxObserver import numpy as np -if __name__ == '__main__': - +if __name__ == "__main__": """ motor type: 'SCIM' Squirrel Cage Induction Motor @@ -17,22 +18,34 @@ action_type: 'AbcCont' Continuous Action Space """ + """ + motor_type = "SCIM" + control_type = "TC" + action_type = "Cont" + """ - motor_type = 'SCIM' - control_type = 'TC' - action_type = 'Cont' - - env_id = action_type + '-' + control_type + '-' + motor_type + '-v0' + motor = Motor( + MotorType.SquirrelCageInductionMotor, + ControlType.TorqueControl, + ActionType.Continuous, + ) # definition of the plotted variables - states = ['omega', 'torque', 'i_sd', 'i_sq', 'u_sd', 'u_sq'] - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states] - external_plot = [ExternalPlot(referenced=control_type != 'CC'), ExternalPlot(min=-np.pi, max=np.pi)] + states = ["omega", "torque", "i_sd", "i_sq", "u_sd", "u_sq"] + external_ref_plots = [ExternallyReferencedStatePlot(state) for state in motor.states()] + external_plot = [ + ExternalPlot(referenced= ControlType.TorqueControl != "CC"), + ExternalPlot(min=-np.pi, max=np.pi), + ] external_ref_plots += external_plot + motor_dashboard = MotorDashboard(state_plots=("omega", "psi_abs", "psi_angle")) # initialize the gym-electric-motor environment - env = gem.make(env_id, physical_system_wrappers=(FluxObserver(),), - visualization=MotorDashboard(state_plots=('omega', 'psi_abs', 'psi_angle'))) + env = gem.make( + motor.env_id(), + physical_system_wrappers=(FluxObserver(),), + visualization=MotorDashboard(), + ) """ initialize the controller @@ -55,4 +68,5 @@ if terminated: env.reset() controller.reset() + motor_dashboard.show_and_hold() env.close() diff --git a/examples/classic_controllers/classic_controllers_synch_motor_example.py b/examples/classic_controllers/classic_controllers_synch_motor_example.py index 7fb5953b..4a367e0a 100644 --- a/examples/classic_controllers/classic_controllers_synch_motor_example.py +++ b/examples/classic_controllers/classic_controllers_synch_motor_example.py @@ -1,11 +1,11 @@ +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot import gym_electric_motor as gem from gym_electric_motor.visualization import MotorDashboard -if __name__ == '__main__': - +if __name__ == "__main__": """ motor type: 'PMSM' Permanent Magnet Synchronous Motor 'SynRM' Synchronous Reluctance Motor @@ -17,19 +17,29 @@ action_type: 'Cont' Continuous Action Space in ABC-Coordinates 'Finite' Discrete Action Space """ + + """ + motor_type = "PMSM" + control_type = "TC" + action_type = "Cont" + """ - motor_type = 'PMSM' - control_type = 'TC' - action_type = 'Cont' - - env_id = action_type + '-' + control_type + '-' + motor_type + '-v0' - + motor = Motor( + MotorType.PermanentMagnetSynchronousMotor, + ControlType.TorqueControl, + ActionType.Continuous + ) # definition of the plotted variables - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in ['omega', 'torque', 'i_sd', 'i_sq', 'u_sd', 'u_sq']] + external_ref_plots = [ + ExternallyReferencedStatePlot(state) for state in ["omega", "torque", "i_sd", "i_sq", "u_sd", "u_sq"] + ] + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots) # initialize the gym-electric-motor environment - env = gem.make(env_id, visualization=MotorDashboard(additional_plots=external_ref_plots)) + env = gem.make( + motor.env_id(), visualization=motor_dashboard + ) """ initialize the controller @@ -48,7 +58,9 @@ """ - controller = Controller.make(env, external_ref_plots=external_ref_plots, torque_control='analytical') + controller = Controller.make( + env, external_ref_plots=external_ref_plots, torque_control="analytical" + ) (state, reference), _ = env.reset() @@ -59,5 +71,6 @@ if terminated: env.reset() controller.reset() - + + motor_dashboard.show_and_hold() env.close() diff --git a/examples/classic_controllers/controllers/cascaded_controller.py b/examples/classic_controllers/controllers/cascaded_controller.py index e526060e..e5b8e968 100644 --- a/examples/classic_controllers/controllers/cascaded_controller.py +++ b/examples/classic_controllers/controllers/cascaded_controller.py @@ -1,51 +1,65 @@ -from .continuous_controller import ContinuousController +import numpy as np from gymnasium.spaces import Box, Discrete, MultiDiscrete + from gym_electric_motor.physical_systems import DcExternallyExcitedMotor -from .plot_external_data import plot -import numpy as np +from .continuous_controller import ContinuousController +from .plot_external_data import plot class CascadedController: """ - This class is used for cascaded torque and speed control of all dc motor environments. Each stage can contain - continuous or discrete controllers. For the externally excited dc motor an additional controller is used for - the excitation current. The calculated reference values of the intermediate stages can be inserted into the - plots. + This class is used for cascaded torque and speed control of all dc motor environments. Each stage can contain + continuous or discrete controllers. For the externally excited dc motor an additional controller is used for + the excitation current. The calculated reference values of the intermediate stages can be inserted into the + plots. """ - def __init__(self, environment, stages, _controllers, visualization, ref_states, external_ref_plots=(), **controller_kwargs): - + 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 - self.state_names = environment.state_names - - self.i_e_idx = environment.physical_system.CURRENTS_IDX[-1] - self.i_a_idx = environment.physical_system.CURRENTS_IDX[0] - self.u_idx = environment.physical_system.VOLTAGES_IDX[-1] - self.omega_idx = environment.state_names.index('omega') - self.torque_idx = environment.state_names.index('torque') - self.ref_idx = np.where(ref_states != 'i_e')[0][0] - self.ref_state_idx = [self.i_a_idx, environment.state_names.index(ref_states[self.ref_idx])] - - self.limit = environment.physical_system.limits[environment.state_filter] - self.nominal_values = environment.physical_system.nominal_state[environment.state_filter] - - self.control_e = isinstance(environment.physical_system.electrical_motor, DcExternallyExcitedMotor) + self.state_space = environment.unwrapped.physical_system.state_space + self.state_names = environment.unwrapped.state_names + + self.i_e_idx = environment.unwrapped.physical_system.CURRENTS_IDX[-1] + self.i_a_idx = environment.unwrapped.physical_system.CURRENTS_IDX[0] + self.u_idx = environment.unwrapped.physical_system.VOLTAGES_IDX[-1] + self.omega_idx = environment.unwrapped.state_names.index("omega") + self.torque_idx = environment.unwrapped.state_names.index("torque") + self.ref_idx = np.where(ref_states != "i_e")[0][0] + self.ref_state_idx = [ + self.i_a_idx, + environment.unwrapped.state_names.index(ref_states[self.ref_idx]), + ] + + self.limit = environment.unwrapped.physical_system.limits[environment.unwrapped.state_filter] + self.nominal_values = environment.unwrapped.physical_system.nominal_state[environment.unwrapped.state_filter] + + self.control_e = isinstance(environment.unwrapped.physical_system.electrical_motor, DcExternallyExcitedMotor) self.control_omega = 0 - mp = environment.physical_system.electrical_motor.motor_parameter - self.psi_e = mp.get('psie_e', False) - self.l_e = mp.get('l_e_prime', False) - self.r_e = mp.get('r_e', None) - self.r_a = mp.get('r_a', None) + mp = environment.unwrapped.physical_system.electrical_motor.motor_parameter + self.psi_e = mp.get("psie_e", False) + self.l_e = mp.get("l_e_prime", False) + self.r_e = mp.get("r_e", None) + self.r_a = mp.get("r_a", None) # Set the action limits if type(self.action_space) is Box: self.action_limit_low = self.action_space.low[0] * self.nominal_values[self.u_idx] / self.limit[self.u_idx] - self.action_limit_high = self.action_space.high[0] * self.nominal_values[self.u_idx] / self.limit[self.u_idx] + self.action_limit_high = ( + self.action_space.high[0] * self.nominal_values[self.u_idx] / self.limit[self.u_idx] + ) # Set the state limits self.state_limit_low = self.state_space.low * self.nominal_values / self.limit @@ -53,8 +67,8 @@ def __init__(self, environment, stages, _controllers, visualization, ref_states, # Initialize i_e Controller if needed if self.control_e: - assert len(stages) == 2, 'Controller design is incomplete' - self.ref_e_idx = False if 'i_e' not in ref_states else np.where(ref_states=='i_e')[0][0] + assert len(stages) == 2, "Controller design is incomplete" + self.ref_e_idx = False if "i_e" not in ref_states else np.where(ref_states == "i_e")[0][0] self.control_e_idx = 1 if self.omega_idx in self.ref_state_idx: @@ -62,84 +76,108 @@ def __init__(self, environment, stages, _controllers, visualization, ref_states, self.control_omega = 1 self.ref_state_idx.append(self.i_e_idx) - self.controller_e = _controllers[stages[1][0]['controller_type']][1].make(environment, stages[1][0], - _controllers, control_e=True, - **controller_kwargs) + self.controller_e = _controllers[stages[1][0]["controller_type"]][1].make( + environment, + stages[1][0], + _controllers, + control_e=True, + **controller_kwargs, + ) stages = stages[0] - u_e_idx = self.state_names.index('u_e') + u_e_idx = self.state_names.index("u_e") # Set action limit for u_e if type(self.action_space) is Box: self.action_e_limit_low = self.action_space.low[1] * self.nominal_values[u_e_idx] / self.limit[u_e_idx] - self.action_e_limit_high = self.action_space.high[1] * self.nominal_values[u_e_idx] / self.limit[u_e_idx] + self.action_e_limit_high = ( + self.action_space.high[1] * self.nominal_values[u_e_idx] / self.limit[u_e_idx] + ) else: self.control_e_idx = 0 - assert len(ref_states) <= 1, 'Too many referenced states' + assert len(ref_states) <= 1, "Too many referenced states" # Check of the stages are using continuous or discrete controller - self.stage_type = [_controllers[stage['controller_type']][1] == ContinuousController for stage in stages] + self.stage_type = [_controllers[stage["controller_type"]][1] == ContinuousController for stage in stages] # Initialize Controller stages self.controller_stages = [ - _controllers[stage['controller_type']][1].make(environment, stage, _controllers, cascaded=stages.index(stage) != 0) for - stage in stages] + _controllers[stage["controller_type"]][1].make( + environment, stage, _controllers, cascaded=stages.index(stage) != 0 + ) + for stage in stages + ] # Set up the plots self.external_ref_plots = external_ref_plots - internal_refs = np.array([environment.state_names[i] for i in self.ref_state_idx]) + internal_refs = np.array([environment.unwrapped.state_names[i] for i in self.ref_state_idx]) ref_states_plotted = np.unique(np.append(ref_states, internal_refs)) for external_plots in self.external_ref_plots: external_plots.set_reference(ref_states_plotted) - assert type(self.action_space) is Box or not self.stage_type[0], 'No suitable inner controller' - assert type(self.action_space) in [Discrete, MultiDiscrete] or self.stage_type[ - 0], 'No suitable inner controller' + assert type(self.action_space) is Box or not self.stage_type[0], "No suitable inner controller" + assert ( + type(self.action_space) in [Discrete, MultiDiscrete] or self.stage_type[0] + ), "No suitable inner controller" self.ref = np.zeros(len(self.controller_stages) + self.control_e_idx + self.control_omega) def control(self, state, reference): """ - Main method that is called by the user to calculate the manipulated variable. + Main method that is called by the user to calculate the manipulated variable. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ # Set the reference - self.ref[-1-self.control_e_idx] = reference[self.ref_idx] + self.ref[-1 - self.control_e_idx] = reference[self.ref_idx] # Iterate through the high-level controller stages - for i in range(len(self.controller_stages) - 1, 0 + self.control_e_idx - self.control_omega, -1): + for i in range( + len(self.controller_stages) - 1, + 0 + self.control_e_idx - self.control_omega, + -1, + ): # Set the indices ref_idx = i - 1 + self.control_omega state_idx = self.ref_state_idx[ref_idx] # Calculate reference for lower stage - self.ref[ref_idx] = self.controller_stages[i].control( - state[state_idx], self.ref[ref_idx + 1]) + self.ref[ref_idx] = self.controller_stages[i].control(state[state_idx], self.ref[ref_idx + 1]) # Check limits and integrate - if (self.state_limit_low[state_idx] <= self.ref[ref_idx] <= self.state_limit_high[state_idx]) and self.stage_type[i]: + if ( + self.state_limit_low[state_idx] <= self.ref[ref_idx] <= self.state_limit_high[state_idx] + ) and self.stage_type[i]: self.controller_stages[i].integrate(state[self.ref_state_idx[i + self.control_omega]], reference[0]) elif self.stage_type[i]: - self.ref[ref_idx] = np.clip(self.ref[ref_idx], self.state_limit_low[state_idx], - self.state_limit_high[state_idx]) + self.ref[ref_idx] = np.clip( + self.ref[ref_idx], + self.state_limit_low[state_idx], + self.state_limit_high[state_idx], + ) # Calculate optimal i_a and i_e for externally excited dc motor if self.control_e: i_e = np.clip( - np.power(self.r_a * (self.ref[1] * self.limit[self.torque_idx]) ** 2 / (self.r_e * self.l_e ** 2), - 1 / 4), self.state_space.low[self.i_e_idx] * self.limit[self.i_e_idx], - self.state_space.high[self.i_e_idx] * self.limit[self.i_e_idx]) - i_a = np.clip(self.ref[1] * self.limit[self.torque_idx] / (self.l_e * i_e), - self.state_space.low[self.i_a_idx] * self.limit[self.i_a_idx], - self.state_space.high[self.i_a_idx] * self.limit[self.i_a_idx]) + np.power( + self.r_a * (self.ref[1] * self.limit[self.torque_idx]) ** 2 / (self.r_e * self.l_e**2), + 1 / 4, + ), + self.state_space.low[self.i_e_idx] * self.limit[self.i_e_idx], + self.state_space.high[self.i_e_idx] * self.limit[self.i_e_idx], + ) + i_a = np.clip( + self.ref[1] * self.limit[self.torque_idx] / (self.l_e * i_e), + self.state_space.low[self.i_a_idx] * self.limit[self.i_a_idx], + self.state_space.high[self.i_a_idx] * self.limit[self.i_a_idx], + ) self.ref[-1] = i_e / self.limit[self.i_e_idx] self.ref[0] = i_a / self.limit[self.i_a_idx] @@ -148,7 +186,7 @@ def control(self, state, reference): # Check if stage is continuous if self.stage_type[0]: - action += self.feedforward(state) # EMF compensation + action += self.feedforward(state) # EMF compensation # Check limits and integrate if self.action_limit_low <= action <= self.action_limit_high: @@ -170,18 +208,25 @@ def control(self, state, reference): self.controller_e.integrate(state[self.i_e_idx], self.ref[-1]) action = np.clip(action, self.action_e_limit_low, self.action_e_limit_high) else: - action = np.array([action, action_u_e], dtype='object') + action = np.array([action, action_u_e], dtype="object") 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()) + plot( + external_reference_plots=self.external_ref_plots, + state_names=self.state_names, + visualization=self.visualization, + external_data=self.get_plot_data(), + ) return action def feedforward(self, state): # EMF compensation - psi_e = max(self.psi_e or self.l_e * state[self.i_e_idx] * self.nominal_values[self.i_e_idx], 1e-6) + psi_e = max( + self.psi_e or self.l_e * state[self.i_e_idx] * self.nominal_values[self.i_e_idx], + 1e-6, + ) return (state[self.omega_idx] * self.nominal_values[self.omega_idx] * psi_e) / self.nominal_values[self.u_idx] def get_plot_data(self): diff --git a/examples/classic_controllers/controllers/cascaded_foc_controller.py b/examples/classic_controllers/controllers/cascaded_foc_controller.py index 80c78013..6b63fb49 100644 --- a/examples/classic_controllers/controllers/cascaded_foc_controller.py +++ b/examples/classic_controllers/controllers/cascaded_foc_controller.py @@ -7,62 +7,78 @@ class CascadedFieldOrientedController: """ - This controller is used for torque or speed control of synchronous motors. The controller consists of a field - oriented controller for current control, an efficiency-optimized torque controller and an optional speed - controller. The current control is equivalent to the current control of the FieldOrientedController. The torque - controller is based on the maximum torque per current (MTPC) control strategy in the voltage control range and - the maximum torque per flux (MTPF) control strategy with an additional modulation controller in the flux - weakening range. The speed controller is designed as a PI-controller by default. + This controller is used for torque or speed control of synchronous motors. The controller consists of a field + oriented controller for current control, an efficiency-optimized torque controller and an optional speed + controller. The current control is equivalent to the current control of the FieldOrientedController. The torque + controller is based on the maximum torque per current (MTPC) control strategy in the voltage control range and + the maximum torque per flux (MTPF) control strategy with an additional modulation controller in the flux + weakening range. The speed controller is designed as a PI-controller by default. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), plot_torque=True, - plot_modulation=False, update_interval=1000, torque_control='interpolate', **controller_kwargs): + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + plot_torque=True, + plot_modulation=False, + update_interval=1000, + torque_control="interpolate", + **controller_kwargs, + ): t32 = environment.physical_system.electrical_motor.t_32 q = environment.physical_system.electrical_motor.q - self.backward_transformation = (lambda quantities, eps: t32(q(quantities, eps))) + self.backward_transformation = lambda quantities, eps: t32(q(quantities, eps)) self.tau = environment.physical_system.tau self.action_space = environment.action_space self.state_space = environment.physical_system.state_space self.state_names = environment.state_names - self.i_sd_idx = environment.state_names.index('i_sd') - self.i_sq_idx = environment.state_names.index('i_sq') - self.u_sd_idx = environment.state_names.index('u_sd') - self.u_sq_idx = environment.state_names.index('u_sq') - self.u_a_idx = environment.state_names.index('u_a') - self.u_b_idx = environment.state_names.index('u_b') - self.u_c_idx = environment.state_names.index('u_c') - self.omega_idx = environment.state_names.index('omega') - self.eps_idx = environment.state_names.index('epsilon') - self.torque_idx = environment.state_names.index('torque') + self.i_sd_idx = environment.state_names.index("i_sd") + self.i_sq_idx = environment.state_names.index("i_sq") + self.u_sd_idx = environment.state_names.index("u_sd") + self.u_sq_idx = environment.state_names.index("u_sq") + self.u_a_idx = environment.state_names.index("u_a") + self.u_b_idx = environment.state_names.index("u_b") + self.u_c_idx = environment.state_names.index("u_c") + self.omega_idx = environment.state_names.index("omega") + self.eps_idx = environment.state_names.index("epsilon") + self.torque_idx = environment.state_names.index("torque") self.external_ref_plots = external_ref_plots - self.torque_control = 'torque' in ref_states or 'omega' in ref_states - self.current_control = 'i_sd' in ref_states - self.omega_control = 'omega' in ref_states + self.torque_control = "torque" in ref_states or "omega" in ref_states + self.current_control = "i_sd" in ref_states + self.omega_control = "omega" in ref_states if self.current_control: - self.ref_d_idx = np.where(ref_states == 'i_sd')[0][0] - self.ref_idx = np.where(ref_states != 'i_sd')[0][0] + self.ref_d_idx = np.where(ref_states == "i_sd")[0][0] + self.ref_idx = np.where(ref_states != "i_sd")[0][0] - self.omega_control = 'omega' in ref_states and type(environment) + self.omega_control = "omega" in ref_states and type(environment) self.has_cont_action_space = type(self.action_space) is Box self.limit = environment.physical_system.limits self.nominal_values = environment.physical_system.nominal_state self.mp = environment.physical_system.electrical_motor.motor_parameter - self.psi_p = self.mp.get('psi_p', 0) + self.psi_p = self.mp.get("psi_p", 0) self.dead_time = 0.5 - self.decoupling = controller_kwargs.get('decoupling', True) + self.decoupling = controller_kwargs.get("decoupling", True) self.ref_state_idx = [self.i_sq_idx, self.i_sd_idx] # Initialize torque controller if self.torque_control: self.ref_state_idx.append(self.torque_idx) - self.torque_controller = TorqueToCurrentConversion(environment, plot_torque, plot_modulation, - update_interval, torque_control) + self.torque_controller = TorqueToCurrentConversion( + environment, + plot_torque, + plot_modulation, + update_interval, + torque_control, + ) if self.omega_control: self.ref_state_idx.append(self.omega_idx) @@ -70,73 +86,121 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_ # Initialize continuous controller stages if self.has_cont_action_space: - assert len(stages[0]) == 2, 'Number of stages not correct' - self.d_controller = _controllers[stages[0][0]['controller_type']][1].make( - environment, stages[0][0], _controllers, **controller_kwargs) - self.q_controller = _controllers[stages[0][1]['controller_type']][1].make( - environment, stages[0][1], _controllers, **controller_kwargs) + assert len(stages[0]) == 2, "Number of stages not correct" + self.d_controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], _controllers, **controller_kwargs + ) + self.q_controller = _controllers[stages[0][1]["controller_type"]][1].make( + environment, stages[0][1], _controllers, **controller_kwargs + ) [self.u_sq_0, self.u_sd_0] = [0, 0] if self.omega_control: - self.overlaid_controller = [_controllers[stages[1][i]['controller_type']][1].make( - environment, stages[1][i], _controllers, cascaded=True, **controller_kwargs) for i in range(0, len(stages[1]))] - self.overlaid_type = [_controllers[stages[1][i]['controller_type']][1] == ContinuousController for i in - range(0, len(stages[1]))] + self.overlaid_controller = [ + _controllers[stages[1][i]["controller_type"]][1].make( + environment, + stages[1][i], + _controllers, + cascaded=True, + **controller_kwargs, + ) + for i in range(0, len(stages[1])) + ] + self.overlaid_type = [ + _controllers[stages[1][i]["controller_type"]][1] + == ContinuousController + for i in range(0, len(stages[1])) + ] # Initialize discrete controller stages else: - if self.omega_control: - assert len(stages) == 4, 'Number of stages not correct' - self.overlaid_controller = [_controllers[stages[3][i]['controller_type']][1].make( - environment, stages[3][i], cascaded=True, **controller_kwargs) for i in range(len(stages[3]))] - self.overlaid_type = [_controllers[stages[3][i]['controller_type']][1] == ContinuousController for i in - range(len(stages[3]))] + assert len(stages) == 4, "Number of stages not correct" + self.overlaid_controller = [ + _controllers[stages[3][i]["controller_type"]][1].make( + environment, stages[3][i], cascaded=True, **controller_kwargs + ) + for i in range(len(stages[3])) + ] + self.overlaid_type = [ + _controllers[stages[3][i]["controller_type"]][1] + == ContinuousController + for i in range(len(stages[3])) + ] else: - assert len(stages) == 3, 'Number of stages not correct' - self.abc_controller = [_controllers[stages[0][0]['controller_type']][1].make( - environment, stages[i][0], _controllers, **controller_kwargs) for i in range(3)] - self.i_abc_idx = [environment.state_names.index(state) for state in ['i_a', 'i_b', 'i_c']] - - self.ref = np.zeros(len(self.ref_state_idx)) # Define array for reference values + assert len(stages) == 3, "Number of stages not correct" + self.abc_controller = [ + _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[i][0], _controllers, **controller_kwargs + ) + for i in range(3) + ] + self.i_abc_idx = [ + environment.state_names.index(state) for state in ["i_a", "i_b", "i_c"] + ] + + self.ref = np.zeros( + len(self.ref_state_idx) + ) # Define array for reference values # Set up the plots - plot_ref = np.append(np.array([environment.state_names[i] for i in self.ref_state_idx]), ref_states) + plot_ref = np.append( + np.array([environment.state_names[i] for i in self.ref_state_idx]), + ref_states, + ) for ext_ref_plot in self.external_ref_plots: ext_ref_plot.set_reference(plot_ref) def control(self, state, reference): """ - Main method that is called by the user to calculate the manipulated variable. + Main method that is called by the user to calculate the manipulated variable. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ self.ref[-1] = reference[self.ref_idx] # Set the reference - epsilon_d = state[self.eps_idx] * self.limit[self.eps_idx] + self.dead_time * self.tau * state[self.omega_idx] * \ - self.limit[self.omega_idx] * self.mp['p'] # Calculate delta epsilon + epsilon_d = ( + state[self.eps_idx] * self.limit[self.eps_idx] + + self.dead_time + * self.tau + * state[self.omega_idx] + * self.limit[self.omega_idx] + * self.mp["p"] + ) # Calculate delta epsilon # Iterate through high-level controller if self.omega_control: for i in range(len(self.overlaid_controller) + 1, 1, -1): # Calculate reference - self.ref[i] = self.overlaid_controller[i-2].control(state[self.ref_state_idx[i + 1]], self.ref[i + 1]) + self.ref[i] = self.overlaid_controller[i - 2].control( + state[self.ref_state_idx[i + 1]], self.ref[i + 1] + ) # Check limits and integrate - if (0.85 * self.state_space.low[self.ref_state_idx[i]] <= self.ref[i] <= 0.85 * - self.state_space.high[self.ref_state_idx[i]]) and self.overlaid_type[i - 2]: - self.overlaid_controller[i - 2].integrate(state[self.ref_state_idx[i + 1]], self.ref[i + 1]) + if ( + 0.85 * self.state_space.low[self.ref_state_idx[i]] + <= self.ref[i] + <= 0.85 * self.state_space.high[self.ref_state_idx[i]] + ) and self.overlaid_type[i - 2]: + self.overlaid_controller[i - 2].integrate( + state[self.ref_state_idx[i + 1]], self.ref[i + 1] + ) else: - self.ref[i] = np.clip(self.ref[i], self.nominal_values[self.ref_state_idx[i]] / self.limit[ - self.ref_state_idx[i]] * self.state_space.low[self.ref_state_idx[i]], - self.nominal_values[self.ref_state_idx[i]] / self.limit[ - self.ref_state_idx[i]] * self.state_space.high[self.ref_state_idx[i]]) + self.ref[i] = np.clip( + self.ref[i], + self.nominal_values[self.ref_state_idx[i]] + / self.limit[self.ref_state_idx[i]] + * self.state_space.low[self.ref_state_idx[i]], + self.nominal_values[self.ref_state_idx[i]] + / self.limit[self.ref_state_idx[i]] + * self.state_space.high[self.ref_state_idx[i]], + ) # Calculate reference values for i_d and i_q if self.torque_control: @@ -145,35 +209,65 @@ def control(self, state, reference): # Calculate action for continuous action space if self.has_cont_action_space: - # Decouple the two current components if self.decoupling: - self.u_sd_0 = -state[self.omega_idx] * self.mp['p'] * self.mp['l_q'] * state[self.i_sq_idx]\ - * self.limit[self.i_sq_idx] / self.limit[self.u_sd_idx] * self.limit[self.omega_idx] - self.u_sq_0 = state[self.omega_idx] * self.mp['p'] * ( - state[self.i_sd_idx] * self.mp['l_d'] * self.limit[self.u_sd_idx] + self.psi_p) / self.limit[ - self.u_sq_idx] * self.limit[self.omega_idx] + self.u_sd_0 = ( + -state[self.omega_idx] + * self.mp["p"] + * self.mp["l_q"] + * state[self.i_sq_idx] + * self.limit[self.i_sq_idx] + / self.limit[self.u_sd_idx] + * self.limit[self.omega_idx] + ) + self.u_sq_0 = ( + state[self.omega_idx] + * self.mp["p"] + * ( + state[self.i_sd_idx] + * self.mp["l_d"] + * self.limit[self.u_sd_idx] + + self.psi_p + ) + / self.limit[self.u_sq_idx] + * self.limit[self.omega_idx] + ) # Calculate action for u_sd if self.torque_control: - u_sd = self.d_controller.control(state[self.i_sd_idx], self.ref[1]) + self.u_sd_0 + u_sd = ( + self.d_controller.control(state[self.i_sd_idx], self.ref[1]) + + self.u_sd_0 + ) else: - u_sd = self.d_controller.control(state[self.i_sd_idx], reference[self.ref_d_idx]) + self.u_sd_0 + u_sd = ( + self.d_controller.control( + state[self.i_sd_idx], reference[self.ref_d_idx] + ) + + self.u_sd_0 + ) # Calculate action for u_sq - u_sq = self.q_controller.control(state[self.i_sq_idx], self.ref[0]) + self.u_sq_0 + u_sq = ( + self.q_controller.control(state[self.i_sq_idx], self.ref[0]) + + self.u_sq_0 + ) # Shifting the reference potential action_temp = self.backward_transformation((u_sd, u_sq), epsilon_d) action_temp = action_temp - 0.5 * (max(action_temp) + min(action_temp)) # Check limit and integrate - action = np.clip(action_temp, self.action_space.low[0], self.action_space.high[0]) + action = np.clip( + action_temp, self.action_space.low[0], self.action_space.high[0] + ) if (action == action_temp).all(): if self.torque_control: self.d_controller.integrate(state[self.i_sd_idx], self.ref[1]) else: - self.d_controller.integrate(state[self.i_sd_idx], reference[self.ref_d_idx]) + self.d_controller.integrate( + state[self.i_sd_idx], reference[self.ref_d_idx] + ) self.q_controller.integrate(state[self.i_sq_idx], self.ref[0]) # Calculate action for discrete action space @@ -182,17 +276,25 @@ def control(self, state, reference): ref_abc = self.backward_transformation((ref, self.ref[0]), epsilon_d) action = 0 for i in range(3): - action += (2 ** (2 - i)) * self.abc_controller[i].control(state[self.i_abc_idx[i]], ref_abc[i]) + action += (2 ** (2 - i)) * self.abc_controller[i].control( + state[self.i_abc_idx[i]], ref_abc[i] + ) # Plot overlaid reference values - plot(external_reference_plots=self.external_ref_plots, state_names=self.state_names, external_data=self.get_plot_data(), - visualization=True) + plot( + external_reference_plots=self.external_ref_plots, + state_names=self.state_names, + external_data=self.get_plot_data(), + visualization=True, + ) return action def get_plot_data(self): # Getting the external data that should be plotted - return dict(ref_state=self.ref_state_idx[:-1], ref_value=self.ref[:-1], external=[]) + return dict( + ref_state=self.ref_state_idx[:-1], ref_value=self.ref[:-1], external=[] + ) def reset(self): # Reset the Controllers diff --git a/examples/classic_controllers/controllers/continuous_action_controller.py b/examples/classic_controllers/controllers/continuous_action_controller.py index 25be55ac..e58f9c7f 100644 --- a/examples/classic_controllers/controllers/continuous_action_controller.py +++ b/examples/classic_controllers/controllers/continuous_action_controller.py @@ -6,34 +6,55 @@ class ContinuousActionController: """ - This class performs a current-control for all continuous DC motor systems. By default, a PI controller is used - for current control. An EMF compensation is applied. For the externally excited dc motor, the excitation current - is also controlled. + This class performs a current-control for all continuous DC motor systems. By default, a PI controller is used + for current control. An EMF compensation is applied. For the externally excited dc motor, the excitation current + is also controlled. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), **controller_kwargs): - assert type(environment.action_space) is Box and isinstance(environment.physical_system, - DcMotorSystem), 'No suitable action space for Continuous Action Controller' + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + **controller_kwargs, + ): + assert type(environment.action_space) is Box and isinstance( + environment.physical_system, DcMotorSystem + ), "No suitable action space for Continuous Action Controller" self.action_space = environment.action_space self.state_names = environment.state_names - self.ref_idx = np.where(ref_states != 'i_e')[0][0] + self.ref_idx = np.where(ref_states != "i_e")[0][0] self.ref_state_idx = environment.state_names.index(ref_states[self.ref_idx]) self.i_idx = environment.physical_system.CURRENTS_IDX[-1] self.u_idx = environment.physical_system.VOLTAGES_IDX[-1] self.limit = environment.physical_system.limits[environment.state_filter] - self.nominal_values = environment.physical_system.nominal_state[environment.state_filter] - self.omega_idx = self.state_names.index('omega') + self.nominal_values = environment.physical_system.nominal_state[ + environment.state_filter + ] + self.omega_idx = self.state_names.index("omega") self.action = np.zeros(self.action_space.shape[0]) - self.control_e = isinstance(environment.physical_system.electrical_motor, DcExternallyExcitedMotor) + self.control_e = isinstance( + environment.physical_system.electrical_motor, DcExternallyExcitedMotor + ) mp = environment.physical_system.electrical_motor.motor_parameter - self.psi_e = mp.get('psi_e', None) - self.l_e = mp.get('l_e_prime', None) - - self.action_limit_low = self.action_space.low[0] * self.nominal_values[self.u_idx] / self.limit[self.u_idx] - self.action_limit_high = self.action_space.high[0] * self.nominal_values[self.u_idx] / self.limit[self.u_idx] + self.psi_e = mp.get("psi_e", None) + self.l_e = mp.get("l_e_prime", None) + + self.action_limit_low = ( + self.action_space.low[0] + * self.nominal_values[self.u_idx] + / self.limit[self.u_idx] + ) + self.action_limit_high = ( + self.action_space.high[0] + * self.nominal_values[self.u_idx] + / self.limit[self.u_idx] + ) self.external_ref_plots = external_ref_plots for ext_ref_plot in self.external_ref_plots: @@ -41,53 +62,75 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p # Initialize Controller if self.control_e: # Check, if a controller for i_e is needed - assert len(stages) == 2, 'Controller design is incomplete' - assert 'i_e' in ref_states, 'No reference for i_e' - self.ref_e_idx = np.where(ref_states == 'i_e')[0][0] - self.controller_e = _controllers[stages[1][0]['controller_type']][1].make(environment, stages[1][0], - _controllers, **controller_kwargs) - self.controller = _controllers[stages[0][0]['controller_type']][1].make(environment, stages[0][0], - _controllers, **controller_kwargs) - u_e_idx = self.state_names.index('u_e') - self.action_e_limit_low = self.action_space.low[1] * self.nominal_values[u_e_idx] / self.limit[u_e_idx] - self.action_e_limit_high = self.action_space.high[1] * self.nominal_values[u_e_idx] / self.limit[u_e_idx] + assert len(stages) == 2, "Controller design is incomplete" + assert "i_e" in ref_states, "No reference for i_e" + self.ref_e_idx = np.where(ref_states == "i_e")[0][0] + self.controller_e = _controllers[stages[1][0]["controller_type"]][1].make( + environment, stages[1][0], _controllers, **controller_kwargs + ) + self.controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], _controllers, **controller_kwargs + ) + u_e_idx = self.state_names.index("u_e") + self.action_e_limit_low = ( + self.action_space.low[1] + * self.nominal_values[u_e_idx] + / self.limit[u_e_idx] + ) + self.action_e_limit_high = ( + self.action_space.high[1] + * self.nominal_values[u_e_idx] + / self.limit[u_e_idx] + ) else: - if 'i_e' not in ref_states: - assert len(ref_states) <= 1, 'Too many referenced states' - self.controller = _controllers[stages[0]['controller_type']][1].make(environment, stages[0], _controllers, - **controller_kwargs) + if "i_e" not in ref_states: + assert len(ref_states) <= 1, "Too many referenced states" + self.controller = _controllers[stages[0]["controller_type"]][1].make( + environment, stages[0], _controllers, **controller_kwargs + ) def control(self, state, reference): """ - Main method that is called by the user to calculate the manipulated variable. + Main method that is called by the user to calculate the manipulated variable. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ - self.action[0] = self.controller.control(state[self.ref_state_idx], reference[self.ref_idx]) + self.feedforward( - state) # Calculate action + self.action[0] = self.controller.control( + state[self.ref_state_idx], reference[self.ref_idx] + ) + self.feedforward(state) # Calculate action # Limit the action and integrate the I-Controller if self.action_limit_low <= self.action[0] <= self.action_limit_high: - self.controller.integrate(state[self.ref_state_idx], reference[self.ref_idx]) + self.controller.integrate( + state[self.ref_state_idx], reference[self.ref_idx] + ) else: - self.action[0] = np.clip(self.action[0], self.action_limit_low, self.action_limit_high) + self.action[0] = np.clip( + self.action[0], self.action_limit_low, self.action_limit_high + ) # Check, if an i_e Controller is used if self.control_e: # Calculate action - self.action[1] = self.controller_e.control(state[self.i_idx], reference[self.ref_e_idx]) + self.action[1] = self.controller_e.control( + state[self.i_idx], reference[self.ref_e_idx] + ) # Limit the action and integrate the I-Controller if self.action_e_limit_low <= self.action[1] <= self.action_e_limit_high: - self.controller_e.integrate(state[self.i_idx], reference[self.ref_e_idx]) + self.controller_e.integrate( + state[self.i_idx], reference[self.ref_e_idx] + ) else: - self.action[1] = np.clip(self.action[1], self.action_e_limit_low, self.action_e_limit_high) + self.action[1] = np.clip( + self.action[1], self.action_e_limit_low, self.action_e_limit_high + ) - plot(self.external_ref_plots, self.state_names) # Plot the external data + plot(self.external_ref_plots, self.state_names) # Plot the external data return self.action @@ -104,5 +147,9 @@ def reset(self): def feedforward(self, state): # EMF compensation - psi_e = self.psi_e or self.l_e * state[self.i_idx] * self.nominal_values[self.i_idx] - return (state[self.omega_idx] * self.nominal_values[self.omega_idx] * psi_e) / self.nominal_values[self.u_idx] + psi_e = ( + self.psi_e or self.l_e * state[self.i_idx] * self.nominal_values[self.i_idx] + ) + return ( + state[self.omega_idx] * self.nominal_values[self.omega_idx] * psi_e + ) / self.nominal_values[self.u_idx] diff --git a/examples/classic_controllers/controllers/continuous_controller.py b/examples/classic_controllers/controllers/continuous_controller.py index 8c3c1c76..6445e44f 100644 --- a/examples/classic_controllers/controllers/continuous_controller.py +++ b/examples/classic_controllers/controllers/continuous_controller.py @@ -3,7 +3,9 @@ class ContinuousController: @classmethod def make(cls, environment, stage, _controllers, **controller_kwargs): - controller = _controllers[stage['controller_type']][2](environment, param_dict=stage, **controller_kwargs) + controller = _controllers[stage["controller_type"]][2]( + environment, param_dict=stage, **controller_kwargs + ) return controller def control(self, state, reference): diff --git a/examples/classic_controllers/controllers/dicrete_action_controller.py b/examples/classic_controllers/controllers/dicrete_action_controller.py index 4785a192..b0e04e26 100644 --- a/examples/classic_controllers/controllers/dicrete_action_controller.py +++ b/examples/classic_controllers/controllers/dicrete_action_controller.py @@ -6,18 +6,32 @@ class DiscreteActionController: """ - This class is used for current control of all DC motor systems with discrete actions. By default, a three-point - controller is used. For the externally excited dc motor, the excitation current is also controlled. + This class is used for current control of all DC motor systems with discrete actions. By default, a three-point + controller is used. For the externally excited dc motor, the excitation current is also controlled. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), **controller_kwargs): - assert type(environment.action_space) in [Discrete, MultiDiscrete] and isinstance(environment.physical_system, - DcMotorSystem), 'No suitable action space for Discrete Action Controller' + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + **controller_kwargs, + ): + assert type(environment.action_space) in [ + Discrete, + MultiDiscrete, + ] and isinstance( + environment.physical_system, DcMotorSystem + ), "No suitable action space for Discrete Action Controller" - self.ref_idx = np.where(ref_states != 'i_e')[0][0] + self.ref_idx = np.where(ref_states != "i_e")[0][0] self.ref_state_idx = environment.state_names.index(ref_states[self.ref_idx]) self.i_idx = environment.physical_system.CURRENTS_IDX[-1] - self.control_e = isinstance(environment.physical_system.electrical_motor, DcExternallyExcitedMotor) + self.control_e = isinstance( + environment.physical_system.electrical_motor, DcExternallyExcitedMotor + ) self.state_names = environment.state_names self.external_ref_plots = external_ref_plots @@ -26,40 +40,50 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p # Initialize Controller if self.control_e: # Check, if a controller for i_e is needed - assert len(stages) == 2, 'Controller design is incomplete' - assert 'i_e' in ref_states, 'No reference for i_e' - self.ref_e_idx = np.where(ref_states == 'i_e')[0][0] - self.controller_e = _controllers[stages[1][0]['controller_type']][1].make(environment, stages[1][0], - _controllers, - control_e=True, - **controller_kwargs) - self.controller = _controllers[stages[0][0]['controller_type']][1].make(environment, stages[0][0], - **controller_kwargs) + assert len(stages) == 2, "Controller design is incomplete" + assert "i_e" in ref_states, "No reference for i_e" + self.ref_e_idx = np.where(ref_states == "i_e")[0][0] + self.controller_e = _controllers[stages[1][0]["controller_type"]][1].make( + environment, + stages[1][0], + _controllers, + control_e=True, + **controller_kwargs, + ) + self.controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], **controller_kwargs + ) else: - assert len(ref_states) <= 1, 'Too many referenced states' - self.controller = _controllers[stages[0]['controller_type']][1].make(environment, stages[0], - _controllers, - **controller_kwargs) + assert len(ref_states) <= 1, "Too many referenced states" + self.controller = _controllers[stages[0]["controller_type"]][1].make( + environment, stages[0], _controllers, **controller_kwargs + ) def control(self, state, reference): """ - Main method that is called by the user to calculate the manipulated variable. + Main method that is called by the user to calculate the manipulated variable. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ - plot(self.external_ref_plots, self.state_names) # Plot external data + plot(self.external_ref_plots, self.state_names) # Plot external data # Check if i_e controller is used if self.control_e: - return [self.controller.control(state[self.ref_state_idx], reference[self.ref_idx]), - self.controller_e.control(state[self.i_idx], reference[self.ref_e_idx])] + return [ + self.controller.control( + state[self.ref_state_idx], reference[self.ref_idx] + ), + self.controller_e.control(state[self.i_idx], reference[self.ref_e_idx]), + ] else: - return self.controller.control(state[self.ref_state_idx], reference[self.ref_idx]) + return self.controller.control( + state[self.ref_state_idx], reference[self.ref_idx] + ) @staticmethod def get_plot_data(): diff --git a/examples/classic_controllers/controllers/discrete_controller.py b/examples/classic_controllers/controllers/discrete_controller.py index d17fbfdb..b0934374 100644 --- a/examples/classic_controllers/controllers/discrete_controller.py +++ b/examples/classic_controllers/controllers/discrete_controller.py @@ -3,8 +3,8 @@ class DiscreteController: """ - The DiscreteController is the base class for the base discrete controllers (OnOff controller and three-point - controller). + The DiscreteController is the base class for the base discrete controllers (OnOff controller and three-point + controller). """ @classmethod @@ -16,8 +16,12 @@ def make(cls, environment, stage, _controllers, **controller_kwargs): else: action_space_n = 3 - controller = _controllers[stage['controller_type']][2](environment, action_space=action_space_n, - param_dict=stage, **controller_kwargs) + controller = _controllers[stage["controller_type"]][2]( + environment, + action_space=action_space_n, + param_dict=stage, + **controller_kwargs, + ) return controller def control(self, state, reference): diff --git a/examples/classic_controllers/controllers/flux_observer.py b/examples/classic_controllers/controllers/flux_observer.py index 1c21d2c3..f785d5d7 100644 --- a/examples/classic_controllers/controllers/flux_observer.py +++ b/examples/classic_controllers/controllers/flux_observer.py @@ -3,34 +3,41 @@ class FluxObserver: """ - This class represents a rotor flux observer for an induction motor base on a current model. Further information - can be found at https://ieeexplore.ieee.org/document/4270863. + This class represents a rotor flux observer for an induction motor base on a current model. Further information + can be found at https://ieeexplore.ieee.org/document/4270863. """ + def __init__(self, env): mp = env.physical_system.electrical_motor.motor_parameter - self.l_m = mp['l_m'] # Main induction - self.l_r = mp['l_m'] + mp['l_sigr'] # Induction of the rotor - self.r_r = mp['r_r'] # Rotor resistance - self.p = mp['p'] # Pole pair number - self.tau = env.physical_system.tau # Sampling time + self.l_m = mp["l_m"] # Main induction + self.l_r = mp["l_m"] + mp["l_sigr"] # Induction of the rotor + self.r_r = mp["r_r"] # Rotor resistance + self.p = mp["p"] # Pole pair number + self.tau = env.physical_system.tau # Sampling time # function to transform the currents from abc to alpha/beta coordinates - self.abc_to_alphabeta_transformation = env.physical_system.abc_to_alphabeta_space + self.abc_to_alphabeta_transformation = ( + env.physical_system.abc_to_alphabeta_space + ) # Integrated values of the flux for the two directions (Re: alpha, Im: beta) self.integrated = np.complex(0, 0) - self.i_s_idx = [env.state_names.index('i_sa'), env.state_names.index('i_sb'), env.state_names.index('i_sc')] - self.omega_idx = env.state_names.index('omega') + self.i_s_idx = [ + env.state_names.index("i_sa"), + env.state_names.index("i_sb"), + env.state_names.index("i_sc"), + ] + self.omega_idx = env.state_names.index("omega") def estimate(self, state): """ - Method to estimate the flux of an induction motor + Method to estimate the flux of an induction motor - Args: - state: state of the gym-electric-motor environment + Args: + state: state of the gym-electric-motor environment - Returns: - Amount and angle of the estimated flux + Returns: + Amount and angle of the estimated flux """ i_s = state[self.i_s_idx] @@ -40,8 +47,11 @@ def estimate(self, state): [i_s_alpha, i_s_beta] = self.abc_to_alphabeta_transformation(i_s) # Calculate delta flux - delta = np.complex(i_s_alpha, i_s_beta) * self.r_r * self.l_m / self.l_r - self.integrated * np.complex( - self.r_r / self.l_r, -omega) + delta = np.complex( + i_s_alpha, i_s_beta + ) * self.r_r * self.l_m / self.l_r - self.integrated * np.complex( + self.r_r / self.l_r, -omega + ) # Integrate the flux self.integrated += delta * self.tau diff --git a/examples/classic_controllers/controllers/foc_controller.py b/examples/classic_controllers/controllers/foc_controller.py index f0918c85..7fce5e32 100644 --- a/examples/classic_controllers/controllers/foc_controller.py +++ b/examples/classic_controllers/controllers/foc_controller.py @@ -6,25 +6,35 @@ class FieldOrientedController: """ - This class controls the currents of synchronous motors. In the case of continuous manipulated variables, the - control is performed in the rotating dq-coordinates. For this purpose, the two current components are optionally - decoupled and two independent current controllers are used. - In the case of discrete manipulated variables, control takes place in stator-fixed coordinates. The reference - values are converted into these coordinates so that a on-off controller calculates the corresponding - manipulated variable for each current component. + This class controls the currents of synchronous motors. In the case of continuous manipulated variables, the + control is performed in the rotating dq-coordinates. For this purpose, the two current components are optionally + decoupled and two independent current controllers are used. + In the case of discrete manipulated variables, control takes place in stator-fixed coordinates. The reference + values are converted into these coordinates so that a on-off controller calculates the corresponding + manipulated variable for each current component. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), **controller_kwargs): - assert isinstance(environment.physical_system, SynchronousMotorSystem), 'No suitable Environment for FOC Controller' + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + **controller_kwargs, + ): + assert isinstance( + environment.physical_system, SynchronousMotorSystem + ), "No suitable Environment for FOC Controller" t32 = environment.physical_system.electrical_motor.t_32 q = environment.physical_system.electrical_motor.q - self.backward_transformation = (lambda quantities, eps: t32(q(quantities, eps))) + self.backward_transformation = lambda quantities, eps: t32(q(quantities, eps)) self.tau = environment.physical_system.tau - self.ref_d_idx = np.where(ref_states == 'i_sd')[0][0] - self.ref_q_idx = np.where(ref_states == 'i_sq')[0][0] + self.ref_d_idx = np.where(ref_states == "i_sd")[0][0] + self.ref_q_idx = np.where(ref_states == "i_sq")[0][0] self.d_idx = environment.state_names.index(ref_states[self.ref_d_idx]) self.q_idx = environment.state_names.index(ref_states[self.ref_q_idx]) @@ -33,20 +43,22 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p self.state_space = environment.physical_system.state_space self.state_names = environment.state_names - self.i_sd_idx = environment.state_names.index('i_sd') - self.i_sq_idx = environment.state_names.index('i_sq') - self.u_sd_idx = environment.state_names.index('u_sd') - self.u_sq_idx = environment.state_names.index('u_sq') - self.u_a_idx = environment.state_names.index('u_a') - self.u_b_idx = environment.state_names.index('u_b') - self.u_c_idx = environment.state_names.index('u_c') - self.omega_idx = environment.state_names.index('omega') - self.eps_idx = environment.state_names.index('epsilon') + self.i_sd_idx = environment.state_names.index("i_sd") + self.i_sq_idx = environment.state_names.index("i_sq") + self.u_sd_idx = environment.state_names.index("u_sd") + self.u_sq_idx = environment.state_names.index("u_sq") + self.u_a_idx = environment.state_names.index("u_a") + self.u_b_idx = environment.state_names.index("u_b") + self.u_c_idx = environment.state_names.index("u_c") + self.omega_idx = environment.state_names.index("omega") + self.eps_idx = environment.state_names.index("epsilon") self.limit = environment.physical_system.limits 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.psi_p = self.mp.get("psi_p", 0) + self.dead_time = ( + 1.5 if environment.physical_system.converter._dead_time else 0.5 + ) self.has_cont_action_space = type(self.action_space) is Box @@ -56,74 +68,123 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p # Initialize continuous controllers if self.has_cont_action_space: - assert len(stages[0]) == 2, 'Number of stages not correct' - self.decoupling = controller_kwargs.get('decoupling', True) + assert len(stages[0]) == 2, "Number of stages not correct" + self.decoupling = controller_kwargs.get("decoupling", True) [self.u_sq_0, self.u_sd_0] = [0, 0] - self.d_controller = _controllers[stages[0][0]['controller_type']][1].make( - environment, stages[0][0], _controllers, **controller_kwargs) - self.q_controller = _controllers[stages[0][1]['controller_type']][1].make( - environment, stages[0][1], _controllers, **controller_kwargs) + self.d_controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], _controllers, **controller_kwargs + ) + self.q_controller = _controllers[stages[0][1]["controller_type"]][1].make( + environment, stages[0][1], _controllers, **controller_kwargs + ) # Initialize discrete controllers else: - assert len(stages) == 3, 'Number of stages not correct' - self.abc_controller = [_controllers[stages[0][0]['controller_type']][1].make( - environment, stages[i][0], _controllers, **controller_kwargs) for i in range(3)] - self.i_abc_idx = [environment.state_names.index(state) for state in ['i_a', 'i_b', 'i_c']] + assert len(stages) == 3, "Number of stages not correct" + self.abc_controller = [ + _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[i][0], _controllers, **controller_kwargs + ) + for i in range(3) + ] + self.i_abc_idx = [ + environment.state_names.index(state) for state in ["i_a", "i_b", "i_c"] + ] def control(self, state, reference): """ - Main method that is called by the user to calculate the manipulated variable. + Main method that is called by the user to calculate the manipulated variable. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ # Calculate delta epsilon - epsilon_d = state[self.eps_idx] * self.limit[self.eps_idx] + self.dead_time * self.tau * \ - state[self.omega_idx] * self.limit[self.omega_idx] * self.mp['p'] + epsilon_d = ( + state[self.eps_idx] * self.limit[self.eps_idx] + + self.dead_time + * self.tau + * state[self.omega_idx] + * self.limit[self.omega_idx] + * self.mp["p"] + ) # Check if action space is continuous if self.has_cont_action_space: - # Decoupling of the d- and q-component if self.decoupling: - self.u_sd_0 = -state[self.omega_idx] * self.mp['p'] * self.mp['l_q'] * state[self.i_sq_idx] * self.limit[ - self.i_sq_idx] / self.limit[self.u_sd_idx] * self.limit[self.omega_idx] - self.u_sq_0 = state[self.omega_idx] * self.mp['p'] * ( - state[self.i_sd_idx] * self.mp['l_d'] * self.limit[self.i_sd_idx] + self.psi_p) / self.limit[ - self.u_sq_idx] * self.limit[self.omega_idx] + self.u_sd_0 = ( + -state[self.omega_idx] + * self.mp["p"] + * self.mp["l_q"] + * state[self.i_sq_idx] + * self.limit[self.i_sq_idx] + / self.limit[self.u_sd_idx] + * self.limit[self.omega_idx] + ) + self.u_sq_0 = ( + state[self.omega_idx] + * self.mp["p"] + * ( + state[self.i_sd_idx] + * self.mp["l_d"] + * self.limit[self.i_sd_idx] + + self.psi_p + ) + / self.limit[self.u_sq_idx] + * self.limit[self.omega_idx] + ) # Calculate the two actions - u_sd = self.d_controller.control(state[self.d_idx], reference[self.ref_d_idx]) + self.u_sd_0 - u_sq = self.q_controller.control(state[self.q_idx], reference[self.ref_q_idx]) + self.u_sq_0 + u_sd = ( + self.d_controller.control(state[self.d_idx], reference[self.ref_d_idx]) + + self.u_sd_0 + ) + u_sq = ( + self.q_controller.control(state[self.q_idx], reference[self.ref_q_idx]) + + self.u_sq_0 + ) # Shifting the reference potential action_temp = self.backward_transformation((u_sd, u_sq), epsilon_d) action_temp = action_temp - 0.5 * (max(action_temp) + min(action_temp)) # Check limit and integrate - action = np.clip(action_temp, self.action_space.low[0], self.action_space.high[0]) + action = np.clip( + action_temp, self.action_space.low[0], self.action_space.high[0] + ) if (action == action_temp).all(): - self.d_controller.integrate(state[self.d_idx], reference[self.ref_d_idx]) - self.q_controller.integrate(state[self.q_idx], reference[self.ref_q_idx]) + self.d_controller.integrate( + state[self.d_idx], reference[self.ref_d_idx] + ) + self.q_controller.integrate( + state[self.q_idx], reference[self.ref_q_idx] + ) else: # Transform reference in abc coordinates - ref_abc = self.backward_transformation((reference[self.ref_d_idx], reference[self.ref_q_idx]), epsilon_d) + ref_abc = self.backward_transformation( + (reference[self.ref_d_idx], reference[self.ref_q_idx]), epsilon_d + ) action = 0 # Calculate discrete action for i in range(3): - action += (2 ** (2 - i)) * self.abc_controller[i].control(state[self.i_abc_idx[i]], ref_abc[i]) + action += (2 ** (2 - i)) * self.abc_controller[i].control( + state[self.i_abc_idx[i]], ref_abc[i] + ) # Plot external data - plot(self.external_ref_plots, self.state_names, external_data=self.get_plot_data()) + plot( + self.external_ref_plots, + self.state_names, + external_data=self.get_plot_data(), + ) return action @staticmethod diff --git a/examples/classic_controllers/controllers/induction_motor_cascaded_foc.py b/examples/classic_controllers/controllers/induction_motor_cascaded_foc.py index b6ee8229..5a175f62 100644 --- a/examples/classic_controllers/controllers/induction_motor_cascaded_foc.py +++ b/examples/classic_controllers/controllers/induction_motor_cascaded_foc.py @@ -1,5 +1,7 @@ from .continuous_controller import ContinuousController -from .induction_motor_torque_to_current_conversion import InductionMotorTorqueToCurrentConversion +from .induction_motor_torque_to_current_conversion import ( + InductionMotorTorqueToCurrentConversion, +) from .flux_observer import FluxObserver from .plot_external_data import plot from gymnasium.spaces import Box @@ -8,16 +10,23 @@ class InductionMotorCascadedFieldOrientedController: """ - This controller is used for torque or speed control of induction motors. The controller consists of a field - oriented controller for current control, an efficiency-optimized torque controller and an optional speed - controller. The current control is equivalent to the current control of the FieldOrientedControllerRotorFluxObserver. - The TorqueToCurrentConversionRotorFluxObserver is used for torque control and a PI-Controller by default is used - for speed control. + This controller is used for torque or speed control of induction motors. The controller consists of a field + oriented controller for current control, an efficiency-optimized torque controller and an optional speed + controller. The current control is equivalent to the current control of the FieldOrientedControllerRotorFluxObserver. + The TorqueToCurrentConversionRotorFluxObserver is used for torque control and a PI-Controller by default is used + for speed control. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), external_plot=(), - **controller_kwargs): - + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + external_plot=(), + **controller_kwargs, + ): self.env = environment self.action_space = environment.action_space self.has_cont_action_space = type(self.action_space) is Box @@ -26,42 +35,48 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p self.stages = stages self.flux_observer = FluxObserver(self.env) - self.i_sd_idx = self.env.state_names.index('i_sd') - self.i_sq_idx = self.env.state_names.index('i_sq') - self.u_s_abc_idx = [self.env.state_names.index(state) for state in ['u_sa', 'u_sb', 'u_sc']] - self.omega_idx = self.env.state_names.index('omega') - self.torque_idx = self.env.state_names.index('torque') + self.i_sd_idx = self.env.state_names.index("i_sd") + self.i_sq_idx = self.env.state_names.index("i_sq") + self.u_s_abc_idx = [ + self.env.state_names.index(state) for state in ["u_sa", "u_sb", "u_sc"] + ] + self.omega_idx = self.env.state_names.index("omega") + self.torque_idx = self.env.state_names.index("torque") mp = self.env.physical_system.electrical_motor.motor_parameter - self.p = mp['p'] - self.l_m = mp['l_m'] - self.l_sigma_s = mp['l_sigs'] - self.l_r = self.l_m + mp['l_sigr'] - self.l_s = self.l_m + mp['l_sigs'] - self.r_r = mp['r_r'] - self.r_s = mp['r_s'] + self.p = mp["p"] + self.l_m = mp["l_m"] + self.l_sigma_s = mp["l_sigs"] + self.l_r = self.l_m + mp["l_sigr"] + self.l_s = self.l_m + mp["l_sigs"] + self.r_r = mp["r_r"] + self.r_s = mp["r_s"] self.tau_r = self.l_r / self.r_r - self.sigma = (self.l_s * self.l_r - self.l_m ** 2) / (self.l_s * self.l_r) + self.sigma = (self.l_s * self.l_r - self.l_m**2) / (self.l_s * self.l_r) self.limits = self.env.physical_system.limits self.nominal_values = self.env.physical_system.nominal_state - self.tau_sigma = self.sigma * self.l_s / (self.r_s + self.r_r * self.l_m ** 2 / self.l_r ** 2) + self.tau_sigma = ( + self.sigma * self.l_s / (self.r_s + self.r_r * self.l_m**2 / self.l_r**2) + ) self.tau = self.env.physical_system.tau self.dq_to_abc_transformation = environment.physical_system.dq_to_abc_space - self.torque_control = 'torque' in ref_states or 'omega' in ref_states - self.current_control = 'i_sd' in ref_states - self.omega_control = 'omega' in ref_states + self.torque_control = "torque" in ref_states or "omega" in ref_states + self.current_control = "i_sd" in ref_states + self.omega_control = "omega" in ref_states self.ref_state_idx = [self.i_sq_idx, self.i_sd_idx] if self.current_control: - self.ref_d_idx = np.where(ref_states == 'i_sd')[0][0] - self.ref_idx = np.where(ref_states != 'i_sd')[0][0] + self.ref_d_idx = np.where(ref_states == "i_sd")[0][0] + self.ref_idx = np.where(ref_states != "i_sd")[0][0] # Initialize torque controller if self.torque_control: self.ref_state_idx.append(self.torque_idx) - self.torque_controller = InductionMotorTorqueToCurrentConversion(environment, stages) + self.torque_controller = InductionMotorTorqueToCurrentConversion( + environment, stages + ) if self.omega_control: self.ref_state_idx.append(self.omega_idx) @@ -73,89 +88,141 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p self.external_plot = external_plot self.external_ref_plots = external_ref_plots self.external_ref_plots = external_ref_plots - plot_ref = np.append(np.array([environment.state_names[i] for i in self.ref_state_idx]), ref_states) + plot_ref = np.append( + np.array([environment.state_names[i] for i in self.ref_state_idx]), + ref_states, + ) for ext_ref_plot in self.external_ref_plots: ext_ref_plot.set_reference(plot_ref) labels = [ - {'y_label': r"|$\Psi_{r}$|/Vs", 'state_label': r"|$\hat{\Psi}_{r}$|/Vs", 'ref_label': r"|$\Psi_{r}$|$^*$/Vs"}, - {'y_label': r"$\measuredangle\Psi_r$/rad", 'state_label': r"$\measuredangle\hat{\Psi}_r$/rad"}] + { + "y_label": r"|$\Psi_{r}$|/Vs", + "state_label": r"|$\hat{\Psi}_{r}$|/Vs", + "ref_label": r"|$\Psi_{r}$|$^*$/Vs", + }, + { + "y_label": r"$\measuredangle\Psi_r$/rad", + "state_label": r"$\measuredangle\hat{\Psi}_r$/rad", + }, + ] for ext_plot, label in zip(self.external_plot, labels): ext_plot.set_label(label) # Initialize continuous controllers if self.has_cont_action_space: - assert len(stages[0]) == 2, 'Number of stages not correct' - self.decoupling = controller_kwargs.get('decoupling', True) + assert len(stages[0]) == 2, "Number of stages not correct" + self.decoupling = controller_kwargs.get("decoupling", True) self.u_sd_0 = self.u_sq_0 = 0 - self.d_controller = _controllers[stages[0][0]['controller_type']][1].make( - environment, stages[0][0], _controllers, **controller_kwargs) - self.q_controller = _controllers[stages[0][1]['controller_type']][1].make( - environment, stages[0][1], _controllers, **controller_kwargs) + self.d_controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], _controllers, **controller_kwargs + ) + self.q_controller = _controllers[stages[0][1]["controller_type"]][1].make( + environment, stages[0][1], _controllers, **controller_kwargs + ) if self.omega_control: - self.overlaid_controller = [_controllers[stages[1][i]['controller_type']][1].make(environment, - stages[1][i], _controllers, cascaded=True, **controller_kwargs) for i in range(0, len(stages[1]))] - self.overlaid_type = [_controllers[stages[1][i]['controller_type']][1] == ContinuousController for i in - range(0, len(stages[1]))] - - self.ref = np.zeros(len(self.ref_state_idx)) # Define array for reference values + self.overlaid_controller = [ + _controllers[stages[1][i]["controller_type"]][1].make( + environment, + stages[1][i], + _controllers, + cascaded=True, + **controller_kwargs, + ) + for i in range(0, len(stages[1])) + ] + self.overlaid_type = [ + _controllers[stages[1][i]["controller_type"]][1] + == ContinuousController + for i in range(0, len(stages[1])) + ] + + self.ref = np.zeros( + len(self.ref_state_idx) + ) # Define array for reference values def control(self, state, reference): """ - This main method of the InductionMotorCascadedFieldOrientedController is called by the user. It calculates - the input voltages u_a,b,c. + This main method of the InductionMotorCascadedFieldOrientedController is called by the user. It calculates + the input voltages u_a,b,c. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ self.ref[-1] = reference[self.ref_idx] # Set the reference - self.psi_abs, self.psi_angle = self.flux_observer.estimate(state * self.limits) # Estimate the flux + self.psi_abs, self.psi_angle = self.flux_observer.estimate( + state * self.limits + ) # Estimate the flux # Iterate through the overlaid controller stages if self.omega_control: for i in range(len(self.overlaid_controller) + 1, 1, -1): # Calculate reference - self.ref[i] = self.overlaid_controller[i-2].control(state[self.ref_state_idx[i + 1]], self.ref[i + 1]) + self.ref[i] = self.overlaid_controller[i - 2].control( + state[self.ref_state_idx[i + 1]], self.ref[i + 1] + ) # Check limit and integrate - if (0.85 * self.state_space.low[self.ref_state_idx[i]] <= self.ref[i] <= 0.85 * - self.state_space.high[self.ref_state_idx[i]]) and self.overlaid_type[i - 2]: - self.overlaid_controller[i - 2].integrate(state[self.ref_state_idx[i + 1]], self.ref[i + 1]) + if ( + 0.85 * self.state_space.low[self.ref_state_idx[i]] + <= self.ref[i] + <= 0.85 * self.state_space.high[self.ref_state_idx[i]] + ) and self.overlaid_type[i - 2]: + self.overlaid_controller[i - 2].integrate( + state[self.ref_state_idx[i + 1]], self.ref[i + 1] + ) else: - self.ref[i] = np.clip(self.ref[i], self.nominal_values[self.ref_state_idx[i]] / self.limits[ - self.ref_state_idx[i]] * self.state_space.low[self.ref_state_idx[i]], - self.nominal_values[self.ref_state_idx[i]] / self.limits[ - self.ref_state_idx[i]] * self.state_space.high[self.ref_state_idx[i]]) + self.ref[i] = np.clip( + self.ref[i], + self.nominal_values[self.ref_state_idx[i]] + / self.limits[self.ref_state_idx[i]] + * self.state_space.low[self.ref_state_idx[i]], + self.nominal_values[self.ref_state_idx[i]] + / self.limits[self.ref_state_idx[i]] + * self.state_space.high[self.ref_state_idx[i]], + ) # Calculate reference values for i_d and i_q if self.torque_control: torque = self.ref[2] * self.limits[self.torque_idx] - self.ref[0], self.ref[1], self.psi_opt = self.torque_controller.control(state, torque, self.psi_abs) + self.ref[0], self.ref[1], self.psi_opt = self.torque_controller.control( + state, torque, self.psi_abs + ) if self.has_cont_action_space: - state = state * self.limits # Denormalize the state + state = state * self.limits # Denormalize the state omega_me = state[self.omega_idx] i_sd = state[self.i_sd_idx] i_sq = state[self.i_sq_idx] - omega_s = omega_me + self.r_r * self.l_m / self.l_r * i_sq / max(np.abs(self.psi_abs), 1e-4) * np.sign(self.psi_abs) + omega_s = omega_me + self.r_r * self.l_m / self.l_r * i_sq / max( + np.abs(self.psi_abs), 1e-4 + ) * np.sign(self.psi_abs) # Calculate delate u_sd, u_sq - u_sd_delta = self.d_controller.control(state[self.i_sd_idx], - self.ref[1] * self.limits[self.i_sd_idx]) - u_sq_delta = self.q_controller.control(state[self.i_sq_idx], - self.ref[0] * self.limits[self.i_sq_idx]) + u_sd_delta = self.d_controller.control( + state[self.i_sd_idx], self.ref[1] * self.limits[self.i_sd_idx] + ) + u_sq_delta = self.q_controller.control( + state[self.i_sq_idx], self.ref[0] * self.limits[self.i_sq_idx] + ) # Decouple the two current components if self.decoupling: - self.u_sd_0 = -omega_s * self.sigma * self.l_s * i_sq - self.l_m * self.r_r / (self.l_r ** 2) * self.psi_abs - self.u_sq_0 = omega_s * self.sigma * self.l_s * i_sd + omega_me * self.l_m / self.l_r * self.psi_abs + self.u_sd_0 = ( + -omega_s * self.sigma * self.l_s * i_sq + - self.l_m * self.r_r / (self.l_r**2) * self.psi_abs + ) + self.u_sq_0 = ( + omega_s * self.sigma * self.l_s * i_sd + + omega_me * self.l_m / self.l_r * self.psi_abs + ) u_sd = self.u_sd_0 + u_sd_delta u_sq = self.u_sq_0 + u_sq_delta @@ -167,22 +234,30 @@ def control(self, state, reference): # Limit the action and integrate action = np.clip(u_s_abc, self.action_space.low, self.action_space.high) if (action == u_s_abc).all(): - self.d_controller.integrate(state[self.i_sd_idx], - self.ref[1] * self.limits[self.i_sd_idx]) - self.q_controller.integrate(state[self.i_sq_idx], - self.ref[0] * self.limits[self.i_sq_idx]) + self.d_controller.integrate( + state[self.i_sd_idx], self.ref[1] * self.limits[self.i_sd_idx] + ) + self.q_controller.integrate( + state[self.i_sq_idx], self.ref[0] * self.limits[self.i_sq_idx] + ) # Plot the external data - plot(external_reference_plots=self.external_ref_plots, state_names=self.state_names, - external_plot=self.external_plot, external_data=self.get_plot_data()) + plot( + external_reference_plots=self.external_ref_plots, + state_names=self.state_names, + external_plot=self.external_plot, + external_data=self.get_plot_data(), + ) return action def get_plot_data(self): # Getting the external data that should be plotted - return dict(ref_state=self.ref_state_idx[:-1], ref_value=self.ref[:-1], - external=[[self.psi_abs, self.psi_opt], - [self.psi_angle]]) + return dict( + ref_state=self.ref_state_idx[:-1], + ref_value=self.ref[:-1], + external=[[self.psi_abs, self.psi_opt], [self.psi_angle]], + ) def reset(self): # Reset the Controllers and the observer diff --git a/examples/classic_controllers/controllers/induction_motor_foc.py b/examples/classic_controllers/controllers/induction_motor_foc.py index 699cd06e..dc5c6f3b 100644 --- a/examples/classic_controllers/controllers/induction_motor_foc.py +++ b/examples/classic_controllers/controllers/induction_motor_foc.py @@ -6,14 +6,22 @@ class InductionMotorFieldOrientedController: """ - This class controls the currents of induction motors using a field oriented controller. The control is performed - in the rotating dq-stator-coordinates. For this purpose, the two current components are optionally decoupled and - two independent current controllers are used. The rotor flux required for this is estimated based on a current - model. + This class controls the currents of induction motors using a field oriented controller. The control is performed + in the rotating dq-stator-coordinates. For this purpose, the two current components are optionally decoupled and + two independent current controllers are used. The rotor flux required for this is estimated based on a current + model. """ - def __init__(self, environment, stages, _controllers, ref_states, external_ref_plots=(), external_plot=(), - **controller_kwargs): + def __init__( + self, + environment, + stages, + _controllers, + ref_states, + external_ref_plots=(), + external_plot=(), + **controller_kwargs, + ): self.env = environment self.action_space = environment.action_space self.has_cont_action_space = type(self.action_space) is Box @@ -22,25 +30,29 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p self.stages = stages self.flux_observer = FluxObserver(self.env) - self.i_sd_idx = self.env.state_names.index('i_sd') - self.i_sq_idx = self.env.state_names.index('i_sq') - self.u_s_abc_idx = [self.env.state_names.index(state) for state in ['u_sa', 'u_sb', 'u_sc']] - self.i_sd_ref_idx = np.where(ref_states == 'i_sd')[0][0] - self.i_sq_ref_idx = np.where(ref_states == 'i_sq')[0][0] - self.omega_idx = self.env.state_names.index('omega') + self.i_sd_idx = self.env.state_names.index("i_sd") + self.i_sq_idx = self.env.state_names.index("i_sq") + self.u_s_abc_idx = [ + self.env.state_names.index(state) for state in ["u_sa", "u_sb", "u_sc"] + ] + self.i_sd_ref_idx = np.where(ref_states == "i_sd")[0][0] + self.i_sq_ref_idx = np.where(ref_states == "i_sq")[0][0] + self.omega_idx = self.env.state_names.index("omega") mp = self.env.physical_system.electrical_motor.motor_parameter - self.p = mp['p'] - self.l_m = mp['l_m'] - self.l_sigma_s = mp['l_sigs'] - self.l_r = self.l_m + mp['l_sigr'] - self.l_s = self.l_m + mp['l_sigs'] - self.r_r = mp['r_r'] - self.r_s = mp['r_s'] + self.p = mp["p"] + self.l_m = mp["l_m"] + self.l_sigma_s = mp["l_sigs"] + self.l_r = self.l_m + mp["l_sigr"] + self.l_s = self.l_m + mp["l_sigs"] + self.r_r = mp["r_r"] + self.r_s = mp["r_s"] self.tau_r = self.l_r / self.r_r - self.sigma = (self.l_s * self.l_r - self.l_m ** 2) / (self.l_s * self.l_r) + self.sigma = (self.l_s * self.l_r - self.l_m**2) / (self.l_s * self.l_r) self.limits = self.env.physical_system.limits - self.tau_sigma = self.sigma * self.l_s / (self.r_s + self.r_r * self.l_m**2 / self.l_r**2) + self.tau_sigma = ( + self.sigma * self.l_s / (self.r_s + self.r_r * self.l_m**2 / self.l_r**2) + ) self.tau = self.env.physical_system.tau self.dq_to_abc_transformation = environment.physical_system.dq_to_abc_space @@ -53,52 +65,75 @@ def __init__(self, environment, stages, _controllers, ref_states, external_ref_p for ext_ref_plot in self.external_ref_plots: ext_ref_plot.set_reference(ref_states) - labels = [{'y_label': r"|$\Psi_{r}$|/Vs", 'state_label': r"|$\hat{\Psi}_{r}$|/Vs"}, - {'y_label': r"$\measuredangle\Psi_r$/rad", 'state_label': r"$\measuredangle\hat{\Psi}_r$/rad"}] + labels = [ + {"y_label": r"|$\Psi_{r}$|/Vs", "state_label": r"|$\hat{\Psi}_{r}$|/Vs"}, + { + "y_label": r"$\measuredangle\Psi_r$/rad", + "state_label": r"$\measuredangle\hat{\Psi}_r$/rad", + }, + ] for ext_plot, label in zip(self.external_plot, labels): ext_plot.set_label(label) # Initialize continuous controllers if self.has_cont_action_space: - assert len(stages[0]) == 2, 'Number of stages not correct' - self.decoupling = controller_kwargs.get('decoupling', True) + assert len(stages[0]) == 2, "Number of stages not correct" + self.decoupling = controller_kwargs.get("decoupling", True) self.u_sd_0 = self.u_sq_0 = 0 - self.d_controller = _controllers[stages[0][0]['controller_type']][1].make( - environment, stages[0][0], _controllers, **controller_kwargs) - self.q_controller = _controllers[stages[0][1]['controller_type']][1].make( - environment, stages[0][1], _controllers, **controller_kwargs) + self.d_controller = _controllers[stages[0][0]["controller_type"]][1].make( + environment, stages[0][0], _controllers, **controller_kwargs + ) + self.q_controller = _controllers[stages[0][1]["controller_type"]][1].make( + environment, stages[0][1], _controllers, **controller_kwargs + ) def control(self, state, reference): """ - This main method of the InductionMotorFieldOrientedController is called by the user. It calculates the input - voltages u_a,b,c. + This main method of the InductionMotorFieldOrientedController is called by the user. It calculates the input + voltages u_a,b,c. - Args: - state: state of the gem environment - reference: reference for the controlled states + Args: + state: state of the gem environment + reference: reference for the controlled states - Returns: - action: action for the gem environment + Returns: + action: action for the gem environment """ - state = state * self.limits # Denormalize the state - self.psi_abs, self.psi_angle = self.flux_observer.estimate(state) # Estimate the flux + state = state * self.limits # Denormalize the state + self.psi_abs, self.psi_angle = self.flux_observer.estimate( + state + ) # Estimate the flux omega_me = state[self.omega_idx] i_sd = state[self.i_sd_idx] i_sq = state[self.i_sq_idx] - omega_s = omega_me + self.r_r * self.l_m / self.l_r * i_sq / max(np.abs(self.psi_abs), 1e-4) * np.sign(self.psi_abs) + omega_s = omega_me + self.r_r * self.l_m / self.l_r * i_sq / max( + np.abs(self.psi_abs), 1e-4 + ) * np.sign(self.psi_abs) # Calculate delate u_sd, u_sq - u_sd_delta = self.d_controller.control(state[self.i_sd_idx], reference[self.i_sd_ref_idx] * self.limits[self.i_sd_idx]) - u_sq_delta = self.q_controller.control(state[self.i_sq_idx], reference[self.i_sq_ref_idx] * self.limits[self.i_sq_idx]) + u_sd_delta = self.d_controller.control( + state[self.i_sd_idx], + reference[self.i_sd_ref_idx] * self.limits[self.i_sd_idx], + ) + u_sq_delta = self.q_controller.control( + state[self.i_sq_idx], + reference[self.i_sq_ref_idx] * self.limits[self.i_sq_idx], + ) # Decouple the two current components if self.decoupling: - self.u_sd_0 = -omega_s * self.sigma * self.l_s * i_sq - self.l_m * self.r_r / (self.l_r ** 2) * self.psi_abs - self.u_sq_0 = omega_s * self.sigma * self.l_s * i_sd + omega_me * self.l_m / self.l_r * self.psi_abs + self.u_sd_0 = ( + -omega_s * self.sigma * self.l_s * i_sq + - self.l_m * self.r_r / (self.l_r**2) * self.psi_abs + ) + self.u_sq_0 = ( + omega_s * self.sigma * self.l_s * i_sd + + omega_me * self.l_m / self.l_r * self.psi_abs + ) u_sd = self.u_sd_0 + u_sd_delta u_sq = self.u_sq_0 + u_sq_delta @@ -110,8 +145,14 @@ def control(self, state, reference): # Limit action and integrate action = np.clip(u_s_abc, self.action_space.low, self.action_space.high) if (action == u_s_abc).all(): - self.d_controller.integrate(state[self.i_sd_idx], reference[self.i_sd_ref_idx] * self.limits[self.i_sd_idx]) - self.q_controller.integrate(state[self.i_sq_idx], reference[self.i_sq_ref_idx] * self.limits[self.i_sq_idx]) + self.d_controller.integrate( + state[self.i_sd_idx], + reference[self.i_sd_ref_idx] * self.limits[self.i_sd_idx], + ) + self.q_controller.integrate( + state[self.i_sq_idx], + reference[self.i_sq_ref_idx] * self.limits[self.i_sq_idx], + ) # Plot the external data plot(external_plot=self.external_plot, external_data=self.get_plot_data()) @@ -120,7 +161,9 @@ def control(self, state, reference): def get_plot_data(self): # Getting the external data that should be plotted - return dict(ref_state=[], ref_value=[], external=[[self.psi_abs], [self.psi_angle]]) + return dict( + ref_state=[], ref_value=[], external=[[self.psi_abs], [self.psi_angle]] + ) def reset(self): # Reset the Controllers and the observer diff --git a/examples/classic_controllers/controllers/induction_motor_torque_to_current_conversion.py b/examples/classic_controllers/controllers/induction_motor_torque_to_current_conversion.py index 5ccf1021..beecc1ac 100644 --- a/examples/classic_controllers/controllers/induction_motor_torque_to_current_conversion.py +++ b/examples/classic_controllers/controllers/induction_motor_torque_to_current_conversion.py @@ -5,44 +5,53 @@ class InductionMotorTorqueToCurrentConversion: """ - This class represents the torque controller for the cascaded control of induction motors. The torque controller - uses LUT to find an appropriate operating point for the flux and torque. The flux is limited by a modulation - controller. A reference value for the i_sd current is then determined using the operating point of the flux and - a PI controller. In addition, a reference for the i_sq current is calculated based on the current flux and the - operating point of the torque. - Predefined plots are available for visualization of the operating points (plot_torque: default True). Also the - operation of the modulation controller can be plotted (plot_modulation: default False). - Further information can be found at https://ieeexplore.ieee.org/document/7203404. + This class represents the torque controller for the cascaded control of induction motors. The torque controller + uses LUT to find an appropriate operating point for the flux and torque. The flux is limited by a modulation + controller. A reference value for the i_sd current is then determined using the operating point of the flux and + a PI controller. In addition, a reference for the i_sq current is calculated based on the current flux and the + operating point of the torque. + Predefined plots are available for visualization of the operating points (plot_torque: default True). Also the + operation of the modulation controller can be plotted (plot_modulation: default False). + Further information can be found at https://ieeexplore.ieee.org/document/7203404. """ - def __init__(self, environment, stages, plot_torque=True, plot_modulation=False, update_interval=1000): + def __init__( + self, + environment, + stages, + plot_torque=True, + plot_modulation=False, + update_interval=1000, + ): self.env = environment self.nominal_values = self.env.physical_system.nominal_state self.state_space = self.env.physical_system.state_space # Calculate parameters of the motor mp = self.env.physical_system.electrical_motor.motor_parameter - self.l_m = mp['l_m'] - self.l_r = self.l_m + mp['l_sigr'] - self.l_s = self.l_m + mp['l_sigs'] - self.r_r = mp['r_r'] - self.r_s = mp['r_s'] - self.p = mp['p'] + self.l_m = mp["l_m"] + self.l_r = self.l_m + mp["l_sigr"] + self.l_s = self.l_m + mp["l_sigs"] + self.r_r = mp["r_r"] + self.r_s = mp["r_s"] + self.p = mp["p"] self.tau = self.env.physical_system.tau tau_s = self.l_s / self.r_s - self.i_sd_idx = self.env.state_names.index('i_sd') - self.i_sq_idx = self.env.state_names.index('i_sq') - self.torque_idx = self.env.state_names.index('torque') - self.u_sa_idx = environment.state_names.index('u_sa') - self.u_sd_idx = environment.state_names.index('u_sd') - self.u_sq_idx = environment.state_names.index('u_sq') - self.omega_idx = environment.state_names.index('omega') + self.i_sd_idx = self.env.state_names.index("i_sd") + self.i_sq_idx = self.env.state_names.index("i_sq") + self.torque_idx = self.env.state_names.index("torque") + self.u_sa_idx = environment.state_names.index("u_sa") + self.u_sd_idx = environment.state_names.index("u_sd") + self.u_sq_idx = environment.state_names.index("u_sq") + self.omega_idx = environment.state_names.index("omega") self.limits = self.env.physical_system.limits - p_gain = stages[0][1]['p_gain'] * 2 * tau_s ** 2 # flux controller p gain + p_gain = stages[0][1]["p_gain"] * 2 * tau_s**2 # flux controller p gain i_gain = p_gain / self.tau # flux controller i gain - self.psi_controller = PIController(self.env, p_gain=p_gain, i_gain=i_gain) # flux controller + self.psi_controller = PIController( + self.env, p_gain=p_gain, i_gain=i_gain + ) # flux controller self.torque_count = 1001 @@ -64,15 +73,17 @@ def __init__(self, environment, stages, plot_torque=True, plot_modulation=False, self.a_max = 1 # maximum modulation level self.k_ = 0.8 d = 2 # damping of the modulation controller - alpha = d / (d - np.sqrt(d ** 2 - 1)) - self.i_gain = 1 / (self.l_s / (1.25 * self.r_s)) * (alpha - 1) / alpha ** 2 + alpha = d / (d - np.sqrt(d**2 - 1)) + self.i_gain = 1 / (self.l_s / (1.25 * self.r_s)) * (alpha - 1) / alpha**2 self.u_dc = np.sqrt(3) * self.limits[self.u_sa_idx] self.limited = False self.integrated = 0 self.psi_high = 0.1 * self.psi_max self.psi_low = -self.psi_max - self.integrated_reset = 0.5 * self.psi_low # Reset value of the modulation controller + self.integrated_reset = ( + 0.5 * self.psi_low + ) # Reset value of the modulation controller self.plot_torque = plot_torque self.plot_modulation = plot_modulation @@ -82,19 +93,23 @@ def __init__(self, environment, stages, plot_torque=True, plot_modulation=False, def intitialize_torque_plot(self): plt.ion() - self.fig_torque = plt.figure('Torque Controller') + self.fig_torque = plt.figure("Torque Controller") self.psi_opt_plot = plt.subplot2grid((1, 2), (0, 0)) self.t_max_plot = plt.subplot2grid((1, 2), (0, 1)) - self.psi_opt_plot.plot(self.psi_opt_t[0], self.psi_opt_t[1], label='$\Psi^*_{r, opt}(T^*)$') + self.psi_opt_plot.plot( + self.psi_opt_t[0], self.psi_opt_t[1], label="$\Psi^*_{r, opt}(T^*)$" + ) self.psi_opt_plot.grid() - self.psi_opt_plot.set_xlabel('T / Nm') - self.psi_opt_plot.set_ylabel('$\Psi$ / Vs') + self.psi_opt_plot.set_xlabel("T / Nm") + self.psi_opt_plot.set_ylabel("$\Psi$ / Vs") self.psi_opt_plot.legend() - self.t_max_plot.plot(self.t_max_psi[1], self.t_max_psi[0], label='$T_{max}(\Psi_{max})$') + self.t_max_plot.plot( + self.t_max_psi[1], self.t_max_psi[0], label="$T_{max}(\Psi_{max})$" + ) self.t_max_plot.grid() - self.t_max_plot.set_xlabel('$\Psi$ / Vs') - self.t_max_plot.set_ylabel('T / Nm') + self.t_max_plot.set_xlabel("$\Psi$ / Vs") + self.t_max_plot.set_ylabel("T / Nm") self.t_max_plot.legend() def psi_opt(self): @@ -103,11 +118,18 @@ def psi_opt(self): i_sd = np.linspace(0, self.limits[self.i_sd_idx], self.i_sd_count) for t in np.linspace(self.t_minimum, self.t_maximum, self.torque_count): if t != 0: - i_sq = t / (3/2 * self.p * self.l_m ** 2 / self.l_r * i_sd[1:]) - pv = 3 / 2 * (self.r_s * np.power(i_sd[1:], 2) + ( - self.r_s + self.r_r * self.l_m ** 2 / self.l_r ** 2) * np.power(i_sq, 2)) # Calculate losses - - i_idx = np.argmin(pv) # Minimize losses + i_sq = t / (3 / 2 * self.p * self.l_m**2 / self.l_r * i_sd[1:]) + pv = ( + 3 + / 2 + * ( + self.r_s * np.power(i_sd[1:], 2) + + (self.r_s + self.r_r * self.l_m**2 / self.l_r**2) + * np.power(i_sq, 2) + ) + ) # Calculate losses + + i_idx = np.argmin(pv) # Minimize losses i_sd_opt = i_sd[i_idx] i_sq_opt = i_sq[i_idx] else: @@ -128,7 +150,11 @@ def t_max(self): for psi_ in psi: i_sd = psi_ / self.l_m - i_sq = np.sqrt(self.nominal_values[self.u_sd_idx] ** 2 / (self.nominal_values[self.omega_idx] ** 2 * self.l_s ** 2) - i_sd ** 2) + i_sq = np.sqrt( + self.nominal_values[self.u_sd_idx] ** 2 + / (self.nominal_values[self.omega_idx] ** 2 * self.l_s**2) + - i_sd**2 + ) t = 3 / 2 * self.p * self.l_m / self.l_r * psi_ * i_sq t_val.append(t) @@ -147,7 +173,13 @@ def t_max(self): def get_psi_opt(self, torque): torque = np.clip(torque, self.t_minimum, self.t_maximum) - return int(round((torque - self.t_minimum) / (self.t_maximum - self.t_minimum) * (self.torque_count - 1))) + return int( + round( + (torque - self.t_minimum) + / (self.t_maximum - self.t_minimum) + * (self.torque_count - 1) + ) + ) def get_t_max(self, psi): psi = np.clip(psi, 0, self.psi_max) @@ -155,16 +187,16 @@ def get_t_max(self, psi): def control(self, state, torque, psi_abs): """ - This main method is called by the CascadedFieldOrientedControllerRotorFluxObserver to calculate reference - values for the i_sd and i_sq currents from a given torque reference. + This main method is called by the CascadedFieldOrientedControllerRotorFluxObserver to calculate reference + values for the i_sd and i_sq currents from a given torque reference. - Args: - state: state of the gym-electric-motor environment - torque: reference value for the torque - psi_abs: amount of the estimated flux + Args: + state: state of the gym-electric-motor environment + torque: reference value for the torque + psi_abs: amount of the estimated flux - Returns: - Reference values for the currents i_sq and i_sd, optimal flux + Returns: + Reference values for the currents i_sq and i_sd, optimal flux """ # Calculate the optimal flux @@ -178,14 +210,24 @@ def control(self, state, torque, psi_abs): # Calculate the reference for i_sd i_sd_ = self.psi_controller.control(psi_abs, psi_opt) - i_sd = np.clip(i_sd_, -0.9 * self.nominal_values[self.i_sd_idx], 0.9 * self.nominal_values[self.i_sd_idx]) + i_sd = np.clip( + i_sd_, + -0.9 * self.nominal_values[self.i_sd_idx], + 0.9 * self.nominal_values[self.i_sd_idx], + ) if i_sd_ == i_sd: self.psi_controller.integrate(psi_abs, psi_opt) # Calculate the reference for i_sq - i_sq = np.clip(torque / max(psi_abs, 0.001) * 2 / 3 / self.p * self.l_r / self.l_m, -self.nominal_values[self.i_sq_idx], self.nominal_values[self.i_sq_idx]) - if self.nominal_values[self.i_sq_idx] < np.sqrt(i_sq ** 2 + i_sd ** 2): - i_sq = np.sign(i_sq) * np.sqrt(self.nominal_values[self.i_sq_idx] ** 2 - i_sd ** 2) + i_sq = np.clip( + torque / max(psi_abs, 0.001) * 2 / 3 / self.p * self.l_r / self.l_m, + -self.nominal_values[self.i_sq_idx], + self.nominal_values[self.i_sq_idx], + ) + if self.nominal_values[self.i_sq_idx] < np.sqrt(i_sq**2 + i_sd**2): + i_sq = np.sign(i_sq) * np.sqrt( + self.nominal_values[self.i_sq_idx] ** 2 - i_sd**2 + ) # Update plots if self.plot_torque: @@ -200,8 +242,12 @@ def control(self, state, torque, psi_abs): self.psi_list.append(psi_opt) if self.k % self.update_interval == 0: - self.psi_opt_plot.scatter(self.torque_list, self.psi_list, c='tab:blue', s=3) - self.t_max_plot.scatter(self.psi_list, self.torque_list, c='tab:blue', s=3) + self.psi_opt_plot.scatter( + self.torque_list, self.psi_list, c="tab:blue", s=3 + ) + self.t_max_plot.scatter( + self.psi_list, self.torque_list, c="tab:blue", s=3 + ) self.fig_torque.canvas.draw() self.fig_torque.canvas.flush_events() @@ -210,13 +256,20 @@ def control(self, state, torque, psi_abs): self.psi_list = [] self.k += 1 - return i_sq / self.limits[self.i_sq_idx], i_sd / self.limits[self.i_sd_idx], psi_opt + return i_sq / self.limits[self.i_sq_idx], i_sd / self.limits[ + self.i_sd_idx + ], psi_opt def modulation_control(self, state): - # Calculate modulation - a = 2 * np.sqrt((state[self.u_sd_idx] * self.limits[self.u_sd_idx]) ** 2 + ( - state[self.u_sq_idx] * self.limits[self.u_sq_idx]) ** 2) / self.u_dc + a = ( + 2 + * np.sqrt( + (state[self.u_sd_idx] * self.limits[self.u_sd_idx]) ** 2 + + (state[self.u_sq_idx] * self.limits[self.u_sq_idx]) ** 2 + ) + / self.u_dc + ) # if a > 1.01 * self.a_max: @@ -230,7 +283,9 @@ def modulation_control(self, state): k_i = 2 * np.abs(omega) * self.p / self.u_dc i_gain = self.i_gain * k_i - psi_delta = i_gain * (a_delta * self.tau + self.integrated) # Calculate Flux delta + psi_delta = i_gain * ( + a_delta * self.tau + self.integrated + ) # Calculate Flux delta # Check, if limits are violated if self.psi_low <= psi_delta <= self.psi_high: @@ -251,40 +306,50 @@ def modulation_control(self, state): self.psi_delta_list.append(psi_delta) if self.k % self.update_interval == 0: - self.a_plot.scatter(self.k_list_a, self.a_list, c='tab:blue', s=3) - self.psi_delta_plot.scatter(self.k_list_a, self.psi_delta_list, c='tab:blue', s=3) - self.a_plot.set_xlim(max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1)) - self.psi_delta_plot.set_xlim(max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1)) - self.k_list_a = [] - self.a_list = [] - self.psi_delta_list = [] + self.a_plot.scatter(self.k_list_a, self.a_list, c="tab:blue", s=3) + self.psi_delta_plot.scatter( + self.k_list_a, self.psi_delta_list, c="tab:blue", s=3 + ) + self.a_plot.set_xlim( + max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1) + ) + self.psi_delta_plot.set_xlim( + max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1) + ) + self.k_list_a = [] + self.a_list = [] + self.psi_delta_list = [] return psi def initialize_modulation_plot(self): if self.plot_modulation: plt.ion() - self.fig_modulation = plt.figure('Modulation Controller') + self.fig_modulation = plt.figure("Modulation Controller") self.a_plot = plt.subplot2grid((1, 2), (0, 0)) self.psi_delta_plot = plt.subplot2grid((1, 2), (0, 1)) # Define modulation plot - self.a_plot.set_title('Modulation') - self.a_plot.axhline(self.k_ * self.a_max, c='tab:orange', label=r'$a^*$') - self.a_plot.plot([], [], c='tab:blue', label='a') - self.a_plot.set_xlabel('t / s') - self.a_plot.set_ylabel('a') + self.a_plot.set_title("Modulation") + self.a_plot.axhline(self.k_ * self.a_max, c="tab:orange", label=r"$a^*$") + self.a_plot.plot([], [], c="tab:blue", label="a") + self.a_plot.set_xlabel("t / s") + self.a_plot.set_ylabel("a") self.a_plot.grid(True) self.a_plot.set_xlim(0, 1) self.a_plot.legend(loc=2) # Define the delta flux plot - self.psi_delta_plot.set_title(r'$\Psi_\mathrm{\Delta}$') - self.psi_delta_plot.axhline(self.psi_low, c='tab:red', linestyle='dashed', label='Limit') - self.psi_delta_plot.axhline(self.psi_high, c='tab:red', linestyle='dashed') - self.psi_delta_plot.plot([], [], c='tab:blue', label=r'$\Psi_\mathrm{\Delta}$') - self.psi_delta_plot.set_xlabel('t / s') - self.psi_delta_plot.set_ylabel(r'$\Psi_\mathrm{\Delta} / Vs$') + self.psi_delta_plot.set_title(r"$\Psi_\mathrm{\Delta}$") + self.psi_delta_plot.axhline( + self.psi_low, c="tab:red", linestyle="dashed", label="Limit" + ) + self.psi_delta_plot.axhline(self.psi_high, c="tab:red", linestyle="dashed") + self.psi_delta_plot.plot( + [], [], c="tab:blue", label=r"$\Psi_\mathrm{\Delta}$" + ) + self.psi_delta_plot.set_xlabel("t / s") + self.psi_delta_plot.set_ylabel(r"$\Psi_\mathrm{\Delta} / Vs$") self.psi_delta_plot.grid(True) self.psi_delta_plot.set_xlim(0, 1) self.psi_delta_plot.legend(loc=2) diff --git a/examples/classic_controllers/controllers/on_off_controller.py b/examples/classic_controllers/controllers/on_off_controller.py index 010a2358..300cd46d 100644 --- a/examples/classic_controllers/controllers/on_off_controller.py +++ b/examples/classic_controllers/controllers/on_off_controller.py @@ -4,9 +4,17 @@ class OnOffController(DiscreteController): """This is a hysteresis controller with two possible output states.""" - def __init__(self, environment, action_space, hysteresis=0.02, param_dict={}, cascaded=False, control_e=False, - **controller_kwargs): - self.hysteresis = param_dict.get('hysteresis', hysteresis) + def __init__( + self, + environment, + action_space, + hysteresis=0.02, + param_dict={}, + cascaded=False, + control_e=False, + **controller_kwargs, + ): + self.hysteresis = param_dict.get("hysteresis", hysteresis) self.switch_on_level = 1 self.switch_off_level = 2 if action_space in [3, 4] and not control_e else 0 diff --git a/examples/classic_controllers/controllers/pi_controller.py b/examples/classic_controllers/controllers/pi_controller.py index 37ac66ce..a07c67a5 100644 --- a/examples/classic_controllers/controllers/pi_controller.py +++ b/examples/classic_controllers/controllers/pi_controller.py @@ -1,18 +1,18 @@ -from .continuous_controller import PController, IController +from .continuous_controller import IController, PController class PIController(PController, IController): """ - The PI-Controller is a combination of the base P-Controller and the base I-Controller. The integrate function is - executed after checking compliance with the limitations in the higher-level controller stage in order to adjust - the I-component of the controller accordingly. + The PI-Controller is a combination of the base P-Controller and the base I-Controller. The integrate function is + executed after checking compliance with the limitations in the higher-level controller stage in order to adjust + the I-component of the controller accordingly. """ def __init__(self, environment, p_gain=5, i_gain=5, param_dict={}, **controller_kwargs): - self.tau = environment.physical_system.tau + self.tau = environment.unwrapped.physical_system.tau - p_gain = param_dict.get('p_gain', p_gain) - i_gain = param_dict.get('i_gain', i_gain) + p_gain = param_dict.get("p_gain", p_gain) + i_gain = param_dict.get("i_gain", i_gain) PController.__init__(self, p_gain) IController.__init__(self, i_gain) diff --git a/examples/classic_controllers/controllers/pid_controller.py b/examples/classic_controllers/controllers/pid_controller.py index 42ded6ca..99d085f9 100644 --- a/examples/classic_controllers/controllers/pid_controller.py +++ b/examples/classic_controllers/controllers/pid_controller.py @@ -5,20 +5,30 @@ class PIDController(PIController, DController): """The PID-Controller is a combination of the PI-Controller and the base P-Controller.""" - def __init__(self, environment, p_gain=5, i_gain=5, d_gain=0.005, param_dict={}, **controller_kwargs): - p_gain = param_dict.get('p_gain', p_gain) - i_gain = param_dict.get('i_gain', i_gain) - d_gain = param_dict.get('d_gain', d_gain) + def __init__( + self, + environment, + p_gain=5, + i_gain=5, + d_gain=0.005, + param_dict={}, + **controller_kwargs, + ): + p_gain = param_dict.get("p_gain", p_gain) + i_gain = param_dict.get("i_gain", i_gain) + d_gain = param_dict.get("d_gain", d_gain) PIController.__init__(self, environment, p_gain, i_gain) DController.__init__(self, d_gain) def control(self, state, reference): - action = PIController.control(self, state, reference) + self.d_gain * ( - reference - state - self.e_old) / self.tau + action = ( + PIController.control(self, state, reference) + + self.d_gain * (reference - state - self.e_old) / self.tau + ) self.e_old = reference - state return action def reset(self): PIController.reset(self) - self.e_old = 0 \ No newline at end of file + self.e_old = 0 diff --git a/examples/classic_controllers/controllers/plot_external_data.py b/examples/classic_controllers/controllers/plot_external_data.py index 87fc223f..89e00345 100644 --- a/examples/classic_controllers/controllers/plot_external_data.py +++ b/examples/classic_controllers/controllers/plot_external_data.py @@ -1,4 +1,10 @@ -def plot(external_reference_plots=(), state_names=(), external_plot=(), visualization=True, external_data=()): +def plot( + external_reference_plots=(), + state_names=(), + external_plot=(), + visualization=True, + external_data=(), +): """ This method passes the latest internally generated references of the controller the ExternalReferencePlots. The GEM-Environment uses this data to plot these references with the according states within its MotorDashboard. @@ -22,26 +28,27 @@ def plot(external_reference_plots=(), state_names=(), external_plot=(), visualiz # Check, if the are external ref plots if len(external_ref_plots) != 0: # Read in the indices of the states and refrences - ref_state_idxs = external_data['ref_state'] + ref_state_idxs = external_data["ref_state"] plot_state_idxs = [ - list(state_names).index(external_ref_plot.state_plot) for external_ref_plot in external_reference_plots + list(state_names).index(external_ref_plot.state_plot) + for external_ref_plot in external_reference_plots ] # Read in the data of the reference - ref_values = external_data['ref_value'] + ref_values = external_data["ref_value"] # Pass the values to the ExternallyReferencedStatePlot object for ref_state_idx, ref_value in zip(ref_state_idxs, ref_values): try: plot_idx = plot_state_idxs.index(ref_state_idx) except ValueError: - pass # Ignore reference input, if there is no reference in this plot + pass # Ignore reference input, if there is no reference in this plot else: external_ref_plots[plot_idx].external_reference(ref_value) # Check if the are external plots and pass the data to the ExternalPlot object if len(external_plots) != 0: - ext_state = external_data['external'] + ext_state = external_data["external"] for ext_plot, ext_data in zip(external_plots, ext_state): ext_plot.add_data(ext_data) diff --git a/examples/classic_controllers/controllers/three_point_controller.py b/examples/classic_controllers/controllers/three_point_controller.py index 597bd07a..c6cd825f 100644 --- a/examples/classic_controllers/controllers/three_point_controller.py +++ b/examples/classic_controllers/controllers/three_point_controller.py @@ -4,14 +4,27 @@ class ThreePointController(DiscreteController): """This is a hysteresis controller with three possible output states.""" - def __init__(self, environment, action_space, switch_to_positive_level=0.02, switch_to_negative_level=0.02, - switch_to_neutral_from_positive=0.01, switch_to_neutral_from_negative=0.01, param_dict={}, - cascaded=False, control_e=False, **controller_kwargs): - - self.pos = param_dict.get('switch_to_positive_level', switch_to_positive_level) - self.neg = param_dict.get('switch_to_negative_level', switch_to_negative_level) - self.neutral_from_pos = param_dict.get('switch_to_neutral_from_positive', switch_to_neutral_from_positive) - self.neutral_from_neg = param_dict.get('switch_to_neutral_from_negative', switch_to_neutral_from_negative) + def __init__( + self, + environment, + action_space, + switch_to_positive_level=0.02, + switch_to_negative_level=0.02, + switch_to_neutral_from_positive=0.01, + switch_to_neutral_from_negative=0.01, + param_dict={}, + cascaded=False, + control_e=False, + **controller_kwargs, + ): + self.pos = param_dict.get("switch_to_positive_level", switch_to_positive_level) + self.neg = param_dict.get("switch_to_negative_level", switch_to_negative_level) + self.neutral_from_pos = param_dict.get( + "switch_to_neutral_from_positive", switch_to_neutral_from_positive + ) + self.neutral_from_neg = param_dict.get( + "switch_to_neutral_from_negative", switch_to_neutral_from_negative + ) self.negative = 2 if action_space in [3, 4, 8] and not control_e else 0 if cascaded: @@ -23,11 +36,14 @@ def __init__(self, environment, action_space, switch_to_positive_level=0.02, swi self.recent_action = self.neutral def control(self, state, reference): - if reference - state > self.pos or ((self.neutral_from_pos < reference - state) and self.recent_action == 1): + if reference - state > self.pos or ( + (self.neutral_from_pos < reference - state) and self.recent_action == 1 + ): self.action = self.positive self.recent_action = 1 elif reference - state < -self.neg or ( - (-self.neutral_from_neg > reference - state) and self.recent_action == 2): + (-self.neutral_from_neg > reference - state) and self.recent_action == 2 + ): self.action = self.negative self.recent_action = 2 else: @@ -38,4 +54,4 @@ def control(self, state, reference): def reset(self): self.action = self.neutral - self.recent_action = self.neutral \ No newline at end of file + self.recent_action = self.neutral diff --git a/examples/classic_controllers/controllers/torque_to_current_conversion.py b/examples/classic_controllers/controllers/torque_to_current_conversion.py index 54362614..ca1f19e2 100644 --- a/examples/classic_controllers/controllers/torque_to_current_conversion.py +++ b/examples/classic_controllers/controllers/torque_to_current_conversion.py @@ -1,63 +1,73 @@ import numpy as np from matplotlib import pyplot as plt from matplotlib import cm -from mpl_toolkits.mplot3d import Axes3D from scipy.interpolate import griddata 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 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 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 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). + 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 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 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 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). """ - def __init__(self, environment, plot_torque=True, plot_modulation=False, update_interval=1000, - torque_control='interpolate'): - + def __init__( + self, + environment, + plot_torque=True, + plot_modulation=False, + update_interval=1000, + torque_control="interpolate", + ): self.mp = environment.physical_system.electrical_motor.motor_parameter self.limit = environment.physical_system.limits self.nominal_values = environment.physical_system.nominal_state self.torque_control = torque_control - self.l_d = self.mp['l_d'] - self.l_q = self.mp['l_q'] - self.p = self.mp['p'] - self.psi_p = self.mp.get('psi_p', 0) + self.l_d = self.mp["l_d"] + self.l_q = self.mp["l_q"] + self.p = self.mp["p"] + self.psi_p = self.mp.get("psi_p", 0) self.invert = -1 if (self.psi_p == 0 and self.l_q < self.l_d) else 1 self.tau = environment.physical_system.tau - self.omega_idx = environment.state_names.index('omega') - self.i_sd_idx = environment.state_names.index('i_sd') - self.i_sq_idx = environment.state_names.index('i_sq') - self.u_sd_idx = environment.state_names.index('u_sd') - self.u_sq_idx = environment.state_names.index('u_sq') - self.torque_idx = environment.state_names.index('torque') - self.epsilon_idx = environment.state_names.index('epsilon') + self.omega_idx = environment.state_names.index("omega") + self.i_sd_idx = environment.state_names.index("i_sd") + self.i_sq_idx = environment.state_names.index("i_sq") + self.u_sd_idx = environment.state_names.index("u_sd") + self.u_sq_idx = environment.state_names.index("u_sq") + self.torque_idx = environment.state_names.index("torque") + self.epsilon_idx = environment.state_names.index("epsilon") - self.a_max = 2 / np.sqrt(3) # maximum modulation level + self.a_max = 2 / np.sqrt(3) # maximum modulation level self.k_ = 0.95 - d = 1.2 # damping of the modulation controller - alpha = d / (d - np.sqrt(d ** 2 - 1)) - self.i_gain = 1 / (self.mp['l_q'] / (1.25 * self.mp['r_s'])) * (alpha - 1) / alpha ** 2 + d = 1.2 # damping of the modulation controller + alpha = d / (d - np.sqrt(d**2 - 1)) + self.i_gain = ( + 1 / (self.mp["l_q"] / (1.25 * self.mp["r_s"])) * (alpha - 1) / alpha**2 + ) - self.u_a_idx = environment.state_names.index('u_a') + self.u_a_idx = environment.state_names.index("u_a") self.u_dc = np.sqrt(3) * self.limit[self.u_a_idx] self.limited = False self.integrated = 0 - self.psi_high = 0.2 * np.sqrt((self.psi_p + self.l_d * self.nominal_values[self.i_sd_idx]) ** 2 + ( - self.l_q * self.nominal_values[self.i_sq_idx]) ** 2) + self.psi_high = 0.2 * np.sqrt( + (self.psi_p + self.l_d * self.nominal_values[self.i_sd_idx]) ** 2 + + (self.l_q * self.nominal_values[self.i_sq_idx]) ** 2 + ) self.psi_low = -self.psi_high - self.integrated_reset = 0.01 * self.psi_low # Reset value of the modulation controller + self.integrated_reset = ( + 0.01 * self.psi_low + ) # Reset value of the modulation controller self.t_count = 250 self.psi_count = 250 @@ -71,15 +81,21 @@ def __init__(self, environment, plot_torque=True, plot_modulation=False, update_ def mtpc(): def i_q_(i_d, torque): - return torque / (i_d * (self.l_d - self.l_q) + self.psi_p) / (1.5 * self.p) + return ( + torque / (i_d * (self.l_d - self.l_q) + self.psi_p) / (1.5 * self.p) + ) def i_d_(i_q, torque): return -np.abs(torque / (1.5 * self.p * (self.l_d - self.l_q) * i_q)) # calculate the maximum torque self.max_torque = max( - 1.5 * self.p * (self.psi_p + (self.l_d - self.l_q) * (-self.limit[self.i_sd_idx])) * self.limit[ - self.i_sq_idx], self.limit[self.torque_idx]) + 1.5 + * self.p + * (self.psi_p + (self.l_d - self.l_q) * (-self.limit[self.i_sd_idx])) + * self.limit[self.i_sq_idx], + self.limit[self.torque_idx], + ) torque = np.linspace(-self.max_torque, self.max_torque, self.t_count) characteristic = [] @@ -88,10 +104,16 @@ def i_d_(i_q, torque): if self.l_d == self.l_q: i_d = 0 else: - i_d = np.linspace(-2.5*self.limit[self.i_sd_idx], 0, self.i_count) + i_d = np.linspace( + -2.5 * self.limit[self.i_sd_idx], 0, self.i_count + ) i_q = i_q_(i_d, t) else: - i_q = np.linspace(-2.5*self.limit[self.i_sq_idx], 2.5*self.limit[self.i_sq_idx], self.i_count) + i_q = np.linspace( + -2.5 * self.limit[self.i_sq_idx], + 2.5 * self.limit[self.i_sq_idx], + self.i_count, + ) if self.l_d == self.l_q: i_d = 0 else: @@ -108,14 +130,18 @@ def i_d_(i_q, torque): i_d_ret = i_d[min_idx] # The flow is finally calculated from the currents - psi = np.sqrt((self.psi_p + self.l_d * i_d_ret) ** 2 + (self.l_q * i_q_ret) ** 2) + psi = np.sqrt( + (self.psi_p + self.l_d * i_d_ret) ** 2 + (self.l_q * i_q_ret) ** 2 + ) characteristic.append([t, i_d_ret, i_q_ret, psi]) return np.array(characteristic) def mtpf(): # maximum flux is calculated - self.psi_max_mtpf = np.sqrt((self.psi_p + self.l_d * self.nominal_values[self.i_sd_idx]) ** 2 + ( - self.l_q * self.nominal_values[self.i_sq_idx]) ** 2) + self.psi_max_mtpf = np.sqrt( + (self.psi_p + self.l_d * self.nominal_values[self.i_sd_idx]) ** 2 + + (self.l_q * self.nominal_values[self.i_sq_idx]) ** 2 + ) psi = np.linspace(0, self.psi_max_mtpf, self.psi_count) i_d = np.linspace(-self.nominal_values[self.i_sd_idx], 0, self.i_count) i_d_best = 0 @@ -132,20 +158,42 @@ def mtpf(): else: if self.psi_p == 0: - i_q_best = psi_ / np.sqrt(self.l_d ** 2 + self.l_q ** 2) + i_q_best = psi_ / np.sqrt(self.l_d**2 + self.l_q**2) i_d_best = -i_q_best - t = 1.5 * self.p * (self.psi_p + (self.l_d - self.l_q) * i_d_best) * i_q_best + t = ( + 1.5 + * self.p + * (self.psi_p + (self.l_d - self.l_q) * i_d_best) + * i_q_best + ) else: - i_d_idx = np.where(psi_ ** 2 - np.power(self.psi_p + self.l_d * i_d, 2) >= 0) + i_d_idx = np.where( + psi_**2 - np.power(self.psi_p + self.l_d * i_d, 2) >= 0 + ) i_d_ = i_d[i_d_idx] # calculate all possible i_q currents for i_d currents - i_q = np.sqrt(psi_ ** 2 - np.power(self.psi_p + self.l_d * i_d_, 2)) / self.l_q - i_idx = np.where(np.sqrt(np.power(i_q / self.nominal_values[self.i_sq_idx], 2) + np.power( - i_d_ / self.nominal_values[self.i_sd_idx], 2)) <= 1) + i_q = ( + np.sqrt( + psi_**2 - np.power(self.psi_p + self.l_d * i_d_, 2) + ) + / self.l_q + ) + i_idx = np.where( + np.sqrt( + np.power(i_q / self.nominal_values[self.i_sq_idx], 2) + + np.power(i_d_ / self.nominal_values[self.i_sd_idx], 2) + ) + <= 1 + ) i_d_ = i_d_[i_idx] i_q = i_q[i_idx] - torque = 1.5 * self.p * (self.psi_p + (self.l_d - self.l_q) * i_d_) * i_q + torque = ( + 1.5 + * self.p + * (self.psi_p + (self.l_d - self.l_q) * i_d_) + * i_q + ) # choose the maximum torque if np.size(torque) > 0: @@ -153,12 +201,24 @@ def mtpf(): i_idx = np.where(torque == t)[0][0] i_d_best = i_d_[i_idx] i_q_best = i_q[i_idx] - if np.sqrt(i_d_best**2 + i_q_best**2) <= self.nominal_values[self.i_sq_idx]: + if ( + np.sqrt(i_d_best**2 + i_q_best**2) + <= self.nominal_values[self.i_sq_idx] + ): psi_i_d_q.append([psi_, t, i_d_best, i_q_best]) psi_i_d_q = np.array(psi_i_d_q) self.psi_max_mtpf = np.max(psi_i_d_q[:, 0]) - psi_i_d_q_neg = np.rot90(np.array([psi_i_d_q[:, 0], -psi_i_d_q[:, 1], psi_i_d_q[:, 2], -psi_i_d_q[:, 3]])) + psi_i_d_q_neg = np.rot90( + np.array( + [ + psi_i_d_q[:, 0], + -psi_i_d_q[:, 1], + psi_i_d_q[:, 2], + -psi_i_d_q[:, 3], + ] + ) + ) psi_i_d_q = np.append(psi_i_d_q_neg, psi_i_d_q, axis=0) return np.array(psi_i_d_q) @@ -168,22 +228,36 @@ def mtpf(): # Calculate a list with the flux and the corresponding torque of the mtpc characteristic self.psi_t = np.sqrt( - np.power(self.psi_p + self.l_d * self.mtpc[:, 1], 2) + np.power(self.l_q * self.mtpc[:, 2], 2)) + np.power(self.psi_p + self.l_d * self.mtpc[:, 1], 2) + + np.power(self.l_q * self.mtpc[:, 2], 2) + ) self.psi_t = np.array([self.mtpc[:, 0], self.psi_t]) # define a grid for the two current components - self.i_q_max = np.linspace(-self.nominal_values[self.i_sq_idx], self.nominal_values[self.i_sq_idx], self.i_count) - self.i_d_max = -np.sqrt(self.nominal_values[self.i_sq_idx] ** 2 - np.power(self.i_q_max, 2)) + self.i_q_max = np.linspace( + -self.nominal_values[self.i_sq_idx], + self.nominal_values[self.i_sq_idx], + self.i_count, + ) + self.i_d_max = -np.sqrt( + self.nominal_values[self.i_sq_idx] ** 2 - np.power(self.i_q_max, 2) + ) i_count_mgrid = self.i_count * 1j - i_d, i_q = np.mgrid[-self.limit[self.i_sd_idx]:0:i_count_mgrid, - -self.limit[self.i_sq_idx]:self.limit[self.i_sq_idx]:i_count_mgrid / 2] + i_d, i_q = np.mgrid[ + -self.limit[self.i_sd_idx] : 0 : i_count_mgrid, + -self.limit[self.i_sq_idx] : self.limit[self.i_sq_idx] : i_count_mgrid / 2, + ] i_d = i_d.flatten() i_q = i_q.flatten() # Decide between SPMSM and IPMSM if self.l_d != self.l_q: - idx = np.where(np.sign(self.psi_p + i_d * self.l_d) * np.power(self.psi_p + i_d * self.l_d, 2) + np.power( - i_q * self.l_q, 2) > 0) + idx = np.where( + np.sign(self.psi_p + i_d * self.l_d) + * np.power(self.psi_p + i_d * self.l_d, 2) + + np.power(i_q * self.l_q, 2) + > 0 + ) else: idx = np.where(self.psi_p + i_d * self.l_d > 0) @@ -192,7 +266,9 @@ def mtpf(): # Calculate torque and flux for the grid of the currents t = self.p * 1.5 * (self.psi_p + (self.l_d - self.l_q) * i_d) * i_q - psi = np.sqrt(np.power(self.l_d * i_d + self.psi_p, 2) + np.power(self.l_q * i_q, 2)) + psi = np.sqrt( + np.power(self.l_d * i_d + self.psi_p, 2) + np.power(self.l_q * i_q, 2) + ) self.t_min = np.amin(t) self.t_max = np.amax(t) @@ -200,7 +276,7 @@ def mtpf(): self.psi_min = np.amin(psi) self.psi_max = np.amax(psi) - if torque_control == 'analytical': + if torque_control == "analytical": res = [] for psi in np.linspace(self.psi_min, self.psi_max, self.psi_count): ret = [] @@ -216,16 +292,22 @@ def mtpf(): self.i_d_inter_plot = self.i_d_inter.T self.i_q_inter_plot = self.i_q_inter.T - elif torque_control == 'interpolate': + elif torque_control == "interpolate": # Interpolate the torque and flux to get lists for the optimal currents - self.t_grid, self.psi_grid = np.mgrid[np.amin(t):np.amax(t):np.complex(0, self.t_count), - self.psi_min:self.psi_max:np.complex(self.psi_count)] - self.i_q_inter = griddata((t, psi), i_q, (self.t_grid, self.psi_grid), method='linear') - self.i_d_inter = griddata((t, psi), i_d, (self.t_grid, self.psi_grid), method='linear') + self.t_grid, self.psi_grid = np.mgrid[ + np.amin(t) : np.amax(t) : np.complex(0, self.t_count), + self.psi_min : self.psi_max : np.complex(self.psi_count), + ] + self.i_q_inter = griddata( + (t, psi), i_q, (self.t_grid, self.psi_grid), method="linear" + ) + self.i_d_inter = griddata( + (t, psi), i_d, (self.t_grid, self.psi_grid), method="linear" + ) self.i_d_inter_plot = self.i_d_inter self.i_q_inter_plot = self.i_q_inter - elif torque_control != 'online': + elif torque_control != "online": raise NotImplementedError self.k = 0 @@ -236,95 +318,134 @@ def mtpf(): def intitialize_torque_plot(self): if self.plot_torque: plt.ion() - self.fig_torque = plt.figure('Torque Controller') + self.fig_torque = plt.figure("Torque Controller") # Check if current, torque, flux characteristics could be plotted - if self.torque_control in ['interpolate', 'analytical']: + if self.torque_control in ["interpolate", "analytical"]: self.i_d_q_characteristic_ = plt.subplot2grid((2, 3), (0, 0), rowspan=2) self.psi_plot = plt.subplot2grid((2, 3), (0, 1)) - self.i_d_plot = plt.subplot2grid((2, 3), (0, 2), projection='3d') + self.i_d_plot = plt.subplot2grid((2, 3), (0, 2), projection="3d") self.torque_plot = plt.subplot2grid((2, 3), (1, 1)) - self.i_q_plot = plt.subplot2grid((2, 3), (1, 2), projection='3d') + self.i_q_plot = plt.subplot2grid((2, 3), (1, 2), projection="3d") - elif self.torque_control == 'online': + elif self.torque_control == "online": self.i_d_q_characteristic_ = plt.subplot2grid((2, 2), (0, 0), rowspan=2) self.psi_plot = plt.subplot2grid((2, 2), (0, 1)) self.torque_plot = plt.subplot2grid((2, 2), (1, 1)) mtpc_i_idx = np.where( - np.sqrt(np.power(self.mtpc[:, 1], 2) + np.power(self.mtpc[:, 2], 2)) <= self.nominal_values[ - self.i_sd_idx]) + np.sqrt(np.power(self.mtpc[:, 1], 2) + np.power(self.mtpc[:, 2], 2)) + <= self.nominal_values[self.i_sd_idx] + ) # Define the plot for the current characteristics - self.i_d_q_characteristic_.set_title('$i_\mathrm{d,q_{ref}}$') - self.i_d_q_characteristic_.plot(self.mtpc[mtpc_i_idx, 1][0], self.mtpc[mtpc_i_idx, 2][0], label='MTPC', c='tab:orange') - self.i_d_q_characteristic_.plot(self.mtpf[:, 2], self.mtpf[:, 3], label=r'MTPF', c='tab:green') - self.i_d_q_characteristic_.plot(self.i_d_max, self.i_q_max, label=r'$i_\mathrm{max}$', c='tab:red') - self.i_d_q_characteristic_.plot([], [], label=r'$i_\mathrm{d,q}$', c='tab:blue') + self.i_d_q_characteristic_.set_title("$i_\mathrm{d,q_{ref}}$") + self.i_d_q_characteristic_.plot( + self.mtpc[mtpc_i_idx, 1][0], + self.mtpc[mtpc_i_idx, 2][0], + label="MTPC", + c="tab:orange", + ) + self.i_d_q_characteristic_.plot( + self.mtpf[:, 2], self.mtpf[:, 3], label=r"MTPF", c="tab:green" + ) + self.i_d_q_characteristic_.plot( + self.i_d_max, self.i_q_max, label=r"$i_\mathrm{max}$", c="tab:red" + ) + self.i_d_q_characteristic_.plot( + [], [], label=r"$i_\mathrm{d,q}$", c="tab:blue" + ) self.i_d_q_characteristic_.grid(True) self.i_d_q_characteristic_.legend(loc=2) - self.i_d_q_characteristic_.axis('equal') - self.i_d_q_characteristic_.set_xlabel(r'$i_\mathrm{d}$ / A') - self.i_d_q_characteristic_.set_ylabel(r'$i_\mathrm{q}$ / A') + self.i_d_q_characteristic_.axis("equal") + self.i_d_q_characteristic_.set_xlabel(r"$i_\mathrm{d}$ / A") + self.i_d_q_characteristic_.set_ylabel(r"$i_\mathrm{q}$ / A") # Define the plot for the flux characteristic - self.psi_plot.set_title(r'$\Psi^*_\mathrm{max}(T^*)$') - self.psi_plot.plot(self.psi_t[0], self.psi_t[1], label=r'$\Psi^*_\mathrm{max}(T^*)$', c='tab:orange') - self.psi_plot.plot([], [], label=r'$\Psi(T)$', c='tab:blue') + self.psi_plot.set_title(r"$\Psi^*_\mathrm{max}(T^*)$") + self.psi_plot.plot( + self.psi_t[0], + self.psi_t[1], + label=r"$\Psi^*_\mathrm{max}(T^*)$", + c="tab:orange", + ) + self.psi_plot.plot([], [], label=r"$\Psi(T)$", c="tab:blue") self.psi_plot.grid(True) - self.psi_plot.set_xlabel(r'T / Nm') - self.psi_plot.set_ylabel(r'$\Psi$ / Vs') + self.psi_plot.set_xlabel(r"T / Nm") + self.psi_plot.set_ylabel(r"$\Psi$ / Vs") self.psi_plot.set_ylim(bottom=0) self.psi_plot.legend(loc=2) # Define the plot for the torque characteristic torque = self.mtpf[:, 1] - torque[0:np.where(torque == np.min(torque))[0][0]] = np.min(torque) - torque[np.where(torque == np.max(torque))[0][0]:] = np.max(torque) - self.torque_plot.set_title(r'$T_\mathrm{max}(\Psi_\mathrm{max})$') - self.torque_plot.plot(self.mtpf[:, 0], torque, label=r'$T_\mathrm{max}(\Psi)$', c='tab:orange') - self.torque_plot.plot([], [], label=r'$T(\Psi)$', c='tab:blue') - self.torque_plot.set_xlabel(r'$\Psi$ / Vs') - self.torque_plot.set_ylabel(r'$T_\mathrm{max}$ / Nm') + torque[0 : np.where(torque == np.min(torque))[0][0]] = np.min(torque) + torque[np.where(torque == np.max(torque))[0][0] :] = np.max(torque) + self.torque_plot.set_title(r"$T_\mathrm{max}(\Psi_\mathrm{max})$") + self.torque_plot.plot( + self.mtpf[:, 0], torque, label=r"$T_\mathrm{max}(\Psi)$", c="tab:orange" + ) + self.torque_plot.plot([], [], label=r"$T(\Psi)$", c="tab:blue") + self.torque_plot.set_xlabel(r"$\Psi$ / Vs") + self.torque_plot.set_ylabel(r"$T_\mathrm{max}$ / Nm") self.torque_plot.grid(True) self.torque_plot.legend(loc=2) # Define the plot of currents - if self.torque_control in ['interpolate', 'analytical']: - self.i_q_plot.plot_surface(self.t_grid, self.psi_grid, self.i_q_inter_plot, cmap=cm.jet, linewidth=0, - vmin=np.nanmin(self.i_q_inter_plot), vmax=np.nanmax(self.i_q_inter_plot)) - self.i_q_plot.set_ylabel(r'$\Psi / Vs$') - self.i_q_plot.set_xlabel(r'$T / Nm$') - self.i_q_plot.set_title(r'$i_\mathrm{q}(T, \Psi)$') - - self.i_d_plot.plot_surface(self.t_grid, self.psi_grid, self.i_d_inter_plot, cmap=cm.jet, linewidth=0, - vmin=np.nanmin(self.i_d_inter_plot), vmax=np.nanmax(self.i_d_inter_plot)) - self.i_d_plot.set_ylabel(r'$\Psi / Vs$') - self.i_d_plot.set_xlabel(r'$T / Nm$') - self.i_d_plot.set_title(r'$i_\mathrm{d}(T, \Psi)$') + if self.torque_control in ["interpolate", "analytical"]: + self.i_q_plot.plot_surface( + self.t_grid, + self.psi_grid, + self.i_q_inter_plot, + cmap=cm.jet, + linewidth=0, + vmin=np.nanmin(self.i_q_inter_plot), + vmax=np.nanmax(self.i_q_inter_plot), + ) + self.i_q_plot.set_ylabel(r"$\Psi / Vs$") + self.i_q_plot.set_xlabel(r"$T / Nm$") + self.i_q_plot.set_title(r"$i_\mathrm{q}(T, \Psi)$") + + self.i_d_plot.plot_surface( + self.t_grid, + self.psi_grid, + self.i_d_inter_plot, + cmap=cm.jet, + linewidth=0, + vmin=np.nanmin(self.i_d_inter_plot), + vmax=np.nanmax(self.i_d_inter_plot), + ) + self.i_d_plot.set_ylabel(r"$\Psi / Vs$") + self.i_d_plot.set_xlabel(r"$T / Nm$") + self.i_d_plot.set_title(r"$i_\mathrm{d}(T, \Psi)$") def solve_analytical(self, torque, psi): """ - Assuming linear magnetization characteristics, the optimal currents for given torque and flux can be obtained - by solving the torque and flux equations. These lead to a fourth degree polynomial which can be solved - analytically. There are two ways to use this analytical solution for control. On the one hand, the currents - can be determined in advance as in the case of interpolation for different torques and fluxes and stored in a - LUT (torque_control='analytical'). On the other hand, the solution can be calculated at runtime with the - given torque and flux (torque_control='online'). + Assuming linear magnetization characteristics, the optimal currents for given torque and flux can be obtained + by solving the torque and flux equations. These lead to a fourth degree polynomial which can be solved + analytically. There are two ways to use this analytical solution for control. On the one hand, the currents + can be determined in advance as in the case of interpolation for different torques and fluxes and stored in a + LUT (torque_control='analytical'). On the other hand, the solution can be calculated at runtime with the + given torque and flux (torque_control='online'). """ - poly = [self.l_d ** 2 * (self.l_d - self.l_q) ** 2, - 2 * self.l_d ** 2 * (self.l_d - self.l_q) * self.psi_p + 2 * self.l_d * self.psi_p * ( - self.l_d - self.l_q) ** 2, - self.l_d ** 2 * self.psi_p ** 2 + 4 * self.l_d * self.psi_p ** 2 * (self.l_d - self.l_q) + ( - self.psi_p ** 2 - psi ** 2) * ( - self.l_d - self.l_q) ** 2, - 2 * self.l_q * self.psi_p ** 3 + 2 * (self.psi_p ** 2 - psi ** 2) * self.psi_p * (self.l_d - self.l_q), - (self.psi_p ** 2 - psi ** 2) * self.psi_p ** 2 + (self.l_q * 2 * torque / (3 * self.p)) ** 2] - - sol = np.roots(poly) # Solve polynomial + poly = [ + self.l_d**2 * (self.l_d - self.l_q) ** 2, + 2 * self.l_d**2 * (self.l_d - self.l_q) * self.psi_p + + 2 * self.l_d * self.psi_p * (self.l_d - self.l_q) ** 2, + self.l_d**2 * self.psi_p**2 + + 4 * self.l_d * self.psi_p**2 * (self.l_d - self.l_q) + + (self.psi_p**2 - psi**2) * (self.l_d - self.l_q) ** 2, + 2 * self.l_q * self.psi_p**3 + + 2 * (self.psi_p**2 - psi**2) * self.psi_p * (self.l_d - self.l_q), + (self.psi_p**2 - psi**2) * self.psi_p**2 + + (self.l_q * 2 * torque / (3 * self.p)) ** 2, + ] + + sol = np.roots(poly) # Solve polynomial i_d = np.real(sol[-1]) # Select the appropriate solution for i_d - i_q = 2 * torque / (3 * self.p * (self.psi_p + (self.l_d - self.l_q) * i_d)) # Calculate the corresponding i_q + i_q = ( + 2 * torque / (3 * self.p * (self.psi_p + (self.l_d - self.l_q) * i_d)) + ) # Calculate the corresponding i_q return i_d, i_q def get_i_d_q(self, torque, psi, psi_idx): @@ -339,24 +460,49 @@ def get_i_d_q(self, torque, psi, psi_idx): def get_t_idx(self, torque): torque = np.clip(torque, self.t_min, self.t_max) - return int(round((torque - self.t_min) / (self.t_max - self.t_min) * (self.t_count - 1))) + return int( + round( + (torque - self.t_min) / (self.t_max - self.t_min) * (self.t_count - 1) + ) + ) def get_psi_idx(self, psi): psi = np.clip(psi, self.psi_min, self.psi_max) - return int(round((psi - self.psi_min) / (self.psi_max - self.psi_min) * (self.psi_count - 1))) + return int( + round( + (psi - self.psi_min) + / (self.psi_max - self.psi_min) + * (self.psi_count - 1) + ) + ) def get_psi_idx_mtpf(self, psi): - return np.clip(int((self.psi_count - 1) - round(psi / self.psi_max_mtpf * (self.psi_count - 1))), 0, - self.psi_count) + return np.clip( + int( + (self.psi_count - 1) + - round(psi / self.psi_max_mtpf * (self.psi_count - 1)) + ), + 0, + self.psi_count, + ) def get_t_idx_mtpc(self, torque): - return np.clip(int(round((torque + self.max_torque) / (2 * self.max_torque) * (self.t_count - 1))), 0, - self.t_count) + return np.clip( + int( + round( + (torque + self.max_torque) + / (2 * self.max_torque) + * (self.t_count - 1) + ) + ), + 0, + self.t_count, + ) def control(self, state, torque): """ - This main method is called by the CascadedFieldOrientedController to calculate reference values for the i_d - and i_q currents from a given torque reference. + This main method is called by the CascadedFieldOrientedController to calculate reference values for the i_d + and i_q currents from a given torque reference. """ # get the optimal psi for a given torque from the mtpc characteristic @@ -374,7 +520,7 @@ def control(self, state, torque): torque = np.sign(torque) * t_max # calculate the currents online - if self.torque_control == 'online': + if self.torque_control == "online": i_d, i_q = self.get_i_d_q(torque, psi_max, psi_idx_) # get the currents from a LUT @@ -413,9 +559,15 @@ def control(self, state, torque): self.psi_list.append(psi_max) if self.k % self.update_interval == 0: - self.psi_plot.scatter(self.torque_list, self.psi_list, c='tab:blue', s=3) - self.torque_plot.scatter(self.psi_list, self.torque_list, c='tab:blue', s=3) - self.i_d_q_characteristic_.scatter(self.i_d_list, self.i_q_list, c='tab:blue', s=3) + self.psi_plot.scatter( + self.torque_list, self.psi_list, c="tab:blue", s=3 + ) + self.torque_plot.scatter( + self.psi_list, self.torque_list, c="tab:blue", s=3 + ) + self.i_d_q_characteristic_.scatter( + self.i_d_list, self.i_q_list, c="tab:blue", s=3 + ) self.fig_torque.canvas.draw() self.fig_torque.canvas.flush_events() @@ -426,8 +578,22 @@ def control(self, state, torque): self.psi_list = [] # clipping and normalizing the currents - i_q = np.clip(i_q, -self.nominal_values[self.i_sq_idx], self.nominal_values[self.i_sq_idx]) / self.limit[self.i_sq_idx] - i_d = np.clip(i_d, -self.nominal_values[self.i_sd_idx], self.nominal_values[self.i_sd_idx]) / self.limit[self.i_sd_idx] + i_q = ( + np.clip( + i_q, + -self.nominal_values[self.i_sq_idx], + self.nominal_values[self.i_sq_idx], + ) + / self.limit[self.i_sq_idx] + ) + i_d = ( + np.clip( + i_d, + -self.nominal_values[self.i_sd_idx], + self.nominal_values[self.i_sd_idx], + ) + / self.limit[self.i_sd_idx] + ) self.k += 1 @@ -435,14 +601,20 @@ def control(self, state, torque): def modulation_control(self, state): """ - To ensure the functionality of the current control, a small dynamic manipulated variable reserve to the - voltage limitation must be kept available. This control is performed by this modulation controller. Further - information can be found at https://ieeexplore.ieee.org/document/7409195. + To ensure the functionality of the current control, a small dynamic manipulated variable reserve to the + voltage limitation must be kept available. This control is performed by this modulation controller. Further + information can be found at https://ieeexplore.ieee.org/document/7409195. """ # Calculate modulation - a = 2 * np.sqrt((state[self.u_sd_idx] * self.limit[self.u_sd_idx]) ** 2 + ( - state[self.u_sq_idx] * self.limit[self.u_sq_idx]) ** 2) / self.u_dc + a = ( + 2 + * np.sqrt( + (state[self.u_sd_idx] * self.limit[self.u_sd_idx]) ** 2 + + (state[self.u_sq_idx] * self.limit[self.u_sq_idx]) ** 2 + ) + / self.u_dc + ) # Check, if integral part should be reset if a > 1.1 * self.a_max: @@ -483,40 +655,50 @@ def modulation_control(self, state): self.psi_delta_list.append(psi_delta) if self.k % self.update_interval == 0: - self.a_plot.scatter(self.k_list_a, self.a_list, c='tab:blue', s=3) - self.psi_delta_plot.scatter(self.k_list_a, self.psi_delta_list, c='tab:blue', s=3) - self.a_plot.set_xlim(max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1)) - self.psi_delta_plot.set_xlim(max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1)) - self.k_list_a = [] - self.a_list = [] - self.psi_delta_list = [] + self.a_plot.scatter(self.k_list_a, self.a_list, c="tab:blue", s=3) + self.psi_delta_plot.scatter( + self.k_list_a, self.psi_delta_list, c="tab:blue", s=3 + ) + self.a_plot.set_xlim( + max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1) + ) + self.psi_delta_plot.set_xlim( + max(self.k * self.tau, 1) - 1, max(self.k * self.tau, 1) + ) + self.k_list_a = [] + self.a_list = [] + self.psi_delta_list = [] return psi def initialize_modulation_plot(self): if self.plot_modulation: plt.ion() - self.fig_modulation = plt.figure('Modulation Controller') + self.fig_modulation = plt.figure("Modulation Controller") self.a_plot = plt.subplot2grid((1, 2), (0, 0)) self.psi_delta_plot = plt.subplot2grid((1, 2), (0, 1)) # Define the modulation plot - self.a_plot.set_title('Modulation') - self.a_plot.axhline(self.k_ * self.a_max, c='tab:orange', label=r'$a^*$') - self.a_plot.plot([], [], c='tab:blue', label='a') - self.a_plot.set_xlabel('t / s') - self.a_plot.set_ylabel('a') + self.a_plot.set_title("Modulation") + self.a_plot.axhline(self.k_ * self.a_max, c="tab:orange", label=r"$a^*$") + self.a_plot.plot([], [], c="tab:blue", label="a") + self.a_plot.set_xlabel("t / s") + self.a_plot.set_ylabel("a") self.a_plot.grid(True) self.a_plot.set_xlim(0, 1) self.a_plot.legend(loc=2) # Define the delta flux plot - self.psi_delta_plot.set_title(r'$\Psi_\mathrm{\Delta}$') - self.psi_delta_plot.axhline(self.psi_low, c='tab:red', linestyle='dashed', label='Limit') - self.psi_delta_plot.axhline(self.psi_high, c='tab:red', linestyle='dashed') - self.psi_delta_plot.plot([], [], c='tab:blue', label=r'$\Psi_\mathrm{\Delta}$') - self.psi_delta_plot.set_xlabel('t / s') - self.psi_delta_plot.set_ylabel(r'$\Psi_\mathrm{\Delta} / Vs$') + self.psi_delta_plot.set_title(r"$\Psi_\mathrm{\Delta}$") + self.psi_delta_plot.axhline( + self.psi_low, c="tab:red", linestyle="dashed", label="Limit" + ) + self.psi_delta_plot.axhline(self.psi_high, c="tab:red", linestyle="dashed") + self.psi_delta_plot.plot( + [], [], c="tab:blue", label=r"$\Psi_\mathrm{\Delta}$" + ) + self.psi_delta_plot.set_xlabel("t / s") + self.psi_delta_plot.set_ylabel(r"$\Psi_\mathrm{\Delta} / Vs$") self.psi_delta_plot.grid(True) self.psi_delta_plot.set_xlim(0, 1) self.psi_delta_plot.legend(loc=2) diff --git a/examples/classic_controllers/custom_classic_controllers_dc_motor_example.py b/examples/classic_controllers/custom_classic_controllers_dc_motor_example.py index 5ea26e4c..af6b414f 100644 --- a/examples/classic_controllers/custom_classic_controllers_dc_motor_example.py +++ b/examples/classic_controllers/custom_classic_controllers_dc_motor_example.py @@ -1,10 +1,11 @@ from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot import gym_electric_motor as gem +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from gym_electric_motor.visualization import MotorDashboard +from gym_electric_motor.visualization.render_modes import RenderMode -if __name__ == '__main__': - +if __name__ == "__main__": """ motor type: 'PermExDc' Permanently Excited DC Motor 'ExtExDc' Externally Excited MC Motor @@ -20,26 +21,28 @@ """ # following manual controller design addresses an ExtExDc. Other motor types require different controller stages - motor_type = 'ExtExDc' - control_type = 'CC' - action_type = 'Cont' + """ + motor_type = "ExtExDc" + control_type = "CC" + action_type = "Cont" + """ - motor = action_type + '-' + control_type + '-' + motor_type + '-v0' + motor = Motor(MotorType.ExternallyExcitedDcMotor, + ControlType.CurrentControl, + ActionType.Continuous,) - if motor_type in ['PermExDc', 'SeriesDc']: - states = ['omega', 'torque', 'i', 'u'] - elif motor_type == 'ShuntDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u'] - elif motor_type == 'ExtExDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u_a', 'u_e'] - else: - raise KeyError(motor_type + ' is not available') # definition of the plotted variables - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states] + external_ref_plots = [ExternallyReferencedStatePlot(state) for state in motor.states()] + + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots, render_mode=RenderMode.Figure) # initialize the gym-electric-motor environment - env = gem.make(motor, visualization=MotorDashboard(additional_plots=external_ref_plots), render_mode = 'figure') + env = gem.make( + motor.env_id(), + visualization=motor_dashboard + + ) """ initialize the controller @@ -58,16 +61,26 @@ added in a separate array. """ - current_a_controller = {'controller_type': 'pi_controller', 'p_gain': 0.3, 'i_gain': 50} - speed_controller = {'controller_type': 'pi_controller', 'p_gain': 1, 'i_gain': 40} - current_e_controller = {'controller_type': 'pi_controller', 'p_gain': 5, 'i_gain': 300} + current_a_controller = { + "controller_type": "pi_controller", + "p_gain": 0.3, + "i_gain": 50, + } + speed_controller = {"controller_type": "pi_controller", "p_gain": 1, "i_gain": 40} + current_e_controller = { + "controller_type": "pi_controller", + "p_gain": 5, + "i_gain": 300, + } stages_a = [current_a_controller, speed_controller] stages_e = [current_e_controller] stages = [stages_a, stages_e] - controller = Controller.make(env, external_ref_plots=external_ref_plots, stages=stages) + controller = Controller.make( + env, external_ref_plots=external_ref_plots, stages=stages + ) (state, reference), _ = env.reset() @@ -79,4 +92,5 @@ env.reset() controller.reset() + motor_dashboard.show_and_hold() env.close() diff --git a/examples/classic_controllers/custom_classic_controllers_ind_motor_example.py b/examples/classic_controllers/custom_classic_controllers_ind_motor_example.py index 4718c37a..135403f5 100644 --- a/examples/classic_controllers/custom_classic_controllers_ind_motor_example.py +++ b/examples/classic_controllers/custom_classic_controllers_ind_motor_example.py @@ -1,3 +1,4 @@ +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot from external_plot import ExternalPlot @@ -5,7 +6,7 @@ from gym_electric_motor.visualization import MotorDashboard import numpy as np -if __name__ == '__main__': +if __name__ == "__main__": """ motor type: 'SCIM' Squirrel Cage Induction Motor @@ -15,21 +16,35 @@ action_type: 'Cont' Continuous Action Space """ + + """ + motor_type = "SCIM" + control_type = "SC" + action_type = "Cont" + """ - motor_type = 'SCIM' - control_type = 'SC' - action_type = 'Cont' - - env_id = action_type + '-' + control_type + '-' + motor_type + '-v0' + motor = Motor( + MotorType.SquirrelCageInductionMotor, + ControlType.SpeedControl, + ActionType.Continuous, + ) # definition of the plotted variables - states = ['omega', 'torque', 'i_sd', 'i_sq', 'u_sd', 'u_sq'] + states = ["omega", "torque", "i_sd", "i_sq", "u_sd", "u_sq"] external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states] - external_plot = [ExternalPlot(referenced=control_type != 'CC'), ExternalPlot(min=-np.pi, max=np.pi)] + external_plot = [ + ExternalPlot(referenced=ControlType.SpeedControl != "CC"), + ExternalPlot(min=-np.pi, max=np.pi), + ] external_ref_plots += external_plot + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots) + # initialize the gym-electric-motor environment - env = gem.make(env_id, visualization=MotorDashboard(additional_plots=external_ref_plots)) + env = gem.make( + motor.env_id(), + visualization=motor_dashboard + ) """ initialize the controller @@ -42,9 +57,13 @@ """ - current_controller = [{'controller_type': 'pi_controller', 'p_gain': 40, 'i_gain': 15000}, - {'controller_type': 'pi_controller', 'p_gain': 25, 'i_gain': 10000}] - speed_controller = [{'controller_type': 'pi_controller', 'p_gain': 1, 'i_gain': 100}] + current_controller = [ + {"controller_type": "pi_controller", "p_gain": 40, "i_gain": 15000}, + {"controller_type": "pi_controller", "p_gain": 25, "i_gain": 10000}, + ] + speed_controller = [ + {"controller_type": "pi_controller", "p_gain": 1, "i_gain": 100} + ] stages = [current_controller, speed_controller] controller = Controller.make(env, stages=stages, external_plot=external_ref_plots) @@ -58,4 +77,6 @@ if terminated: env.reset() controller.reset() + + motor_dashboard.show_and_hold() env.close() diff --git a/examples/classic_controllers/custom_classic_controllers_synch_motor_example.py b/examples/classic_controllers/custom_classic_controllers_synch_motor_example.py index d6cf2f08..f1332d5b 100644 --- a/examples/classic_controllers/custom_classic_controllers_synch_motor_example.py +++ b/examples/classic_controllers/custom_classic_controllers_synch_motor_example.py @@ -1,11 +1,11 @@ +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot import gym_electric_motor as gem from gym_electric_motor.visualization import MotorDashboard import numpy as np -if __name__ == '__main__': - +if __name__ == "__main__": """ motor type: 'PMSM' Permanent Magnet Synchronous Motor 'SynRM' Synchronous Reluctance Motor @@ -17,26 +17,44 @@ action_type: 'Cont' Continuous Action Space in ABC-Coordinates 'Finite' Discrete Action Space """ + """ + motor_type = "PMSM" + control_type = "SC" + action_type = "Cont" + """ - motor_type = 'PMSM' - control_type = 'SC' - action_type = 'Cont' - - env_id = action_type + '-' + control_type + '-' + motor_type + '-v0' + motor = Motor(MotorType.PermanentMagnetSynchronousMotor, + ControlType.SpeedControl, + ActionType.Continuous) # definition of the motor parameters - psi_p = 0 if motor_type == 'SynRM' else 45e-3 + psi_p = 0 if "SynRM" in motor.env_id() else 45e-3 limit_values = dict(omega=12e3 * np.pi / 30, torque=100, i=280, u=320) - nominal_values = dict(omega=10e3 * np.pi / 30, torque=95.0, i=240, epsilon=np.pi, u=300) - motor_parameter = dict(p=3, l_d=0.37e-3, l_q=1.2e-3, j_rotor=0.03883, r_s=18e-3, psi_p=psi_p) + nominal_values = dict( + omega=10e3 * np.pi / 30, torque=95.0, i=240, epsilon=np.pi, u=300 + ) + motor_parameter = dict( + p=3, l_d=0.37e-3, l_q=1.2e-3, j_rotor=0.03883, r_s=18e-3, psi_p=psi_p + ) # definition of the plotted variables - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in ['omega', 'torque', 'i_sd', 'i_sq', 'u_sd', 'u_sq']] + external_ref_plots = [ + ExternallyReferencedStatePlot(state) + for state in ["omega", "torque", "i_sd", "i_sq", "u_sd", "u_sq"] + ] + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots) # 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), - render_mode = 'figure') + env = gem.make( + motor.env_id(), + visualization=MotorDashboard(additional_plots=external_ref_plots), + motor=dict( + limit_values=limit_values, + nominal_values=nominal_values, + motor_parameter=motor_parameter, + ), + render_mode="figure", + ) """ initialize the controller @@ -90,16 +108,33 @@ """ - current_d_controller = {'controller_type': 'pi_controller', 'p_gain': 1, 'i_gain': 500} - current_q_controller = {'controller_type': 'pi_controller', 'p_gain': 3, 'i_gain': 1400} - speed_controller = {'controller_type': 'pi_controller', 'p_gain': 12, 'i_gain': 1300} + current_d_controller = { + "controller_type": "pi_controller", + "p_gain": 1, + "i_gain": 500, + } + current_q_controller = { + "controller_type": "pi_controller", + "p_gain": 3, + "i_gain": 1400, + } + speed_controller = { + "controller_type": "pi_controller", + "p_gain": 12, + "i_gain": 1300, + } current_controller = [current_d_controller, current_q_controller] overlaid_controller = [speed_controller] stages = [current_controller, overlaid_controller] - controller = Controller.make(env, stages=stages, external_ref_plots=external_ref_plots, torque_control='analytical') + controller = Controller.make( + env, + stages=stages, + external_ref_plots=external_ref_plots, + torque_control="analytical", + ) (state, reference), _ = env.reset() @@ -110,5 +145,5 @@ if terminated: env.reset() controller.reset() - + env.close() diff --git a/examples/classic_controllers/external_plot.py b/examples/classic_controllers/external_plot.py index 679736c0..872b35f9 100644 --- a/examples/classic_controllers/external_plot.py +++ b/examples/classic_controllers/external_plot.py @@ -4,48 +4,48 @@ class ExternalPlot(TimePlot): """ - Class to plot lines that do not belong to the state of the environment. A reference and any number of additional - lines can be plotted. - Usage Example - ------------- - >>> from classic_controllers import Controller - >>> from external_plot import ExternalPlot - >>> import gym_electric_motor as gem - >>> from gym_electric_motor.visualization import MotorDashboard - >>> import numpy as np - - >>> if __name__ == '__main__': - >>> #define ExternalPlot Object with reference and two additional lines - >>> external_plot = ExternalPlot(min=-1, max=1, referenced=True, additional_lines=2) - - >>> # define gem environment and pass the ExternalPlot object as an additional plot - >>> env = gem.make('DqCont-CC-PMSM-v0', visualization=MotorDashboard(state_plots=['i_sd', 'i_sq'], - ... additional_plots=(external_plot,))) - - >>> # 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$']}) - >>> terminated = True - >>> for t in range(100000): - >>> if terminated: - >>> state, reference = env.reset() - >>> 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, terminated, truncated, _ = env.step([0, 0]) + Class to plot lines that do not belong to the state of the environment. A reference and any number of additional + lines can be plotted. + Usage Example + ------------- + >>> from classic_controllers import Controller + >>> from external_plot import ExternalPlot + >>> import gym_electric_motor as gem + >>> from gym_electric_motor.visualization import MotorDashboard + >>> import numpy as np + + >>> if __name__ == '__main__': + >>> #define ExternalPlot Object with reference and two additional lines + >>> external_plot = ExternalPlot(min=-1, max=1, referenced=True, additional_lines=2) + + >>> # define gem environment and pass the ExternalPlot object as an additional plot + >>> env = gem.make('DqCont-CC-PMSM-v0', visualization=MotorDashboard(state_plots=['i_sd', 'i_sq'], + ... additional_plots=(external_plot,))) + + >>> # 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$']}) + >>> terminated = True + >>> for t in range(100000): + >>> if terminated: + >>> state, reference = env.reset() + >>> 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, terminated, truncated, _ = env.step([0, 0]) """ def __init__(self, referenced=False, additional_lines=0, min=0, max=1): """ - This function creates an object for external plots in a GEM MotorDashboard. + This function creates an object for external plots in a GEM MotorDashboard. - Args: - referenced: a reference is to be displayed - additional_lines: number of additional lines in plot - min: minimum y-value of the plot - max: maximum y-value of the plot + Args: + referenced: a reference is to be displayed + additional_lines: number of additional lines in plot + min: minimum y-value of the plot + max: maximum y-value of the plot - Returns: - Object that can be passed to a GEM environment to plot additional data. + Returns: + Object that can be passed to a GEM environment to plot additional data. """ super().__init__() @@ -61,8 +61,8 @@ def __init__(self, referenced=False, additional_lines=0, min=0, max=1): self._state_line = None self._reference_line = None - self.state_label = '' - self.ref_label = '' + self.state_label = "" + self.ref_label = "" # Data containers self._state_data = [] @@ -79,7 +79,7 @@ def __init__(self, referenced=False, additional_lines=0, min=0, max=1): for i in range(additional_lines): self._additional_lines.append([]) self._additional_data.append(None) - self.add_labels.append('') + self.add_labels.append("") def set_env(self, env): # Docstring of superclass @@ -97,20 +97,32 @@ def reset_data(self): if self.added: for i in range(self.add_lines): - self._additional_data[i] = np.full(shape=self._x_data.shape, fill_value=np.nan) + self._additional_data[i] = np.full( + shape=self._x_data.shape, fill_value=np.nan + ) def initialize(self, axis): # Docstring of superclass super().initialize(axis) # Line to plot the state data - self._state_line, = self._axis.plot(self._x_data, self._state_data, **self._state_line_config, zorder=self.add_lines+2) + (self._state_line,) = self._axis.plot( + self._x_data, + self._state_data, + **self._state_line_config, + zorder=self.add_lines + 2, + ) self._lines = [self._state_line] # 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] + (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] self._lines.append(self._reference_line) self._y_data = [self._state_data, self._reference_data] @@ -118,7 +130,12 @@ def initialize(self, axis): # If there are added lines plot also these lines if self.added: for i in range(self.add_lines): - self._additional_lines[i], = self._axis.plot(self._x_data, self._additional_data[i], **self._add_line_config, zorder=self.add_lines-i) + (self._additional_lines[i],) = self._axis.plot( + self._x_data, + self._additional_data[i], + **self._add_line_config, + zorder=self.add_lines - i, + ) self._lines.append(self._additional_lines[i]) self._y_data.append(self._additional_data[i]) @@ -129,24 +146,31 @@ def initialize(self, axis): lines.extend(self._additional_lines) labels = [self.state_label, self.ref_label] labels.extend(self.add_labels) - self._axis.legend((lines), (labels), loc='upper left', numpoints=20) + self._axis.legend((lines), (labels), loc="upper left", numpoints=20) else: - self._axis.legend(([self._state_line, self._reference_line]), ([self.state_label, self.ref_label]), loc='upper left', numpoints=20) + self._axis.legend( + ([self._state_line, self._reference_line]), + ([self.state_label, self.ref_label]), + loc="upper left", + numpoints=20, + ) else: - self._axis.legend((self._state_line, ), (self.state_label, ), loc='upper left', numpoints=20) + self._axis.legend( + (self._state_line,), (self.state_label,), loc="upper left", numpoints=20 + ) def set_label(self, labels): """ - Method to set the labels, A dict must be passed. The keys are: y_label, state_label, ref_label, add_label. - For the key add_label a list with the length of the number of additional lines is passed. + Method to set the labels, A dict must be passed. The keys are: y_label, state_label, ref_label, add_label. + For the key add_label a list with the length of the number of additional lines is passed. """ - self._label = labels.get('y_label', '') - self.state_label = labels['state_label'] + self._label = labels.get("y_label", "") + self.state_label = labels["state_label"] if self._referenced: - self.ref_label = labels.get('ref_label', '') - if 'add_label' in labels.keys(): - self.add_labels = labels['add_label'] + self.ref_label = labels.get("ref_label", "") + if "add_label" in labels.keys(): + self.add_labels = labels["add_label"] def on_step_end(self, k, state, reference, reward, terminated): super().on_step_end(k, state, reference, reward, terminated) diff --git a/examples/classic_controllers/externally_referenced_state_plot.py b/examples/classic_controllers/externally_referenced_state_plot.py index b0daf0ae..e6df2590 100644 --- a/examples/classic_controllers/externally_referenced_state_plot.py +++ b/examples/classic_controllers/externally_referenced_state_plot.py @@ -3,24 +3,24 @@ class ExternallyReferencedStatePlot(StatePlot): """Plot that displays environments states together with externally generated references. - These could be for example references that are generated intermediately within a cascaded controller. - Usage Example - ------------- - .. code-block:: python - :emphasize-lines: 1,12 - my_externally_referenced_plot = ExternallyReferencedStatePlot(state='i_sd') - env = gem.make( - 'DqCont-SC-PMSM-v0', - visualization=dict(additional_plots=(my_externally_referenced_plot,), - ) - terminated = True - for _ in range(10000): - 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) - action = env.action_space.sample() - (state, reference), reward, terminated, truncated, _ = env.step(action) + These could be for example references that are generated intermediately within a cascaded controller. + Usage Example + ------------- + .. code-block:: python + :emphasize-lines: 1,12 + my_externally_referenced_plot = ExternallyReferencedStatePlot(state='i_sd') + env = gem.make( + 'DqCont-SC-PMSM-v0', + visualization=dict(additional_plots=(my_externally_referenced_plot,), + ) + terminated = True + for _ in range(10000): + 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) + action = env.action_space.sample() + (state, reference), reward, terminated, truncated, _ = env.step(action) """ def __init__(self, state): diff --git a/examples/classic_controllers/integration_test_classic_controllers_dc_motor.py b/examples/classic_controllers/integration_test_classic_controllers_dc_motor.py index cbec7db2..b22dc7ce 100644 --- a/examples/classic_controllers/integration_test_classic_controllers_dc_motor.py +++ b/examples/classic_controllers/integration_test_classic_controllers_dc_motor.py @@ -1,62 +1,53 @@ from classic_controllers import Controller from externally_referenced_state_plot import ExternallyReferencedStatePlot + +# from gem_controllers.gem_controller import GemController import gym_electric_motor as gem -from gym_electric_motor.visualization import MotorDashboard +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType from gym_electric_motor.reference_generators import SinusoidalReferenceGenerator -import time - -if __name__ == '__main__': +from gym_electric_motor.visualization import MotorDashboard, RenderMode +from gym_electric_motor.visualization.motor_dashboard_plots import StatePlot +if __name__ == "__main__": """ motor type: 'PermExDc' Permanently Excited DC Motor - 'ExtExDc' Externally Excited MC Motor + 'ExtExDc' Externally Excited DC Motor 'SeriesDc' DC Series Motor 'ShuntDc' DC Shunt Motor - + control type: 'SC' Speed Control 'TC' Torque Control 'CC' Current Control - + action_type: 'Cont' Continuous Action Space 'Finite' Discrete Action Space """ - motor_type = 'PermExDc' - control_type = 'SC' - action_type = 'Cont' - - motor = action_type + '-' + control_type + '-' + motor_type + '-v0' - - if motor_type in ['PermExDc', 'SeriesDc']: - states = ['omega', 'torque', 'i', 'u'] - elif motor_type == 'ShuntDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u'] - elif motor_type == 'ExtExDc': - states = ['omega', 'torque', 'i_a', 'i_e', 'u_a', 'u_e'] - else: - raise KeyError(motor_type + ' is not available') + motor = Motor( + MotorType.PermanentlyExcitedDcMotor, + ControlType.SpeedControl, + ActionType.Continuous, + ) # definition of the plotted variables - external_ref_plots = [ExternallyReferencedStatePlot(state) for state in states] - + external_ref_plots = [ExternallyReferencedStatePlot(state) for state in motor.states()] # definition of the reference generator - ref_generator = SinusoidalReferenceGenerator(amplitude_range= (1,1), - frequency_range= (5,5), - offset_range = (0,0), - episode_lengths = (10001, 10001)) - + ref_generator = SinusoidalReferenceGenerator( + amplitude_range=(1, 1), + frequency_range=(5, 5), + offset_range=(0, 0), + episode_lengths=(10001, 10001), + ) + motor_dashboard = MotorDashboard(additional_plots=external_ref_plots, render_mode=RenderMode.Figure) # initialize the gym-electric-motor environment - env = gem.make(motor, - visualization=MotorDashboard(additional_plots=external_ref_plots), - scale_plots=True, - render_mode="figure", - reference_generator = ref_generator) - - env.metadata["filename_prefix"] = "integration-test" - env.metadata["filename_suffix"] = "" - env.metadata["save_figure_on_close"] = False - env.metadata["hold_figure_on_close"] = True + env = gem.make( + motor.env_id(), + visualization=motor_dashboard, + scale_plots=True, + reference_generator=ref_generator, + ) + """ initialize the controller @@ -68,20 +59,28 @@ a (optional) tuning parameter of the symmetrical optimum (default: 4) """ + controller = Controller.make(env, external_ref_plots=external_ref_plots) + # controller = GemController.make(env, env_id=motor.env_id()) (state, reference), _ = env.reset(seed=1337) + print("state_names: ", motor.states()) # simulate the environment for i in range(10001): action = controller.control(state, reference) - #if i % 100 == 0: - # (state, reference), reward, terminated, truncated, _ = env.step(env.action_space.sample()) - #else: + # if i % 100 == 0: + # (state, reference), reward, terminated, truncated, _ = env.step(env.action_space.sample()) + # else: (state, reference), reward, terminated, truncated, _ = env.step(action) + # viz.render() if terminated: env.reset() + controller.reset() - - env.close() \ No newline at end of file + + env.close() + + # motor_dashboard.save_to_file(filename="integration_test") + motor_dashboard.show_and_hold() diff --git a/examples/environment_features/GEM_cookbook.ipynb b/examples/environment_features/GEM_cookbook.ipynb index 176b4fd6..df795b6e 100644 --- a/examples/environment_features/GEM_cookbook.ipynb +++ b/examples/environment_features/GEM_cookbook.ipynb @@ -34,23 +34,6 @@ "For this notebook, we can install it by executing the following cell." ] }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "^C\n" - ] - } - ], - "source": [ - "!pip install -q git+https://github.com/upb-lea/gym-electric-motor.git" - ] - }, { "attachments": {}, "cell_type": "markdown", @@ -77,10 +60,11 @@ "- series motor\n", "- shunt motor\n", "\n", - "Two three phase motors:\n", + "Three three phase symchronous motors:\n", "\n", "- PMSM (permanent magnet synchronous motor)\n", "- SynRM (synchronous reluctance motor)\n", + "- EESM (externally excited synchronous motor)\n", "\n", "Two variants of the induction motor:\n", "\n", @@ -170,38 +154,42 @@ "source": [ "When the environment is run in a jupiter notebook, it is recommended to split the enviromnent creation and execution into two cells. Furthermore, the ``visu.initialize()`` call is required. The dashboard is per default the first (and only) visualization in an environment.\n", "\n", - "If the environment is run from a script, the ``visu.initialize()`` call is not necessary." + "If the environment is run from a script, the ``visu.initialize()`` call is not necessary. " ] }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 1, "metadata": {}, "outputs": [ { - "name": "stdout", + "name": "stderr", "output_type": "stream", "text": [ - "Warning: Cannot change to a different GUI toolkit: widget. Using notebook instead.\n" + "c:\\Users\\jakobeit\\Anaconda3\\envs\\GEMUpdate\\lib\\site-packages\\gymnasium\\core.py:311: UserWarning: \u001b[33mWARN: env.visualizations to get variables from other wrappers is deprecated and will be removed in v1.0, to get this variable you can do `env.unwrapped.visualizations` for environment variables or `env.get_wrapper_attr('visualizations')` that will search the reminding wrappers.\u001b[0m\n", + " logger.warn(\n" ] }, { "data": { - "application/javascript": "/* Put everything inside the global mpl namespace */\n/* global mpl */\nwindow.mpl = {};\n\nmpl.get_websocket_type = function () {\n if (typeof WebSocket !== 'undefined') {\n return WebSocket;\n } else if (typeof MozWebSocket !== 'undefined') {\n return MozWebSocket;\n } else {\n alert(\n 'Your browser does not have WebSocket support. ' +\n 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n 'Firefox 4 and 5 are also supported but you ' +\n 'have to enable WebSockets in about:config.'\n );\n }\n};\n\nmpl.figure = function (figure_id, websocket, ondownload, parent_element) {\n this.id = figure_id;\n\n this.ws = websocket;\n\n this.supports_binary = this.ws.binaryType !== undefined;\n\n if (!this.supports_binary) {\n var warnings = document.getElementById('mpl-warnings');\n if (warnings) {\n warnings.style.display = 'block';\n warnings.textContent =\n 'This browser does not support binary websocket messages. ' +\n 'Performance may be slow.';\n }\n }\n\n this.imageObj = new Image();\n\n this.context = undefined;\n this.message = undefined;\n this.canvas = undefined;\n this.rubberband_canvas = undefined;\n this.rubberband_context = undefined;\n this.format_dropdown = undefined;\n\n this.image_mode = 'full';\n\n this.root = document.createElement('div');\n this.root.setAttribute('style', 'display: inline-block');\n this._root_extra_style(this.root);\n\n parent_element.appendChild(this.root);\n\n this._init_header(this);\n this._init_canvas(this);\n this._init_toolbar(this);\n\n var fig = this;\n\n this.waiting = false;\n\n this.ws.onopen = function () {\n fig.send_message('supports_binary', { value: fig.supports_binary });\n fig.send_message('send_image_mode', {});\n if (fig.ratio !== 1) {\n fig.send_message('set_device_pixel_ratio', {\n device_pixel_ratio: fig.ratio,\n });\n }\n fig.send_message('refresh', {});\n };\n\n this.imageObj.onload = function () {\n if (fig.image_mode === 'full') {\n // Full images could contain transparency (where diff images\n // almost always do), so we need to clear the canvas so that\n // there is no ghosting.\n fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n }\n fig.context.drawImage(fig.imageObj, 0, 0);\n };\n\n this.imageObj.onunload = function () {\n fig.ws.close();\n };\n\n this.ws.onmessage = this._make_on_message_function(this);\n\n this.ondownload = ondownload;\n};\n\nmpl.figure.prototype._init_header = function () {\n var titlebar = document.createElement('div');\n titlebar.classList =\n 'ui-dialog-titlebar ui-widget-header ui-corner-all ui-helper-clearfix';\n var titletext = document.createElement('div');\n titletext.classList = 'ui-dialog-title';\n titletext.setAttribute(\n 'style',\n 'width: 100%; text-align: center; padding: 3px;'\n );\n titlebar.appendChild(titletext);\n this.root.appendChild(titlebar);\n this.header = titletext;\n};\n\nmpl.figure.prototype._canvas_extra_style = function (_canvas_div) {};\n\nmpl.figure.prototype._root_extra_style = function (_canvas_div) {};\n\nmpl.figure.prototype._init_canvas = function () {\n var fig = this;\n\n var canvas_div = (this.canvas_div = document.createElement('div'));\n canvas_div.setAttribute('tabindex', '0');\n canvas_div.setAttribute(\n 'style',\n 'border: 1px solid #ddd;' +\n 'box-sizing: content-box;' +\n 'clear: both;' +\n 'min-height: 1px;' +\n 'min-width: 1px;' +\n 'outline: 0;' +\n 'overflow: hidden;' +\n 'position: relative;' +\n 'resize: both;' +\n 'z-index: 2;'\n );\n\n function on_keyboard_event_closure(name) {\n return function (event) {\n return fig.key_event(event, name);\n };\n }\n\n canvas_div.addEventListener(\n 'keydown',\n on_keyboard_event_closure('key_press')\n );\n canvas_div.addEventListener(\n 'keyup',\n on_keyboard_event_closure('key_release')\n );\n\n this._canvas_extra_style(canvas_div);\n this.root.appendChild(canvas_div);\n\n var canvas = (this.canvas = document.createElement('canvas'));\n canvas.classList.add('mpl-canvas');\n canvas.setAttribute(\n 'style',\n 'box-sizing: content-box;' +\n 'pointer-events: none;' +\n 'position: relative;' +\n 'z-index: 0;'\n );\n\n this.context = canvas.getContext('2d');\n\n var backingStore =\n this.context.backingStorePixelRatio ||\n this.context.webkitBackingStorePixelRatio ||\n this.context.mozBackingStorePixelRatio ||\n this.context.msBackingStorePixelRatio ||\n this.context.oBackingStorePixelRatio ||\n this.context.backingStorePixelRatio ||\n 1;\n\n this.ratio = (window.devicePixelRatio || 1) / backingStore;\n\n var rubberband_canvas = (this.rubberband_canvas = document.createElement(\n 'canvas'\n ));\n rubberband_canvas.setAttribute(\n 'style',\n 'box-sizing: content-box;' +\n 'left: 0;' +\n 'pointer-events: none;' +\n 'position: absolute;' +\n 'top: 0;' +\n 'z-index: 1;'\n );\n\n // Apply a ponyfill if ResizeObserver is not implemented by browser.\n if (this.ResizeObserver === undefined) {\n if (window.ResizeObserver !== undefined) {\n this.ResizeObserver = window.ResizeObserver;\n } else {\n var obs = _JSXTOOLS_RESIZE_OBSERVER({});\n this.ResizeObserver = obs.ResizeObserver;\n }\n }\n\n this.resizeObserverInstance = new this.ResizeObserver(function (entries) {\n var nentries = entries.length;\n for (var i = 0; i < nentries; i++) {\n var entry = entries[i];\n var width, height;\n if (entry.contentBoxSize) {\n if (entry.contentBoxSize instanceof Array) {\n // Chrome 84 implements new version of spec.\n width = entry.contentBoxSize[0].inlineSize;\n height = entry.contentBoxSize[0].blockSize;\n } else {\n // Firefox implements old version of spec.\n width = entry.contentBoxSize.inlineSize;\n height = entry.contentBoxSize.blockSize;\n }\n } else {\n // Chrome <84 implements even older version of spec.\n width = entry.contentRect.width;\n height = entry.contentRect.height;\n }\n\n // Keep the size of the canvas and rubber band canvas in sync with\n // the canvas container.\n if (entry.devicePixelContentBoxSize) {\n // Chrome 84 implements new version of spec.\n canvas.setAttribute(\n 'width',\n entry.devicePixelContentBoxSize[0].inlineSize\n );\n canvas.setAttribute(\n 'height',\n entry.devicePixelContentBoxSize[0].blockSize\n );\n } else {\n canvas.setAttribute('width', width * fig.ratio);\n canvas.setAttribute('height', height * fig.ratio);\n }\n /* This rescales the canvas back to display pixels, so that it\n * appears correct on HiDPI screens. */\n canvas.style.width = width + 'px';\n canvas.style.height = height + 'px';\n\n rubberband_canvas.setAttribute('width', width);\n rubberband_canvas.setAttribute('height', height);\n\n // And update the size in Python. We ignore the initial 0/0 size\n // that occurs as the element is placed into the DOM, which should\n // otherwise not happen due to the minimum size styling.\n if (fig.ws.readyState == 1 && width != 0 && height != 0) {\n fig.request_resize(width, height);\n }\n }\n });\n this.resizeObserverInstance.observe(canvas_div);\n\n function on_mouse_event_closure(name) {\n /* User Agent sniffing is bad, but WebKit is busted:\n * https://bugs.webkit.org/show_bug.cgi?id=144526\n * https://bugs.webkit.org/show_bug.cgi?id=181818\n * The worst that happens here is that they get an extra browser\n * selection when dragging, if this check fails to catch them.\n */\n var UA = navigator.userAgent;\n var isWebKit = /AppleWebKit/.test(UA) && !/Chrome/.test(UA);\n if(isWebKit) {\n return function (event) {\n /* This prevents the web browser from automatically changing to\n * the text insertion cursor when the button is pressed. We\n * want to control all of the cursor setting manually through\n * the 'cursor' event from matplotlib */\n event.preventDefault()\n return fig.mouse_event(event, name);\n };\n } else {\n return function (event) {\n return fig.mouse_event(event, name);\n };\n }\n }\n\n canvas_div.addEventListener(\n 'mousedown',\n on_mouse_event_closure('button_press')\n );\n canvas_div.addEventListener(\n 'mouseup',\n on_mouse_event_closure('button_release')\n );\n canvas_div.addEventListener(\n 'dblclick',\n on_mouse_event_closure('dblclick')\n );\n // Throttle sequential mouse events to 1 every 20ms.\n canvas_div.addEventListener(\n 'mousemove',\n on_mouse_event_closure('motion_notify')\n );\n\n canvas_div.addEventListener(\n 'mouseenter',\n on_mouse_event_closure('figure_enter')\n );\n canvas_div.addEventListener(\n 'mouseleave',\n on_mouse_event_closure('figure_leave')\n );\n\n canvas_div.addEventListener('wheel', function (event) {\n if (event.deltaY < 0) {\n event.step = 1;\n } else {\n event.step = -1;\n }\n on_mouse_event_closure('scroll')(event);\n });\n\n canvas_div.appendChild(canvas);\n canvas_div.appendChild(rubberband_canvas);\n\n this.rubberband_context = rubberband_canvas.getContext('2d');\n this.rubberband_context.strokeStyle = '#000000';\n\n this._resize_canvas = function (width, height, forward) {\n if (forward) {\n canvas_div.style.width = width + 'px';\n canvas_div.style.height = height + 'px';\n }\n };\n\n // Disable right mouse context menu.\n canvas_div.addEventListener('contextmenu', function (_e) {\n event.preventDefault();\n return false;\n });\n\n function set_focus() {\n canvas.focus();\n canvas_div.focus();\n }\n\n window.setTimeout(set_focus, 100);\n};\n\nmpl.figure.prototype._init_toolbar = function () {\n var fig = this;\n\n var toolbar = document.createElement('div');\n toolbar.classList = 'mpl-toolbar';\n this.root.appendChild(toolbar);\n\n function on_click_closure(name) {\n return function (_event) {\n return fig.toolbar_button_onclick(name);\n };\n }\n\n function on_mouseover_closure(tooltip) {\n return function (event) {\n if (!event.currentTarget.disabled) {\n return fig.toolbar_button_onmouseover(tooltip);\n }\n };\n }\n\n fig.buttons = {};\n var buttonGroup = document.createElement('div');\n buttonGroup.classList = 'mpl-button-group';\n for (var toolbar_ind in mpl.toolbar_items) {\n var name = mpl.toolbar_items[toolbar_ind][0];\n var tooltip = mpl.toolbar_items[toolbar_ind][1];\n var image = mpl.toolbar_items[toolbar_ind][2];\n var method_name = mpl.toolbar_items[toolbar_ind][3];\n\n if (!name) {\n /* Instead of a spacer, we start a new button group. */\n if (buttonGroup.hasChildNodes()) {\n toolbar.appendChild(buttonGroup);\n }\n buttonGroup = document.createElement('div');\n buttonGroup.classList = 'mpl-button-group';\n continue;\n }\n\n var button = (fig.buttons[name] = document.createElement('button'));\n button.classList = 'mpl-widget';\n button.setAttribute('role', 'button');\n button.setAttribute('aria-disabled', 'false');\n button.addEventListener('click', on_click_closure(method_name));\n button.addEventListener('mouseover', on_mouseover_closure(tooltip));\n\n var icon_img = document.createElement('img');\n icon_img.src = '_images/' + image + '.png';\n icon_img.srcset = '_images/' + image + '_large.png 2x';\n icon_img.alt = tooltip;\n button.appendChild(icon_img);\n\n buttonGroup.appendChild(button);\n }\n\n if (buttonGroup.hasChildNodes()) {\n toolbar.appendChild(buttonGroup);\n }\n\n var fmt_picker = document.createElement('select');\n fmt_picker.classList = 'mpl-widget';\n toolbar.appendChild(fmt_picker);\n this.format_dropdown = fmt_picker;\n\n for (var ind in mpl.extensions) {\n var fmt = mpl.extensions[ind];\n var option = document.createElement('option');\n option.selected = fmt === mpl.default_extension;\n option.innerHTML = fmt;\n fmt_picker.appendChild(option);\n }\n\n var status_bar = document.createElement('span');\n status_bar.classList = 'mpl-message';\n toolbar.appendChild(status_bar);\n this.message = status_bar;\n};\n\nmpl.figure.prototype.request_resize = function (x_pixels, y_pixels) {\n // Request matplotlib to resize the figure. Matplotlib will then trigger a resize in the client,\n // which will in turn request a refresh of the image.\n this.send_message('resize', { width: x_pixels, height: y_pixels });\n};\n\nmpl.figure.prototype.send_message = function (type, properties) {\n properties['type'] = type;\n properties['figure_id'] = this.id;\n this.ws.send(JSON.stringify(properties));\n};\n\nmpl.figure.prototype.send_draw_message = function () {\n if (!this.waiting) {\n this.waiting = true;\n this.ws.send(JSON.stringify({ type: 'draw', figure_id: this.id }));\n }\n};\n\nmpl.figure.prototype.handle_save = function (fig, _msg) {\n var format_dropdown = fig.format_dropdown;\n var format = format_dropdown.options[format_dropdown.selectedIndex].value;\n fig.ondownload(fig, format);\n};\n\nmpl.figure.prototype.handle_resize = function (fig, msg) {\n var size = msg['size'];\n if (size[0] !== fig.canvas.width || size[1] !== fig.canvas.height) {\n fig._resize_canvas(size[0], size[1], msg['forward']);\n fig.send_message('refresh', {});\n }\n};\n\nmpl.figure.prototype.handle_rubberband = function (fig, msg) {\n var x0 = msg['x0'] / fig.ratio;\n var y0 = (fig.canvas.height - msg['y0']) / fig.ratio;\n var x1 = msg['x1'] / fig.ratio;\n var y1 = (fig.canvas.height - msg['y1']) / fig.ratio;\n x0 = Math.floor(x0) + 0.5;\n y0 = Math.floor(y0) + 0.5;\n x1 = Math.floor(x1) + 0.5;\n y1 = Math.floor(y1) + 0.5;\n var min_x = Math.min(x0, x1);\n var min_y = Math.min(y0, y1);\n var width = Math.abs(x1 - x0);\n var height = Math.abs(y1 - y0);\n\n fig.rubberband_context.clearRect(\n 0,\n 0,\n fig.canvas.width / fig.ratio,\n fig.canvas.height / fig.ratio\n );\n\n fig.rubberband_context.strokeRect(min_x, min_y, width, height);\n};\n\nmpl.figure.prototype.handle_figure_label = function (fig, msg) {\n // Updates the figure title.\n fig.header.textContent = msg['label'];\n};\n\nmpl.figure.prototype.handle_cursor = function (fig, msg) {\n fig.canvas_div.style.cursor = msg['cursor'];\n};\n\nmpl.figure.prototype.handle_message = function (fig, msg) {\n fig.message.textContent = msg['message'];\n};\n\nmpl.figure.prototype.handle_draw = function (fig, _msg) {\n // Request the server to send over a new figure.\n fig.send_draw_message();\n};\n\nmpl.figure.prototype.handle_image_mode = function (fig, msg) {\n fig.image_mode = msg['mode'];\n};\n\nmpl.figure.prototype.handle_history_buttons = function (fig, msg) {\n for (var key in msg) {\n if (!(key in fig.buttons)) {\n continue;\n }\n fig.buttons[key].disabled = !msg[key];\n fig.buttons[key].setAttribute('aria-disabled', !msg[key]);\n }\n};\n\nmpl.figure.prototype.handle_navigate_mode = function (fig, msg) {\n if (msg['mode'] === 'PAN') {\n fig.buttons['Pan'].classList.add('active');\n fig.buttons['Zoom'].classList.remove('active');\n } else if (msg['mode'] === 'ZOOM') {\n fig.buttons['Pan'].classList.remove('active');\n fig.buttons['Zoom'].classList.add('active');\n } else {\n fig.buttons['Pan'].classList.remove('active');\n fig.buttons['Zoom'].classList.remove('active');\n }\n};\n\nmpl.figure.prototype.updated_canvas_event = function () {\n // Called whenever the canvas gets updated.\n this.send_message('ack', {});\n};\n\n// A function to construct a web socket function for onmessage handling.\n// Called in the figure constructor.\nmpl.figure.prototype._make_on_message_function = function (fig) {\n return function socket_on_message(evt) {\n if (evt.data instanceof Blob) {\n var img = evt.data;\n if (img.type !== 'image/png') {\n /* FIXME: We get \"Resource interpreted as Image but\n * transferred with MIME type text/plain:\" errors on\n * Chrome. But how to set the MIME type? It doesn't seem\n * to be part of the websocket stream */\n img.type = 'image/png';\n }\n\n /* Free the memory for the previous frames */\n if (fig.imageObj.src) {\n (window.URL || window.webkitURL).revokeObjectURL(\n fig.imageObj.src\n );\n }\n\n fig.imageObj.src = (window.URL || window.webkitURL).createObjectURL(\n img\n );\n fig.updated_canvas_event();\n fig.waiting = false;\n return;\n } else if (\n typeof evt.data === 'string' &&\n evt.data.slice(0, 21) === 'data:image/png;base64'\n ) {\n fig.imageObj.src = evt.data;\n fig.updated_canvas_event();\n fig.waiting = false;\n return;\n }\n\n var msg = JSON.parse(evt.data);\n var msg_type = msg['type'];\n\n // Call the \"handle_{type}\" callback, which takes\n // the figure and JSON message as its only arguments.\n try {\n var callback = fig['handle_' + msg_type];\n } catch (e) {\n console.log(\n \"No handler for the '\" + msg_type + \"' message type: \",\n msg\n );\n return;\n }\n\n if (callback) {\n try {\n // console.log(\"Handling '\" + msg_type + \"' message: \", msg);\n callback(fig, msg);\n } catch (e) {\n console.log(\n \"Exception inside the 'handler_\" + msg_type + \"' callback:\",\n e,\n e.stack,\n msg\n );\n }\n }\n };\n};\n\nfunction getModifiers(event) {\n var mods = [];\n if (event.ctrlKey) {\n mods.push('ctrl');\n }\n if (event.altKey) {\n mods.push('alt');\n }\n if (event.shiftKey) {\n mods.push('shift');\n }\n if (event.metaKey) {\n mods.push('meta');\n }\n return mods;\n}\n\n/*\n * return a copy of an object with only non-object keys\n * we need this to avoid circular references\n * https://stackoverflow.com/a/24161582/3208463\n */\nfunction simpleKeys(original) {\n return Object.keys(original).reduce(function (obj, key) {\n if (typeof original[key] !== 'object') {\n obj[key] = original[key];\n }\n return obj;\n }, {});\n}\n\nmpl.figure.prototype.mouse_event = function (event, name) {\n if (name === 'button_press') {\n this.canvas.focus();\n this.canvas_div.focus();\n }\n\n // from https://stackoverflow.com/q/1114465\n var boundingRect = this.canvas.getBoundingClientRect();\n var x = (event.clientX - boundingRect.left) * this.ratio;\n var y = (event.clientY - boundingRect.top) * this.ratio;\n\n this.send_message(name, {\n x: x,\n y: y,\n button: event.button,\n step: event.step,\n modifiers: getModifiers(event),\n guiEvent: simpleKeys(event),\n });\n\n return false;\n};\n\nmpl.figure.prototype._key_event_extra = function (_event, _name) {\n // Handle any extra behaviour associated with a key event\n};\n\nmpl.figure.prototype.key_event = function (event, name) {\n // Prevent repeat events\n if (name === 'key_press') {\n if (event.key === this._key) {\n return;\n } else {\n this._key = event.key;\n }\n }\n if (name === 'key_release') {\n this._key = null;\n }\n\n var value = '';\n if (event.ctrlKey && event.key !== 'Control') {\n value += 'ctrl+';\n }\n else if (event.altKey && event.key !== 'Alt') {\n value += 'alt+';\n }\n else if (event.shiftKey && event.key !== 'Shift') {\n value += 'shift+';\n }\n\n value += 'k' + event.key;\n\n this._key_event_extra(event, name);\n\n this.send_message(name, { key: value, guiEvent: simpleKeys(event) });\n return false;\n};\n\nmpl.figure.prototype.toolbar_button_onclick = function (name) {\n if (name === 'download') {\n this.handle_save(this, null);\n } else {\n this.send_message('toolbar_button', { name: name });\n }\n};\n\nmpl.figure.prototype.toolbar_button_onmouseover = function (tooltip) {\n this.message.textContent = tooltip;\n};\n\n///////////////// REMAINING CONTENT GENERATED BY embed_js.py /////////////////\n// prettier-ignore\nvar _JSXTOOLS_RESIZE_OBSERVER=function(A){var t,i=new WeakMap,n=new WeakMap,a=new WeakMap,r=new WeakMap,o=new Set;function s(e){if(!(this instanceof s))throw new TypeError(\"Constructor requires 'new' operator\");i.set(this,e)}function h(){throw new TypeError(\"Function is not a constructor\")}function c(e,t,i,n){e=0 in arguments?Number(arguments[0]):0,t=1 in arguments?Number(arguments[1]):0,i=2 in arguments?Number(arguments[2]):0,n=3 in arguments?Number(arguments[3]):0,this.right=(this.x=this.left=e)+(this.width=i),this.bottom=(this.y=this.top=t)+(this.height=n),Object.freeze(this)}function d(){t=requestAnimationFrame(d);var s=new WeakMap,p=new Set;o.forEach((function(t){r.get(t).forEach((function(i){var r=t instanceof window.SVGElement,o=a.get(t),d=r?0:parseFloat(o.paddingTop),f=r?0:parseFloat(o.paddingRight),l=r?0:parseFloat(o.paddingBottom),u=r?0:parseFloat(o.paddingLeft),g=r?0:parseFloat(o.borderTopWidth),m=r?0:parseFloat(o.borderRightWidth),w=r?0:parseFloat(o.borderBottomWidth),b=u+f,F=d+l,v=(r?0:parseFloat(o.borderLeftWidth))+m,W=g+w,y=r?0:t.offsetHeight-W-t.clientHeight,E=r?0:t.offsetWidth-v-t.clientWidth,R=b+v,z=F+W,M=r?t.width:parseFloat(o.width)-R-E,O=r?t.height:parseFloat(o.height)-z-y;if(n.has(t)){var k=n.get(t);if(k[0]===M&&k[1]===O)return}n.set(t,[M,O]);var S=Object.create(h.prototype);S.target=t,S.contentRect=new c(u,d,M,O),s.has(i)||(s.set(i,[]),p.add(i)),s.get(i).push(S)}))})),p.forEach((function(e){i.get(e).call(e,s.get(e),e)}))}return s.prototype.observe=function(i){if(i instanceof window.Element){r.has(i)||(r.set(i,new Set),o.add(i),a.set(i,window.getComputedStyle(i)));var n=r.get(i);n.has(this)||n.add(this),cancelAnimationFrame(t),t=requestAnimationFrame(d)}},s.prototype.unobserve=function(i){if(i instanceof window.Element&&r.has(i)){var n=r.get(i);n.has(this)&&(n.delete(this),n.size||(r.delete(i),o.delete(i))),n.size||r.delete(i),o.size||cancelAnimationFrame(t)}},A.DOMRectReadOnly=c,A.ResizeObserver=s,A.ResizeObserverEntry=h,A}; // eslint-disable-line\nmpl.toolbar_items = [[\"Home\", \"Reset original view\", \"fa fa-home\", \"home\"], [\"Back\", \"Back to previous view\", \"fa fa-arrow-left\", \"back\"], [\"Forward\", \"Forward to next view\", \"fa fa-arrow-right\", \"forward\"], [\"\", \"\", \"\", \"\"], [\"Pan\", \"Left button pans, Right button zooms\\nx/y fixes axis, CTRL fixes aspect\", \"fa fa-arrows\", \"pan\"], [\"Zoom\", \"Zoom to rectangle\\nx/y fixes axis\", \"fa fa-square-o\", \"zoom\"], [\"\", \"\", \"\", \"\"], [\"Download\", \"Download plot\", \"fa fa-floppy-o\", \"download\"]];\n\nmpl.extensions = [\"eps\", \"jpeg\", \"pgf\", \"pdf\", \"png\", \"ps\", \"raw\", \"svg\", \"tif\", \"webp\"];\n\nmpl.default_extension = \"png\";/* global mpl */\n\nvar comm_websocket_adapter = function (comm) {\n // Create a \"websocket\"-like object which calls the given IPython comm\n // object with the appropriate methods. Currently this is a non binary\n // socket, so there is still some room for performance tuning.\n var ws = {};\n\n ws.binaryType = comm.kernel.ws.binaryType;\n ws.readyState = comm.kernel.ws.readyState;\n function updateReadyState(_event) {\n if (comm.kernel.ws) {\n ws.readyState = comm.kernel.ws.readyState;\n } else {\n ws.readyState = 3; // Closed state.\n }\n }\n comm.kernel.ws.addEventListener('open', updateReadyState);\n comm.kernel.ws.addEventListener('close', updateReadyState);\n comm.kernel.ws.addEventListener('error', updateReadyState);\n\n ws.close = function () {\n comm.close();\n };\n ws.send = function (m) {\n //console.log('sending', m);\n comm.send(m);\n };\n // Register the callback with on_msg.\n comm.on_msg(function (msg) {\n //console.log('receiving', msg['content']['data'], msg);\n var data = msg['content']['data'];\n if (data['blob'] !== undefined) {\n data = {\n data: new Blob(msg['buffers'], { type: data['blob'] }),\n };\n }\n // Pass the mpl event to the overridden (by mpl) onmessage function.\n ws.onmessage(data);\n });\n return ws;\n};\n\nmpl.mpl_figure_comm = function (comm, msg) {\n // This is the function which gets called when the mpl process\n // starts-up an IPython Comm through the \"matplotlib\" channel.\n\n var id = msg.content.data.id;\n // Get hold of the div created by the display call when the Comm\n // socket was opened in Python.\n var element = document.getElementById(id);\n var ws_proxy = comm_websocket_adapter(comm);\n\n function ondownload(figure, _format) {\n window.open(figure.canvas.toDataURL());\n }\n\n var fig = new mpl.figure(id, ws_proxy, ondownload, element);\n\n // Call onopen now - mpl needs it, as it is assuming we've passed it a real\n // web socket which is closed, not our websocket->open comm proxy.\n ws_proxy.onopen();\n\n fig.parent_element = element;\n fig.cell_info = mpl.find_output_cell(\"
\");\n if (!fig.cell_info) {\n console.error('Failed to find cell for figure', id, fig);\n return;\n }\n fig.cell_info[0].output_area.element.on(\n 'cleared',\n { fig: fig },\n fig._remove_fig_handler\n );\n};\n\nmpl.figure.prototype.handle_close = function (fig, msg) {\n var width = fig.canvas.width / fig.ratio;\n fig.cell_info[0].output_area.element.off(\n 'cleared',\n fig._remove_fig_handler\n );\n fig.resizeObserverInstance.unobserve(fig.canvas_div);\n\n // Update the output cell to use the data from the current canvas.\n fig.push_to_output();\n var dataURL = fig.canvas.toDataURL();\n // Re-enable the keyboard manager in IPython - without this line, in FF,\n // the notebook keyboard shortcuts fail.\n IPython.keyboard_manager.enable();\n fig.parent_element.innerHTML =\n '';\n fig.close_ws(fig, msg);\n};\n\nmpl.figure.prototype.close_ws = function (fig, msg) {\n fig.send_message('closing', msg);\n // fig.ws.close()\n};\n\nmpl.figure.prototype.push_to_output = function (_remove_interactive) {\n // Turn the data on the canvas into data in the output cell.\n var width = this.canvas.width / this.ratio;\n var dataURL = this.canvas.toDataURL();\n this.cell_info[1]['text/html'] =\n '';\n};\n\nmpl.figure.prototype.updated_canvas_event = function () {\n // Tell IPython that the notebook contents must change.\n IPython.notebook.set_dirty(true);\n this.send_message('ack', {});\n var fig = this;\n // Wait a second, then push the new image to the DOM so\n // that it is saved nicely (might be nice to debounce this).\n setTimeout(function () {\n fig.push_to_output();\n }, 1000);\n};\n\nmpl.figure.prototype._init_toolbar = function () {\n var fig = this;\n\n var toolbar = document.createElement('div');\n toolbar.classList = 'btn-toolbar';\n this.root.appendChild(toolbar);\n\n function on_click_closure(name) {\n return function (_event) {\n return fig.toolbar_button_onclick(name);\n };\n }\n\n function on_mouseover_closure(tooltip) {\n return function (event) {\n if (!event.currentTarget.disabled) {\n return fig.toolbar_button_onmouseover(tooltip);\n }\n };\n }\n\n fig.buttons = {};\n var buttonGroup = document.createElement('div');\n buttonGroup.classList = 'btn-group';\n var button;\n for (var toolbar_ind in mpl.toolbar_items) {\n var name = mpl.toolbar_items[toolbar_ind][0];\n var tooltip = mpl.toolbar_items[toolbar_ind][1];\n var image = mpl.toolbar_items[toolbar_ind][2];\n var method_name = mpl.toolbar_items[toolbar_ind][3];\n\n if (!name) {\n /* Instead of a spacer, we start a new button group. */\n if (buttonGroup.hasChildNodes()) {\n toolbar.appendChild(buttonGroup);\n }\n buttonGroup = document.createElement('div');\n buttonGroup.classList = 'btn-group';\n continue;\n }\n\n button = fig.buttons[name] = document.createElement('button');\n button.classList = 'btn btn-default';\n button.href = '#';\n button.title = name;\n button.innerHTML = '';\n button.addEventListener('click', on_click_closure(method_name));\n button.addEventListener('mouseover', on_mouseover_closure(tooltip));\n buttonGroup.appendChild(button);\n }\n\n if (buttonGroup.hasChildNodes()) {\n toolbar.appendChild(buttonGroup);\n }\n\n // Add the status bar.\n var status_bar = document.createElement('span');\n status_bar.classList = 'mpl-message pull-right';\n toolbar.appendChild(status_bar);\n this.message = status_bar;\n\n // Add the close button to the window.\n var buttongrp = document.createElement('div');\n buttongrp.classList = 'btn-group inline pull-right';\n button = document.createElement('button');\n button.classList = 'btn btn-mini btn-primary';\n button.href = '#';\n button.title = 'Stop Interaction';\n button.innerHTML = '';\n button.addEventListener('click', function (_evt) {\n fig.handle_close(fig, {});\n });\n button.addEventListener(\n 'mouseover',\n on_mouseover_closure('Stop Interaction')\n );\n buttongrp.appendChild(button);\n var titlebar = this.root.querySelector('.ui-dialog-titlebar');\n titlebar.insertBefore(buttongrp, titlebar.firstChild);\n};\n\nmpl.figure.prototype._remove_fig_handler = function (event) {\n var fig = event.data.fig;\n if (event.target !== this) {\n // Ignore bubbled events from children.\n return;\n }\n fig.close_ws(fig, {});\n};\n\nmpl.figure.prototype._root_extra_style = function (el) {\n el.style.boxSizing = 'content-box'; // override notebook setting of border-box.\n};\n\nmpl.figure.prototype._canvas_extra_style = function (el) {\n // this is important to make the div 'focusable\n el.setAttribute('tabindex', 0);\n // reach out to IPython and tell the keyboard manager to turn it's self\n // off when our div gets focus\n\n // location in version 3\n if (IPython.notebook.keyboard_manager) {\n IPython.notebook.keyboard_manager.register_events(el);\n } else {\n // location in version 2\n IPython.keyboard_manager.register_events(el);\n }\n};\n\nmpl.figure.prototype._key_event_extra = function (event, _name) {\n // Check for shift+enter\n if (event.shiftKey && event.which === 13) {\n this.canvas_div.blur();\n // select the cell after this one\n var index = IPython.notebook.find_cell_index(this.cell_info[0]);\n IPython.notebook.select(index + 1);\n }\n};\n\nmpl.figure.prototype.handle_save = function (fig, _msg) {\n fig.ondownload(fig, null);\n};\n\nmpl.find_output_cell = function (html_output) {\n // Return the cell and output element which can be found *uniquely* in the notebook.\n // Note - this is a bit hacky, but it is done because the \"notebook_saving.Notebook\"\n // IPython event is triggered only after the cells have been serialised, which for\n // our purposes (turning an active figure into a static one), is too late.\n var cells = IPython.notebook.get_cells();\n var ncells = cells.length;\n for (var i = 0; i < ncells; i++) {\n var cell = cells[i];\n if (cell.cell_type === 'code') {\n for (var j = 0; j < cell.output_area.outputs.length; j++) {\n var data = cell.output_area.outputs[j];\n if (data.data) {\n // IPython >= 3 moved mimebundle to data attribute of output\n data = data.data;\n }\n if (data['text/html'] === html_output) {\n return [cell, data, j];\n }\n }\n }\n }\n};\n\n// Register the function which deals with the matplotlib target/channel.\n// The kernel may be null if the page has been refreshed.\nif (IPython.notebook.kernel !== null) {\n IPython.notebook.kernel.comm_manager.register_target(\n 'matplotlib',\n mpl.mpl_figure_comm\n );\n}\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "161b0ed12b47418bb434740e12dd00c0", + "version_major": 2, + "version_minor": 0 + }, + "image/png": "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", "text/html": [ - "
" + "\n", + "
\n", + "
\n", + " Time Plots\n", + "
\n", + " \n", + "
\n", + " " ], "text/plain": [ - "" + "Canvas(toolbar=Toolbar(toolitems=[('Home', 'Reset original view', 'home', 'home'), ('Back', 'Back to previous …" ] }, "metadata": {}, @@ -209,9 +197,9 @@ } ], "source": [ - "%matplotlib notebook\n", + "#%matplotlib notebook\n", "# Alternatively for Visual Studio Code use:\n", - "#%matplotlib widget\n", + "%matplotlib widget\n", "import gym_electric_motor as gem\n", "# instantiate a finite control set current controlled PMSM\n", "env = gem.make(\"Finite-CC-PMSM-v0\") \n", @@ -221,9 +209,20 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 2, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "c:\\Users\\jakobeit\\Anaconda3\\envs\\GEMUpdate\\lib\\site-packages\\gymnasium\\utils\\passive_env_checker.py:159: UserWarning: \u001b[33mWARN: The obs returned by the `reset()` method is not within the observation space.\u001b[0m\n", + " logger.warn(f\"{pre} is not within the observation space.\")\n", + "c:\\Users\\jakobeit\\Anaconda3\\envs\\GEMUpdate\\lib\\site-packages\\gymnasium\\utils\\passive_env_checker.py:159: UserWarning: \u001b[33mWARN: The obs returned by the `step()` method is not within the observation space.\u001b[0m\n", + " logger.warn(f\"{pre} is not within the observation space.\")\n" + ] + } + ], "source": [ "terminated = True\n", "\n", @@ -234,7 +233,7 @@ " (state, references), _ = env.reset()\n", " # Visualization of environment: Red vertical lines indicate a constraint violation and therefore, a reset environment.\n", " # Blue vertical lines indicate an additional reset by the user which is not due to a terminated episode.\n", - " \n", + " env.render()\n", " # pick random control actions\n", " action = env.action_space.sample()\n", " # Execute one control cycle on the environment\n", @@ -258,7 +257,7 @@ "\n", " * The ControlTask is in {`TC` / `SC` / `CC`} (Torque / Speed / Current Control)\n", "\n", - " * The MotorType is in {`PermExDc` / `ExtExDc` / `SeriesDc` / `ShuntDc` / `PMSM` / `SynRM` / `DFIM` / `SCIM` }\n", + " * The MotorType is in {`PermExDc` / `ExtExDc` / `SeriesDc` / `ShuntDc` / `PMSM` / `SynRM` / `DFIM` / `SCIM`, `EESM` }\n", " \n", " * The Version of all environments is currently 0. Therefore the VersionID equals `v0`. Future versions will be named `v1, v2,...`.\n", " \n" @@ -306,7 +305,7 @@ " * `my_reference_generator = SinusoidalReferenceGenerator(amplitude_range=(0.2,0.8))`\n", " * The reference generator instance will be used in the environment.\n", "\n", - "* Passing a keystring:\n", + "* Passing a keystring **(deprecated with GEM 3.0.0)**:\n", " * `my_reference_generator='SinusoidalReference'`\n", " * The Sinusoidal Reference Generator will be used in the environment with its default parameters.\n", " * Equals: `my_reference_generator=SinusoidalReferenceGenerator()`\n", @@ -350,7 +349,9 @@ "metadata": {}, "outputs": [], "source": [ - "supply = 'IdealVoltageSupply'" + "from gym_electric_motor.physical_systems.voltage_supplies import IdealVoltageSupply\n", + "\n", + "supply = IdealVoltageSupply(u_nominal=350)" ] }, { @@ -405,7 +406,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -448,7 +449,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 5, "metadata": {}, "outputs": [], "source": [ @@ -471,7 +472,7 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 6, "metadata": {}, "outputs": [], "source": [ @@ -505,7 +506,7 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 7, "metadata": {}, "outputs": [], "source": [ @@ -542,7 +543,7 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 8, "metadata": {}, "outputs": [], "source": [ @@ -604,7 +605,7 @@ }, { "cell_type": "code", - "execution_count": 12, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -634,7 +635,7 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -644,6 +645,25 @@ "# plots the states i_sd and i_sq and reward." ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### 2.7 ODE Solvers\n", + "\n", + "In GEM, all motor classes are simulated by their respective ODEs. To solve these ODEs, different solvers are available such as the EulerSolver which utilized the Euler discretization. All Scipy solvers are available using GEM's built-in wrapper classes such as `ScipyOdeSolver`." + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "from gym_electric_motor.physical_systems.solvers import EulerSolver\n", + "ode_solver = EulerSolver()" + ] + }, { "attachments": {}, "cell_type": "markdown", @@ -673,7 +693,7 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -721,7 +741,7 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ @@ -759,7 +779,7 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -834,7 +854,7 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": 15, "metadata": {}, "outputs": [], "source": [ @@ -857,7 +877,7 @@ }, { "cell_type": "code", - "execution_count": 20, + "execution_count": 16, "metadata": {}, "outputs": [], "source": [ @@ -877,9 +897,9 @@ " load=load,\n", " reward_function=rf,\n", " tau=tau,\n", - " #supply=supply,\n", + " supply=supply,\n", " reference_generator=rg,\n", - " ode_solver='euler',\n", + " ode_solver=ode_solver,\n", " callbacks=my_callback,\n", " physical_system_wrappers=physical_system_wrappers, # Pass the Physical System Wrappers\n", " constraints=constraints\n", @@ -891,7 +911,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "### 2.9 Seeding\n", + "### 2.10 Seeding\n", "The random processes in the environment can be made reproducible by seeding the environments. The seeding takes place when resetting an environment, i.e. calling `env.reset(seed=seed)` with the keyword argument `seed`. " ] }, @@ -919,18 +939,18 @@ { "data": { "application/vnd.jupyter.widget-view+json": { - "model_id": "da30fd6221fe4677b48a6d6c5295cadb", + "model_id": "2e768062e0f14b96a0c8e6deea594eae", "version_major": 2, "version_minor": 0 }, - "image/png": "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", + "image/png": "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", "text/html": [ "\n", "
\n", "
\n", - " Figure\n", + " Time Plots\n", "
\n", - " \n", + " \n", "
\n", " " ], @@ -955,9 +975,9 @@ "name": "stderr", "output_type": "stream", "text": [ - "C:\\Users\\arnet\\anaconda3\\envs\\gem_dev\\lib\\site-packages\\numpy\\core\\fromnumeric.py:3372: RuntimeWarning: Mean of empty slice.\n", + "c:\\Users\\jakobeit\\Anaconda3\\envs\\GEMUpdate\\lib\\site-packages\\numpy\\core\\fromnumeric.py:3504: RuntimeWarning: Mean of empty slice.\n", " return _methods._mean(a, axis=axis, dtype=dtype,\n", - "C:\\Users\\arnet\\anaconda3\\envs\\gem_dev\\lib\\site-packages\\numpy\\core\\_methods.py:170: RuntimeWarning: invalid value encountered in double_scalars\n", + "c:\\Users\\jakobeit\\Anaconda3\\envs\\GEMUpdate\\lib\\site-packages\\numpy\\core\\_methods.py:129: RuntimeWarning: invalid value encountered in scalar divide\n", " ret = ret.dtype.type(ret / rcount)\n" ] } @@ -967,7 +987,7 @@ "env.reset()\n", "k = 0\n", "for i in range(int(3e4)): \n", - "\n", + " env.render()\n", " (states, refs), rewards, terminated, truncated, _ = env.step(env.action_space.sample()) # pick random control actions\n", " if terminated:\n", " env.reset()\n", @@ -985,7 +1005,7 @@ ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "GEMUpdate", "language": "python", "name": "python3" }, @@ -999,7 +1019,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.6" + "version": "3.10.14" }, "varInspector": { "cols": { diff --git a/examples/environment_features/external_speed_profile.py b/examples/environment_features/external_speed_profile.py index 89f38236..9e7f43aa 100644 --- a/examples/environment_features/external_speed_profile.py +++ b/examples/environment_features/external_speed_profile.py @@ -2,13 +2,17 @@ import gym_electric_motor as gem from gym_electric_motor import reference_generators as rg from gym_electric_motor.visualization import MotorDashboard +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType +from gym_electric_motor.physical_systems.solvers import ScipySolveIvpSolver import time from scipy import signal -from gym_electric_motor.physical_systems.mechanical_loads \ - import ExternalSpeedLoad, ConstantSpeedLoad +from gym_electric_motor.physical_systems.mechanical_loads import ( + ExternalSpeedLoad, + ConstantSpeedLoad, +) -''' +""" This code example presents how the speed load classes can be used to define a speed profile which the drive will then follow. This is often useful when prototyping drive controllers that either @@ -16,17 +20,17 @@ drive torque with fixed speed requirements (e.g. traction applications, generator operation). For a more general introduction to GEM, we recommend to have a look at the "_control.py" examples first. -''' +""" # We will have a look at a current control scenario here const_sub_gen = [ # operation at 10 % of the current limit - rg.ConstReferenceGenerator(reference_state='i', reference_value=0.1), + rg.ConstReferenceGenerator(reference_state="i", reference_value=0.1), # operation at 90 % of the current limit - rg.ConstReferenceGenerator(reference_state='i', reference_value=0.9), + rg.ConstReferenceGenerator(reference_state="i", reference_value=0.9), # operation at 110 % of the current limit, - rg.ConstReferenceGenerator(reference_state='i', reference_value=1.1) + rg.ConstReferenceGenerator(reference_state="i", reference_value=1.1), ] # since the case of 110 % current may lead to limit violation, we only assign a small probability of 2 % to it @@ -37,39 +41,57 @@ # The ExternalSpeedLoad class allows to pass an arbitrary function of time which will then dictate the speed profile. # As shown here it can also contain more parameters. Some examples: # Parameterizable sine oscillation -sinus_lambda = (lambda t, frequency, amplitude, bias: amplitude * - np.sin(2 * np.pi * frequency * t) + bias) +sinus_lambda = ( + lambda t, frequency, amplitude, bias: amplitude * np.sin(2 * np.pi * frequency * t) + + bias +) # Constant speed -constant_lambda = (lambda t, value: value) +constant_lambda = lambda t, value: value # Parameterizable triangle oscillation -triangle_lambda = (lambda t, amplitude, frequency, bias: amplitude * signal.sawtooth(2 * np.pi * frequency * t, - width=0.5) + bias) +triangle_lambda = ( + lambda t, amplitude, frequency, bias: amplitude + * signal.sawtooth(2 * np.pi * frequency * t, width=0.5) + + bias +) # Parameterizable sawtooth oscillation -saw_lambda = (lambda t, amplitude, frequency, bias: amplitude * signal.sawtooth(2 * np.pi * frequency * t, - width=0.9) + bias) +saw_lambda = ( + lambda t, amplitude, frequency, bias: amplitude + * signal.sawtooth(2 * np.pi * frequency * t, width=0.9) + + bias +) # usage of a random load initializer is only recommended for the # ConstantSpeedLoad, due to the already given profile by an ExternalSpeedLoad -load_init = {'random_init': 'uniform'}, +load_init = ({"random_init": "uniform"},) # External speed profiles can be given by an ExternalSpeedLoad, # inital value is given by bias of the profile sampling_time = 1e-4 -if __name__ == '__main__': +#define the motor env object +motor = Motor( + motor_type=MotorType.SeriesDc, + control_type=ControlType.CurrentControl, + action_type=ActionType.Continuous, +) + + +if __name__ == "__main__": # Create the environment env = gem.make( - 'Cont-CC-SeriesDc-v0', - ode_solver='scipy.solve_ivp', + motor.env_id(), + ode_solver=ScipySolveIvpSolver(), tau=sampling_time, reference_generator=const_switch_gen, - visualization=MotorDashboard( - state_plots=['omega', 'i'], reward_plot=True), + visualization=MotorDashboard(state_plots=["omega", "i"], reward_plot=True), constraints=(), # using ExternalSpeedLoad: - load=ExternalSpeedLoad(speed_profile=saw_lambda, tau=sampling_time, - speed_profile_kwargs=dict(amplitude=40, frequency=5, bias=40)) + load=ExternalSpeedLoad( + speed_profile=saw_lambda, + tau=sampling_time, + speed_profile_kwargs=dict(amplitude=40, frequency=5, bias=40), + ), ) episode_duration = 0.2 # episode duration in seconds @@ -89,4 +111,4 @@ state, _ = env.reset() cum_rew += reward - print(f'Ep {eps} - cum_rew: {cum_rew:10.3f}') + print(f"Ep {eps} - cum_rew: {cum_rew:10.3f}") diff --git a/examples/environment_features/scim_ideal_grid_simulation.py b/examples/environment_features/scim_ideal_grid_simulation.py index 7d47db5f..e3d20c29 100644 --- a/examples/environment_features/scim_ideal_grid_simulation.py +++ b/examples/environment_features/scim_ideal_grid_simulation.py @@ -6,6 +6,8 @@ import numpy as np import gym_electric_motor as gem +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType +from gym_electric_motor.physical_systems.solvers import ScipyOdeSolver import matplotlib.pyplot as plt @@ -25,38 +27,36 @@ def grid_voltage(t): u_abc = [ amplitude * np.sin(omega * t + phi_initial), amplitude * np.sin(omega * t + phi_initial - phi), - amplitude * np.sin(omega * t + phi_initial + phi) - ] + amplitude * np.sin(omega * t + phi_initial + phi), + ] return u_abc + return grid_voltage +motor = Motor(motor_type=MotorType.SquirrelCageInductionMotor, control_type=ControlType.CurrentControl, action_type=ActionType.Continuous) # Create the environment env = gem.make( # Choose the squirrel cage induction motor (SCIM) with continuous-control-set - "Cont-CC-SCIM-v0", - + motor.env_id(), # load=gem.physical_systems.PolynomialStaticLoad( dict(a=0.0, b=0.0, c=0.0, j_load=1e-6) ), - # Define the numerical solver for the simulation - ode_solver="scipy.ode", - + ode_solver=ScipyOdeSolver(), # Define which state variables are to be monitored concerning limit violations # "()" means, that limit violation will not necessitate an env.reset() constraints=(), - # Set the sampling time - tau=1e-5 + tau=1e-5, ) tau = env.physical_system.tau limits = env.physical_system.limits # reset the environment such that the simulation can be started -(state, reference) = env.reset() +(state, reference),_ = env.reset() # We define these arrays in order to save our simulation results in them # Initial state and initial time are directly inserted @@ -97,16 +97,20 @@ def grid_voltage(t): # STATE[13]: u_sup (DC-link supply voltage) plt.subplots(2, 2, figsize=(7.45, 2.5)) -plt.subplots_adjust(left=None, bottom=None, right=None, top=None, wspace=0.08, hspace=0.05) -plt.rcParams.update({'font.size': 8}) +plt.subplots_adjust( + left=None, bottom=None, right=None, top=None, wspace=0.08, hspace=0.05 +) +plt.rcParams.update({"font.size": 8}) plt.subplot(2, 2, 1) plt.plot(TIME, STATE[0]) plt.ylabel(r"$\omega_\mathrm{me} \, / \, \frac{1}{\mathrm{s}}$") plt.xlim([TIME[0], TIME[-1]]) plt.yticks([0, 50, 100, 150]) -plt.tick_params(axis='x', which='both', labelbottom=False) -plt.tick_params(axis='both', direction="in", left=True, right=False, bottom=True, top=True) +plt.tick_params(axis="x", which="both", labelbottom=False) +plt.tick_params( + axis="both", direction="in", left=True, right=False, bottom=True, top=True +) plt.grid() ax = plt.subplot(2, 2, 2) @@ -118,8 +122,10 @@ def grid_voltage(t): plt.yticks([-200, 0, 200]) ax.yaxis.set_label_position("right") ax.yaxis.tick_right() -plt.tick_params(axis='x', which='both', labelbottom=False) -plt.tick_params(axis='both', direction="in", left=False, right=True, bottom=True, top=True) +plt.tick_params(axis="x", which="both", labelbottom=False) +plt.tick_params( + axis="both", direction="in", left=False, right=True, bottom=True, top=True +) plt.grid() plt.legend(loc="lower right", ncol=3) @@ -129,7 +135,9 @@ def grid_voltage(t): plt.ylabel(r"$T \, / \, \mathrm{Nm}$") plt.xlim([TIME[0], TIME[-1]]) plt.yticks([0, 20]) -plt.tick_params(axis='both', direction="in", left=True, right=False, bottom=True, top=True) +plt.tick_params( + axis="both", direction="in", left=True, right=False, bottom=True, top=True +) plt.grid() ax = plt.subplot(2, 2, 4) @@ -140,7 +148,9 @@ def grid_voltage(t): plt.xlim([TIME[0], TIME[-1]]) ax.yaxis.set_label_position("right") ax.yaxis.tick_right() -plt.tick_params(axis='both', direction="in", left=False, right=True, bottom=True, top=True) +plt.tick_params( + axis="both", direction="in", left=False, right=True, bottom=True, top=True +) plt.yticks([0, 10, 20, 30]) plt.grid() diff --git a/examples/environment_features/userdefined_initialization.py b/examples/environment_features/userdefined_initialization.py index 7ae529c3..f427a7fe 100644 --- a/examples/environment_features/userdefined_initialization.py +++ b/examples/environment_features/userdefined_initialization.py @@ -1,9 +1,11 @@ import gym_electric_motor as gem from gym_electric_motor import reference_generators as rg from gym_electric_motor.visualization import MotorDashboard +from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType +from gym_electric_motor.physical_systems.solvers import ScipySolveIvpSolver import time -''' +""" This code example presents how the initializer interface can be used to sample random initial states for the drive. This is important, e.g., when using reinforcement learning, because random initialization allows for a better exploration of the state space (so called "exploring starts"). @@ -11,68 +13,68 @@ mechanical load (which sets initial drive speed). For a more general introduction to GEM, we recommend to have a look at the "_control.py" examples first. -''' +""" # Initializers use the state names that are present for the used motor: # initializer for a specific current; e.g. DC series motor ('DcSeriesCont-v1' / 'DcSeriesDisc-v1') -dc_series_init = {'states': {'i': 12}} +dc_series_init = {"states": {"i": 12}} # initializer for a specific current and position; e.g. permanent magnet synchronous motor -pmsm_init = { - 'states': { - 'i_sd': -36.0, - 'i_sq': 55.0, - 'epsilon': 3.0 - } -} +pmsm_init = {"states": {"i_sd": -36.0, "i_sq": 55.0, "epsilon": 3.0}} # initializer for a random initial current with gaussian distribution, parameterized with mu=25 and sigma=10 gaussian_init = { - 'random_init': 'gaussian', - 'random_params': (25, 0.1), - 'states': {'i': 0} + "random_init": "gaussian", + "random_params": (25, 0.1), + "states": {"i": 0}, } # initializer for a ranom initial speed with uniform distribution within the interval omega=60 to omega=80 uniform_init = { - 'random_init': 'uniform', - 'interval': [[60, 80]], - 'states': {'omega': 0} + "random_init": "uniform", + "interval": [[60, 80]], + "states": {"omega": 0}, } # initializer for a specific speed -load_init = {'states': {'omega': 20}} +load_init = {"states": {"omega": 20}} + +motor = Motor(motor_type=MotorType.SeriesDc, control_type=ControlType.CurrentControl, action_type=ActionType.Continuous) -if __name__ == '__main__': +if __name__ == "__main__": env = gem.make( - 'Cont-CC-SeriesDc-v0', - visualization=MotorDashboard(state_plots=['omega', 'i']), - motor=dict(motor_parameter=dict(j_rotor=0.001), motor_initializer=gaussian_init), - load=dict(j_load=0.001, load_initializer=uniform_init), - ode_solver='scipy.solve_ivp', - reference_generator=rg.SwitchedReferenceGenerator( - sub_generators=[ - rg.SinusoidalReferenceGenerator(reference_state='omega'), - rg.WienerProcessReferenceGenerator(reference_state='omega'), - rg.StepReferenceGenerator(reference_state='omega') - ], - p=[0.2, 0.6, 0.2], - super_episode_length=(1000, 10000) - ), - constraints=(), - ) + motor.env_id(), + visualization=MotorDashboard(state_plots=["omega", "i"]), + motor=dict( + motor_parameter=dict(j_rotor=0.001), motor_initializer=gaussian_init + ), + load=dict(j_load=0.001, load_initializer=uniform_init), + ode_solver=ScipySolveIvpSolver(), + reference_generator=rg.SwitchedReferenceGenerator( + sub_generators=[ + rg.SinusoidalReferenceGenerator(reference_state="omega"), + rg.WienerProcessReferenceGenerator(reference_state="omega"), + rg.StepReferenceGenerator(reference_state="omega"), + ], + p=[0.2, 0.6, 0.2], + super_episode_length=(1000, 10000), + ), + constraints=(), + ) start = time.time() cum_rew = 0 for j in range(10): - state, reference = env.reset() + (state, reference), _ = env.reset() # Print the initial states: denorm_state = state * env.limits - print(f"Ep. {j}: Initial speed: {denorm_state[0]:5.2f} 1/s, Initial current: {denorm_state[2]:3.2f} A") + print( + f"Ep. {j}: Initial speed: {denorm_state[0]:5.2f} 1/s, Initial current: {denorm_state[2]:3.2f} A" + ) # We should be able to see that the initial state fits the used initializers # Here we should have omega in the interval [60 1/s, 80 1/s] and current closely around 25 A @@ -82,7 +84,3 @@ if terminated: break - - - - diff --git a/examples/gem_controllers/example.py b/examples/gem_controllers/example.py new file mode 100644 index 00000000..dec6f9b3 --- /dev/null +++ b/examples/gem_controllers/example.py @@ -0,0 +1,37 @@ +import gym_electric_motor as gem +import gem_controllers as gc +from gym_electric_motor.physical_system_wrappers import FluxObserver + + + +if __name__ == '__main__': + + # choose the action space + action_space = 'Cont' # 'Cont' or 'Finite' + + # choose the control task + control_task = 'CC' # 'SC' (speed control), 'TC' (torque control) or 'CC' (current control) + + # chosse the motor type + motor_type = 'PMSM' # 'PermExDc', 'ExtExDc', 'SeriesDc', 'ShuntDc', 'PMSM', 'EESM', 'SynRM' or 'SCIM' + + env_id = action_space + '-' + control_task + '-' + motor_type + '-v0' + + # using a flux observer for the SCIM + physical_system_wrappers = (FluxObserver(),) if motor_type == 'SCIM' else () + + # Initilize the environment + env = gem.make(env_id, physical_system_wrappers=physical_system_wrappers) + + # Initialize the controller + c = gc.GemController.make( + env, + env_id, + a=8, + block_diagram=True, + current_safety_margin=0.25, + save_block_diagram_as=(), + ) + + # Control the environment + c.control_environment(env, n_steps=30000, render_env=True, max_episode_length=10000) \ No newline at end of file diff --git a/examples/model_predictive_controllers/pmsm_mpc_dq_current_control.ipynb b/examples/model_predictive_controllers/pmsm_mpc_dq_current_control.ipynb index a7222e84..36dcd2e4 100644 --- a/examples/model_predictive_controllers/pmsm_mpc_dq_current_control.ipynb +++ b/examples/model_predictive_controllers/pmsm_mpc_dq_current_control.ipynb @@ -32,7 +32,7 @@ }, { "cell_type": "code", - "execution_count": 1, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -42,7 +42,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -52,10 +52,12 @@ "from gekko import GEKKO\n", "\n", "import gym_electric_motor as gem\n", + "from gym_electric_motor.envs.motors import ActionType, ControlType, Motor, MotorType\n", "from gym_electric_motor.physical_systems import ConstantSpeedLoad\n", "from gym_electric_motor.reference_generators import MultipleReferenceGenerator, SwitchedReferenceGenerator, \\\n", " TriangularReferenceGenerator, SinusoidalReferenceGenerator, StepReferenceGenerator\n", - "from gym_electric_motor.visualization.motor_dashboard import MotorDashboard" + "from gym_electric_motor.visualization.motor_dashboard import MotorDashboard\n", + "from gym_electric_motor.physical_systems.solvers import ScipySolveIvpSolver" ] }, { @@ -67,7 +69,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -95,7 +97,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -253,7 +255,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -271,7 +273,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -308,46 +310,21 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "application/javascript": "/* Put everything inside the global mpl namespace */\nwindow.mpl = {};\n\n\nmpl.get_websocket_type = function() {\n if (typeof(WebSocket) !== 'undefined') {\n return WebSocket;\n } else if (typeof(MozWebSocket) !== 'undefined') {\n return MozWebSocket;\n } else {\n alert('Your browser does not have WebSocket support. ' +\n 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n 'Firefox 4 and 5 are also supported but you ' +\n 'have to enable WebSockets in about:config.');\n };\n}\n\nmpl.figure = function(figure_id, websocket, ondownload, parent_element) {\n this.id = figure_id;\n\n this.ws = websocket;\n\n this.supports_binary = (this.ws.binaryType != undefined);\n\n if (!this.supports_binary) {\n var warnings = document.getElementById(\"mpl-warnings\");\n if (warnings) {\n warnings.style.display = 'block';\n warnings.textContent = (\n \"This browser does not support binary websocket messages. \" +\n \"Performance may be slow.\");\n }\n }\n\n this.imageObj = new Image();\n\n this.context = undefined;\n this.message = undefined;\n this.canvas = undefined;\n this.rubberband_canvas = undefined;\n this.rubberband_context = undefined;\n this.format_dropdown = undefined;\n\n this.image_mode = 'full';\n\n this.root = $('
');\n this._root_extra_style(this.root)\n this.root.attr('style', 'display: inline-block');\n\n $(parent_element).append(this.root);\n\n this._init_header(this);\n this._init_canvas(this);\n this._init_toolbar(this);\n\n var fig = this;\n\n this.waiting = false;\n\n this.ws.onopen = function () {\n fig.send_message(\"supports_binary\", {value: fig.supports_binary});\n fig.send_message(\"send_image_mode\", {});\n if (mpl.ratio != 1) {\n fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.ratio});\n }\n fig.send_message(\"refresh\", {});\n }\n\n this.imageObj.onload = function() {\n if (fig.image_mode == 'full') {\n // Full images could contain transparency (where diff images\n // almost always do), so we need to clear the canvas so that\n // there is no ghosting.\n fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n }\n fig.context.drawImage(fig.imageObj, 0, 0);\n };\n\n this.imageObj.onunload = function() {\n fig.ws.close();\n }\n\n this.ws.onmessage = this._make_on_message_function(this);\n\n this.ondownload = ondownload;\n}\n\nmpl.figure.prototype._init_header = function() {\n var titlebar = $(\n '
');\n var titletext = $(\n '
');\n titlebar.append(titletext)\n this.root.append(titlebar);\n this.header = titletext[0];\n}\n\n\n\nmpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n\n}\n\n\nmpl.figure.prototype._root_extra_style = function(canvas_div) {\n\n}\n\nmpl.figure.prototype._init_canvas = function() {\n var fig = this;\n\n var canvas_div = $('
');\n\n canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n\n function canvas_keyboard_event(event) {\n return fig.key_event(event, event['data']);\n }\n\n canvas_div.keydown('key_press', canvas_keyboard_event);\n canvas_div.keyup('key_release', canvas_keyboard_event);\n this.canvas_div = canvas_div\n this._canvas_extra_style(canvas_div)\n this.root.append(canvas_div);\n\n var canvas = $('');\n canvas.addClass('mpl-canvas');\n canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n\n this.canvas = canvas[0];\n this.context = canvas[0].getContext(\"2d\");\n\n var backingStore = this.context.backingStorePixelRatio ||\n\tthis.context.webkitBackingStorePixelRatio ||\n\tthis.context.mozBackingStorePixelRatio ||\n\tthis.context.msBackingStorePixelRatio ||\n\tthis.context.oBackingStorePixelRatio ||\n\tthis.context.backingStorePixelRatio || 1;\n\n mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n\n var rubberband = $('');\n rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n\n var pass_mouse_events = true;\n\n canvas_div.resizable({\n start: function(event, ui) {\n pass_mouse_events = false;\n },\n resize: function(event, ui) {\n fig.request_resize(ui.size.width, ui.size.height);\n },\n stop: function(event, ui) {\n pass_mouse_events = true;\n fig.request_resize(ui.size.width, ui.size.height);\n },\n });\n\n function mouse_event_fn(event) {\n if (pass_mouse_events)\n return fig.mouse_event(event, event['data']);\n }\n\n rubberband.mousedown('button_press', mouse_event_fn);\n rubberband.mouseup('button_release', mouse_event_fn);\n // Throttle sequential mouse events to 1 every 20ms.\n rubberband.mousemove('motion_notify', mouse_event_fn);\n\n rubberband.mouseenter('figure_enter', mouse_event_fn);\n rubberband.mouseleave('figure_leave', mouse_event_fn);\n\n canvas_div.on(\"wheel\", function (event) {\n event = event.originalEvent;\n event['data'] = 'scroll'\n if (event.deltaY < 0) {\n event.step = 1;\n } else {\n event.step = -1;\n }\n mouse_event_fn(event);\n });\n\n canvas_div.append(canvas);\n canvas_div.append(rubberband);\n\n this.rubberband = rubberband;\n this.rubberband_canvas = rubberband[0];\n this.rubberband_context = rubberband[0].getContext(\"2d\");\n this.rubberband_context.strokeStyle = \"#000000\";\n\n this._resize_canvas = function(width, height) {\n // Keep the size of the canvas, canvas container, and rubber band\n // canvas in synch.\n canvas_div.css('width', width)\n canvas_div.css('height', height)\n\n canvas.attr('width', width * mpl.ratio);\n canvas.attr('height', height * mpl.ratio);\n canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n\n rubberband.attr('width', width);\n rubberband.attr('height', height);\n }\n\n // Set the figure to an initial 600x600px, this will subsequently be updated\n // upon first draw.\n this._resize_canvas(600, 600);\n\n // Disable right mouse context menu.\n $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\n return false;\n });\n\n function set_focus () {\n canvas.focus();\n canvas_div.focus();\n }\n\n window.setTimeout(set_focus, 100);\n}\n\nmpl.figure.prototype._init_toolbar = function() {\n var fig = this;\n\n var nav_element = $('
');\n nav_element.attr('style', 'width: 100%');\n this.root.append(nav_element);\n\n // Define a callback function for later on.\n function toolbar_event(event) {\n return fig.toolbar_button_onclick(event['data']);\n }\n function toolbar_mouse_event(event) {\n return fig.toolbar_button_onmouseover(event['data']);\n }\n\n for(var toolbar_ind in mpl.toolbar_items) {\n var name = mpl.toolbar_items[toolbar_ind][0];\n var tooltip = mpl.toolbar_items[toolbar_ind][1];\n var image = mpl.toolbar_items[toolbar_ind][2];\n var method_name = mpl.toolbar_items[toolbar_ind][3];\n\n if (!name) {\n // put a spacer in here.\n continue;\n }\n var button = $('