Skip to content

Commit

Permalink
Refactoring (#147)
Browse files Browse the repository at this point in the history
  • Loading branch information
mhinkkan authored Aug 21, 2024
1 parent 9cc8e69 commit c6e0bda
Show file tree
Hide file tree
Showing 8 changed files with 89 additions and 96 deletions.
17 changes: 5 additions & 12 deletions examples/flux_vector/README.txt
Original file line number Diff line number Diff line change
@@ -1,19 +1,12 @@
Flux-Vector Control
-------------------

These examples demonstrate flux-vector control of synchronous machine drives
[#Pel2009]_. In the implemented controller, rotor coordinates as well as
decoupling between the stator flux and torque channels are used according to
[#Awa2019]_. Furthermore, the stator flux magnitude and the electromagnetic
torque are selected as controllable variables.
These examples demonstrate flux-vector control of electric machine drives [#Pel2009]_. In the implemented controller, decoupling between the stator flux and torque channels are used according to [#Awa2019]_. Furthermore, the stator flux magnitude and the electromagnetic torque are selected as controllable variables. The implementation of sensorless mode corresponds to [Tii2024_].

.. rubric:: References

.. [#Pel2009] Pellegrino, Armando, Guglielmi, “Direct flux field-oriented
control of IPM drives with variable DC link in the field-weakening
region,” IEEE Trans.Ind. Appl., 2009,
https://doi.org/10.1109/TIA.2009.2027167
.. [#Pel2009] Pellegrino, Armando, Guglielmi, “Direct flux field-oriented control of IPM drives with variable DC link in the field-weakening region,” IEEE Trans.Ind. Appl., 2009, https://doi.org/10.1109/TIA.2009.2027167

.. [#Awa2019] Awan, Hinkkanen, Bojoi, Pellegrino, "Stator-flux-oriented
control of synchronous motors: A systematic design procedure," IEEE Trans.
Ind. Appl., 2019, https://doi.org/10.1109/TIA.2019.2927316
.. [#Awa2019] Awan, Hinkkanen, Bojoi, Pellegrino, "Stator-flux-oriented control of synchronous motors: A systematic design procedure," IEEE Trans. Ind. Appl., 2019, https://doi.org/10.1109/TIA.2019.2927316

.. [#Tii2024] Tiitinen, Hinkkanen, Harnefors, "Design framework for sensorless control of synchronous machine drives," IEEE Trans. Ind. Electron., 2024, https://doi.org/10.1109/TIE.2024.3429650
22 changes: 16 additions & 6 deletions examples/flux_vector/plot_flux_vector_im_2kw.py
Original file line number Diff line number Diff line change
@@ -1,17 +1,20 @@
"""
2.2-kW AM
===========
2.2-kW induction motor
======================
This example simulates sensorless flux-vector control of a 2.2-kW induction machine drive.
This example simulates sensorless flux-vector control of a 2.2-kW induction
machine drive.
"""
# %%
import numpy as np

from motulator.common.utils import Sequence
from motulator.drive import model
import motulator.drive.control.im as control
from motulator.drive.utils import (
BaseValues, NominalValues, plot, InductionMachineInvGammaPars, InductionMachinePars)
BaseValues, NominalValues, InductionMachineInvGammaPars,
InductionMachinePars, plot)

# %%
# Compute base values based on the nominal values (just for figures).
Expand All @@ -28,13 +31,14 @@
mdl_par = InductionMachinePars.from_inv_gamma_model_pars(par)
machine = model.InductionMachine(mdl_par)
mechanics = model.StiffMechanicalSystem(J=.015)
converter = model.Inverter(u_dc=540)
converter = model.VoltageSourceConverter(u_dc=540)
mdl = model.Drive(converter, machine, mechanics)

# %%
# Configure the control system.

# Set nominal values and limits for reference generation
cfg = control.FluxVectorControlCfg(base.u, base.w, base.tau)
cfg = control.FluxVectorControlCfg(.95*base.psi, 1.5*base.i, 1.5*nom.tau)
ctrl = control.FluxVectorControl(par, cfg, J=.015, T_s=250e-6, sensorless=True)

# %%
Expand All @@ -48,6 +52,11 @@
times = np.array([0, .125, .125, .875, .875, 1])*4
values = np.array([0, 0, 1, 1, 0, 0])*nom.tau
mdl.mechanics.tau_L = Sequence(times, values)

# No load, field-weakening (uncomment to try)
# ctrl.ref.w_m = lambda t: (t > .2)*2*base.w
# mdl.mechanics.tau_L = lambda t: 0

# %%
# Create the simulation object and simulate it.

Expand All @@ -56,4 +65,5 @@

# %%
# Plot results in per-unit values.

plot(sim, base)
14 changes: 3 additions & 11 deletions examples/grid_forming/README.txt
Original file line number Diff line number Diff line change
@@ -1,18 +1,10 @@
Grid-Forming Control
--------------------

These examples demonstrate grid-forming control for grid-connected converters.
The example :doc:`/auto_examples/grid_forming/plot_gfm_rfpsc_13kva` uses a
power-synchronization loop for synchronizing with the grid [#Har2020]_. In
:doc:`/auto_examples/grid_forming/plot_gfm_obs_13kva`, disturbance-observer-
based control is used [#Nur2024]_.
These examples demonstrate grid-forming control for grid-connected converters. The example :doc:`/auto_examples/grid_forming/plot_gfm_rfpsc_13kva` uses a power-synchronization loop for synchronizing with the grid [#Har2020]_. In :doc:`/auto_examples/grid_forming/plot_gfm_obs_13kva`, disturbance-observer-based control is used [#Nur2024]_.

.. rubric:: References

.. [#Har2020] Harnefors, Rahman, Hinkkanen, Routimo, "Reference-feedforward
power-synchronization control," IEEE Trans. Power Electron., 2020,
https://doi.org/10.1109/TPEL.2020.2970991
.. [#Har2020] Harnefors, Rahman, Hinkkanen, Routimo, "Reference-feedforward power-synchronization control," IEEE Trans. Power Electron., 2020, https://doi.org/10.1109/TPEL.2020.2970991

.. [#Nur2024] Nurminen, Mourouvin, Hinkkanen, Kukkola, "Multifunctional
grid-forming converter control based on a disturbance observer, "IEEE
Trans. Power Electron., 2024, https://doi.org/10.1109/TPEL.2024.3433503
.. [#Nur2024] Nurminen, Mourouvin, Hinkkanen, Kukkola, "Multifunctional grid-forming converter control based on a disturbance observer, "IEEE Trans. Power Electron., 2024, https://doi.org/10.1109/TPEL.2024.3433503
1 change: 0 additions & 1 deletion examples/obs_vhz/README.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,4 @@ These examples demonstrate observer-based V/Hz control for induction machines [#

.. [#Tii2022a] Tiitinen, Hinkkanen, Harnefors, "Stable and passive observer-based V/Hz control for induction motors," Proc. IEEE ECCE, Detroit, MI, Oct. 2022, https://doi.org/10.1109/ECCE50734.2022.9948057


.. [#Tii2022b] Tiitinen, Hinkkanen, Kukkola, Routimo, Pellegrino, Harnefors, "Stable and passive observer-based V/Hz control for synchronous Motors," Proc. IEEE ECCE, Detroit, MI, Oct. 2022, https://doi.org/10.1109/ECCE50734.2022.9947858
10 changes: 2 additions & 8 deletions examples/signal_inj/README.txt
Original file line number Diff line number Diff line change
@@ -1,14 +1,8 @@
Signal Injection
----------------

These examples demonstrate a square-wave signal injection for low-speed
operation based on [#Kim2012]_. A phase-locked loop is used to track the rotor
position. For a wider speed range, signal injection could be combined to a
model-based observer. The effects of magnetic saturation are not compensated
for in this version.
These examples demonstrate a square-wave signal injection for low-speed operation based on [#Kim2012]_. A phase-locked loop is used to track the rotor position. For a wider speed range, signal injection could be combined to a model-based observer. The effects of magnetic saturation are not compensated for in this version.

.. rubric:: References

.. [#Kim2012] Kim, Ha, Sul, "PWM switching frequency signal injection
sensorless method in IPMSM," IEEE Trans. Ind. Appl., 2012,
https://doi.org/10.1109/TIA.2012.2210175
.. [#Kim2012] Kim, Ha, Sul, "PWM switching frequency signal injection sensorless method in IPMSM," IEEE Trans. Ind. Appl., 2012, https://doi.org/10.1109/TIA.2012.2210175
5 changes: 3 additions & 2 deletions motulator/drive/control/im/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
ObserverBasedVHzControl, ObserverBasedVHzControlCfg)
from motulator.drive.control.im._vhz import VHzControl, VHzControlCfg
from motulator.drive.control._common import SpeedController
from motulator.drive.control.im._flux_vector import FluxVectorControl, FluxVectorControlCfg
from motulator.drive.control.im._flux_vector import (
FluxVectorControl, FluxVectorControlCfg)

__all__ = [
"FullOrderObserver",
Expand All @@ -25,5 +26,5 @@
"VHzControlCfg",
"SpeedController",
"FluxVectorControl",
"FluxVectorControlCfg"
"FluxVectorControlCfg",
]
86 changes: 44 additions & 42 deletions motulator/drive/control/im/_flux_vector.py
Original file line number Diff line number Diff line change
@@ -1,34 +1,35 @@
"""Flux-vector control of synchronous machine drives."""

from dataclasses import dataclass, InitVar
from dataclasses import dataclass

import numpy as np

from motulator.drive.control import DriveControlSystem, SpeedController
from motulator.drive.control.im._common import Observer, ObserverCfg


@dataclass
class FluxVectorControlCfg:
"""
Controller configuration.
Flux-vector control configuration.
Parameters
----------
nom_u_s : float
Nominal voltage
nom_w_s : float
Nominal speed
tau_max : float
Maximum torque reference
nom_psi_s : float
Nominal stator flux linkage (Vs).
max_i_s : float
Maximum stator current (A).
max_tau_M : float
Maximum torque reference (Nm).
k_u : float, optional
Voltage utilization factor. The default is 0.95.
"""
def __init__(self, nom_u_s, nom_w_s, nom_tau_M, k_u = 0.95) -> None:
self.nom_u_s = nom_u_s
self.nom_w_s = nom_w_s
self.tau_max = nom_tau_M * 1.5
self.nom_psi_s = nom_u_s/nom_w_s
self.k_u = k_u
nom_psi_s: float
max_i_s: float
max_tau_M: float
k_u: float = .95


# %%
class FluxVectorControl(DriveControlSystem):
Expand All @@ -41,9 +42,11 @@ class FluxVectorControl(DriveControlSystem):
Machine model parameters.
alpha_psi : float, optional
Bandwidth of the flux controller (rad/s). The default is 2*pi*100.
Flux-control bandwidth (rad/s). The default is 2*pi*100.
alpha_tau : float, optional
Bandwidth of the torque controller (rad/s). The default is 2*pi*200.
Torque-control bandwidth (rad/s). The default is 2*pi*200.
alpha_c : float, optional
Internal current-control bandwidth (rad/s). The default is 2*pi*200.
alpha_o : float, optional
Observer bandwidth (rad/s). The default is 2*pi*40.
J : float, optional
Expand All @@ -53,9 +56,6 @@ class FluxVectorControl(DriveControlSystem):
sensorless : bool, optional
If True, sensorless control is used. The default is True.
References
----------
"""

def __init__(
Expand All @@ -64,66 +64,68 @@ def __init__(
cfg: FluxVectorControlCfg,
alpha_psi=2*np.pi*100,
alpha_tau=2*np.pi*200,
alpha_c=2*np.pi*200,
alpha_o=2*np.pi*40,
J=None,
T_s=250e-6,
sensorless=True):
super().__init__(par, T_s, sensorless)
self.cfg = cfg

if J is not None:
self.speed_ctrl = SpeedController(J, 2*np.pi*4)
else:
self.speed_ctrl = None
self.observer = Observer(
ObserverCfg(par, T_s, sensorless, alpha_o))
# Bandwidths
self.observer = Observer(ObserverCfg(par, T_s, sensorless, alpha_o))
self.alpha_psi = alpha_psi
self.alpha_tau = alpha_tau
self.k = 0
self.alpha_c = alpha_c

def get_flux_reference(self, fbk):
"""Simple field-weakening with flux-magnitude
reduced inversely proportional to the speed at speeds beyond the nominal."""

"""Simple field-weakening strategy."""
# The flux magnitude is reduced inversely proportional to the angular
# frequency beyond the nominal.
max_u_s = self.cfg.k_u*fbk.u_dc/np.sqrt(3)
max_psi_s = max_u_s/np.abs(fbk.w_s) if fbk.w_s != 0 else np.inf
return np.min([max_psi_s, self.cfg.nom_psi_s])


def output(self, fbk):
"""Calculate references."""
par = self.par
par, cfg = self.par, self.cfg

# Get the references from the outer loop
ref = super().output(fbk)
ref = super().get_torque_reference(fbk, ref)

# Compute flux and torque references
ref.psi_s = self.get_flux_reference(fbk)
ref.tau_M = np.clip(ref.tau_M, -self.cfg.tau_max, self.cfg.tau_max)

# Torque estimates
# Limit the torque reference
ref.tau_M = np.clip(ref.tau_M, -cfg.max_tau_M, cfg.max_tau_M)

# Torque estimate
tau_M = 1.5*par.n_p*np.imag(fbk.i_s*np.conj(fbk.psi_s))

# Torque-production factor, c_tau = 0 corresponds to the MTPV condition
c_tau = 1.5*par.n_p*np.real(fbk.psi_R*np.conj(fbk.psi_s))

# References for the flux and torque controllers
v_psi = self.alpha_psi*(ref.psi_s - np.abs(fbk.psi_s))
v_tau = self.alpha_tau*(ref.tau_M - tau_M)
e_psi = self.alpha_psi*(ref.psi_s - np.abs(fbk.psi_s))
e_tau = self.alpha_tau*(ref.tau_M - tau_M)
if c_tau > 0:
v = (
1.5*par.n_p*np.abs(fbk.psi_s)*fbk.psi_R*v_psi +
1j*fbk.psi_s*par.L_sgm*v_tau)/c_tau
e_s = (
1.5*par.n_p*np.abs(fbk.psi_s)*fbk.psi_R*e_psi +
1j*fbk.psi_s*par.L_sgm*e_tau)/c_tau
else:
v = v_psi
e_s = e_psi

# Internal current reference for state feedback
ref.i_s = fbk.i_s + e_s/(self.alpha_c*self.par.L_sgm)
# Limit the current reference
if np.abs(ref.i_s) > cfg.max_i_s:
ref.i_s = cfg.max_i_s*ref.i_s/np.abs(ref.i_s)
e_sp = self.alpha_c*self.par.L_sgm*(ref.i_s - fbk.i_s)

# Stator voltage reference
ref.u_s = par.R_s*fbk.i_s + 1j*(fbk.w_m + fbk.w_r)*fbk.psi_s + v
ref.u_s = par.R_s*fbk.i_s + 1j*(fbk.w_m + fbk.w_r)*fbk.psi_s + e_sp
u_ss = ref.u_s*np.exp(1j*fbk.theta_s)

ref.d_abc = self.pwm(ref.T_s, u_ss, fbk.u_dc, fbk.w_s)

return ref

30 changes: 16 additions & 14 deletions motulator/drive/control/sm/_flux_vector.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,9 @@ class FluxVectorControl(DriveControlSystem):
coordinates as well as decoupling between the stator flux and torque
channels are used according to [#Awa2019b]_. Here, the stator flux
magnitude and the electromagnetic torque are selected as controllable
variables. Proportional controllers are used for simplicity. The magnetic
saturation is not considered in this implementation.
variables, and proportional controllers are used for simplicity
[#Tii2024]_. The magnetic saturation is not considered in this
implementation.
Parameters
----------
Expand All @@ -29,9 +30,9 @@ class FluxVectorControl(DriveControlSystem):
cfg : FluxTorqueReferenceCfg
Reference generation configuration.
alpha_psi : float, optional
Bandwidth of the flux controller (rad/s). The default is 2*pi*100.
Flux-control bandwidth (rad/s). The default is 2*pi*100.
alpha_tau : float, optional
Bandwidth of the torque controller (rad/s). The default is 2*pi*200.
Torque-control bandwidth (rad/s). The default is 2*pi*200.
alpha_o : float, optional
Observer bandwidth (rad/s). The default is 2*pi*100.
J : float, optional
Expand All @@ -52,6 +53,10 @@ class FluxVectorControl(DriveControlSystem):
control of synchronous motors: A systematic design procedure," IEEE
Trans. Ind. Appl., 2019, https://doi.org/10.1109/TIA.2019.2927316
.. [#Tii2024] Tiitinen, Hinkkanen, Harnefors, "Design framework for
sensorless control of synchronous machine drives," IEEE Trans. Ind.
Electron., 2024, https://doi.org/10.1109/TIE.2024.3429650
"""

def __init__(
Expand All @@ -65,15 +70,13 @@ def __init__(
T_s=250e-6,
sensorless=True):
super().__init__(par, T_s, sensorless)
# Subsystems
self.flux_torque_reference = FluxTorqueReference(cfg)
if J is not None:
self.speed_ctrl = SpeedController(J, 2*np.pi*4)
else:
self.speed_ctrl = None
self.observer = Observer(
ObserverCfg(par, alpha_o=alpha_o, sensorless=sensorless))
# Bandwidths
self.alpha_psi = alpha_psi
self.alpha_tau = alpha_tau

Expand All @@ -96,19 +99,18 @@ def output(self, fbk):
c_tau = 1.5*par.n_p*np.real(i_a*np.conj(fbk.psi_s))

# References for the flux and torque controllers
v_psi = self.alpha_psi*(ref.psi_s - np.abs(fbk.psi_s))
v_tau = self.alpha_tau*(ref.tau_M - tau_M)
e_psi = self.alpha_psi*(ref.psi_s - np.abs(fbk.psi_s))
e_tau = self.alpha_tau*(ref.tau_M - tau_M)
if c_tau > 0:
v = (
1.5*par.n_p*np.abs(fbk.psi_s)*i_a*v_psi +
1j*fbk.psi_s*v_tau)/c_tau
e_s = (
1.5*par.n_p*np.abs(fbk.psi_s)*i_a*e_psi +
1j*fbk.psi_s*e_tau)/c_tau
else:
v = v_psi
e_s = e_psi

# Stator voltage reference
ref.u_s = par.R_s*fbk.i_s + 1j*fbk.w_m*fbk.psi_s + v
ref.u_s = par.R_s*fbk.i_s + 1j*fbk.w_m*fbk.psi_s + e_s
u_ss = ref.u_s*np.exp(1j*fbk.theta_m)

ref.d_abc = self.pwm(ref.T_s, u_ss, fbk.u_dc, fbk.w_s)

return ref
Expand Down

0 comments on commit c6e0bda

Please sign in to comment.