Similar to rotational DC-Motors, the electro-mechanical energy conversion of translatory electrodynamic actuators can be described with the following two converter equations:
F = c_m * i V_i = c_m * vwith electrodynamic or Lorentz force F, motor constant c_m, current i, induced back-emf V_i and armature velocity v. For a moving coil actuator with a coil inside an air gap with flux density B and a total wire length l inside the magnetic field, the motor constant becomes
c_m = B * lThis motor constant c_m can roughly be determined with a lumped magnetic network model of the actuator's permanent magnetic excitation system. Coil resistance R and inductance L can be calculated from geometry and material data of the magnetic circuit and the winding as well.
Name | Description |
---|---|
![]() | Simple behavioural actuator model for system simulation |
![]() | Detailed actuator model for rough design of actuator and system simulation |
![]() | MagneticCircuitModel with fixed armature; suited for analysis of actuator model during magnetic design |
![]() | Armature stroke of MagneticCircuitModel with load mass |
This is a simple behavioural model of a translatory electrodynamic actuator (either moving coil or moving magnet type). The electro-mechanical conversion process is described with the motor constant c_m. The model is very similar to the well-known behavioural model of a rotational DC-Machine, except that it is for translatory motion.
The motor constant c_m as well as coil resistance R and inductance L are assumed to be known, e.g. from measurements or from catalogue data. Hence this model is well-suited for system simulation together with neighbouring subsystems, but not for actuator design, where the motor constant is to be found on base of the magnetic circuit's geometry, material properties and winding data. See MagneticCircuitModel for an actuator model intended for rough design of an electrodynamic actuator. Due to identical connectors, both models can be used in system simulation, e.g. to simulate a stroke as demonstrated in ArmatureStroke.
Type | Name | Default | Description |
---|---|---|---|
Real | c_m | 1 | Motor constant in N/A and V/(m/s) respectively |
Mass | m_a | 0.1 | Armature mass [kg] |
Position | x_min | 0 | Minimum armature position [m] |
Position | x_max | 0.1 | Maximum armature position [m] |
Resistance | R_coil | 1 | Coil resistance [Ohm] |
Inductance | L_coil | 0.1 | Coil inductance [H] |
Type | Name | Description |
---|---|---|
NegativePin | n | Electrical connector |
PositivePin | p | Electrical connector |
Flange_a | flange | Flange for connection to translatory load |
model MotorConstantModel "Simple behavioural actuator model for system simulation" extends Modelica_Magnetic.Interfaces.ElectromechanicalActuator; parameter Real c_m = 1 "Motor constant in N/A and V/(m/s) respectively"; parameter SI.Mass m_a = 0.1 "Armature mass"; parameter SI.Position x_min = 0 "Minimum armature position"; parameter SI.Position x_max = 0.1 "Maximum armature position"; parameter SI.Resistance R_coil = 1 "Coil resistance"; parameter SI.Inductance L_coil = 0.1 "Coil inductance"; SI.Position x(start=x_min, stateSelect=StateSelect.prefer) "Armature position, alias for flange position"; Modelica.Electrical.Analog.Sensors.CurrentSensor iSensor "coil current"; Modelica.Electrical.Analog.Sources.SignalVoltage u_i "Induced back-emf due to armature motion"; Modelica.Mechanics.Translational.Force MotorForce; Modelica.Electrical.Analog.Basic.Resistor R(R=R_coil) "Coil resistance"; Modelica.Mechanics.Translational.Sensors.SpeedSensor vSensor "armature velocity"; Modelica_Magnetic.Utilities.TranslatoryArmature armature( m=m_a, x_max=x_max, x_min=x_min) "Armature inertia with stoppers at end of stroke range"; Modelica.Electrical.Analog.Basic.Inductor L(L=L_coil) "Coil inductance"; Modelica.Blocks.Math.Gain c_force(k=c_m); Modelica.Blocks.Math.Gain c_velocity(k=c_m); equation flange.s = x; connect(iSensor.n, u_i.p); connect(R.p, p); connect(u_i.n, n); connect(armature.flange_a, vSensor.flange_a); connect(armature.flange_b, flange); connect(L.p, R.n); connect(L.n, iSensor.p); connect(c_force.y, MotorForce.f); connect(c_velocity.y, u_i.v); connect(c_velocity.u, vSensor.v); connect(MotorForce.flange_b, armature.flange_a); connect(c_force.u, iSensor.i); end MotorConstantModel;
Please refer to the Parameters section for a schematic drawing of this axisymmetric moving coil actuator. The half-section below shows the field lines of the permanent magnetic field (without armature current) obtained with a finite element analysis (FEA). The overlaid network of magnetic flux tube elements with nearly homogenous flux is rather simple in this example. Leakage fields are accounted for with a leakage coefficient and an appropriate leakage reluctance R_mLeak. Despite its simplicity, the model is well-suited for initial rough design of such moving coil actuators prior to detailed magnetic design, e.g. with FEA.
Type | Name | Default | Description |
---|---|---|---|
Radius | r_core | 18.5e-3 | Radius of ferromagnetic stator core [m] |
Thickness | l_PM | 3.2e-3 | Radial thickness of permanent magnet ring [m] |
Length | t | 0.02 | Axial length of permanent magnet ring and air gap respectively [m] |
Length | t_add | 0.01 | Additional axial clearance between permanent magnet and stator bottom side [m] |
Thickness | t_bot | 0.01 | Axial thickness of stator bottom side [m] |
Thickness | l_air | 3e-3 | Total radial length of armature air gap [m] |
Thickness | l_clear | 0.5e-3 | Radial clearance armature <=> stator (on either side of armature) [m] |
Thickness | l_car | 0.5e-3 | Radial thickness of coil carrier [m] |
Thickness | t_out | 6.3e-3 | Radial thickness of outer section of stator [m] |
Breadth | w_w | 12e-3 | Width of armature winding (axial direction) [m] |
Position | x_min | w_w/2 | Minimum armature position [m] |
Position | x_max | t - w_w/2 | Maximum armature position [m] |
Mass | m_a | 0.08 | Armature mass [kg] |
![]() |
Type | Name | Description |
---|---|---|
NegativePin | n | Electrical connector |
PositivePin | p | Electrical connector |
Flange_a | flange | Flange for connection to translatory load |
model MagneticCircuitModel "Detailed actuator model for rough design of actuator and system simulation" extends Modelica_Magnetic.Interfaces.ElectromechanicalActuator; parameter SI.Radius r_core = 18.5e-3 "Radius of ferromagnetic stator core"; parameter SI.Thickness l_PM = 3.2e-3 "Radial thickness of permanent magnet ring"; parameter SI.Length t = 0.02 "Axial length of permanent magnet ring and air gap respectively"; parameter SI.Length t_add = 0.01 "Additional axial clearance between permanent magnet and stator bottom side"; parameter SI.Thickness t_bot = 0.01 "Axial thickness of stator bottom side"; parameter SI.Thickness l_air = 3e-3 "Total radial length of armature air gap"; parameter SI.Thickness l_clear = 0.5e-3 "Radial clearance armature <=> stator (on either side of armature)"; parameter SI.Thickness l_car = 0.5e-3 "Radial thickness of coil carrier"; parameter SI.Thickness t_out = 6.3e-3 "Radial thickness of outer section of stator"; parameter SI.Breadth w_w = 12e-3 "Width of armature winding (axial direction)"; parameter SI.Position x_min = w_w/2 "Minimum armature position"; parameter SI.Position x_max = t - w_w/2 "Maximum armature position"; parameter SI.Mass m_a = 0.08 "Armature mass"; SI.Position x(start = x_min, stateSelect=StateSelect.prefer) "Armature position, alias for flange position"; SI.Reluctance R_mTot "Estimate for total reluctance as seen by coil"; // R_mTot is different from total reluctance as seen by permanent magnet's magnetomotive force, see info Sources.ConstantMMF theta_PM(theta=PM.H_cB*l_PM) "Permanent magnet's magnetomotive force"; MagneticGround magGround; Modelica_Magnetic.FluxTube.FixedShape.HollowCylinderRadialFlux R_mPM( my_rConst=PM.my_r, b=t, r_i=r_core + l_air, r_o=r_core + l_air + l_PM, nonLinearPermeability=false) "Reluctance of permanent magnet"; Material.HardMagnetic.PermanentMagnetBehaviour PM(redeclare record material = Modelica_Magnetic.Material.HardMagnetic.NdFeB, T_opCelsius=coil.T_opCelsius) "Permanent magnet material; coercitivity and relative permeabiliity used in theta_PM and R_mPM"; Modelica_Magnetic.FluxTube.FixedShape.HollowCylinderRadialFlux R_mAir( b=t, my_rConst=1, r_i=r_core, r_o=r_core + l_air, nonLinearPermeability=false) "Reluctance of radial air gap between core and permanent magnet"; Modelica_Magnetic.FluxTube.Leakage.LeakageWithCoefficient R_mLeak( c_leak=0.2, R_m(start=1e6), R_mUsefulTot=R_mAir.R_m + R_mFeCore.R_m + R_mFeBot.R_m + R_mFeOut.R_m) "Simple estimate for leakage reluctance"; Modelica_Magnetic.FluxTube.FixedShape.HollowCylinderAxialFlux R_mFeCore( redeclare record Material = Modelica_Magnetic.Material.SoftMagnetic.Steel.Steel_9SMnPb28, l=t_add + t/2, r_o=r_core) "Reluctance of ferromagnetic stator core"; Modelica_Magnetic.FluxTube.FixedShape.HollowCylinderAxialFlux R_mFeOut( redeclare record Material = Modelica_Magnetic.Material.SoftMagnetic.Steel.Steel_9SMnPb28, l=t_add + t/2, r_i=r_core + l_air + l_PM, r_o=R_mFeOut.r_i + t_out) "Reluctance of outer section of ferromagnetic stator"; Modelica_Magnetic.Sources.CoilDesign coil( b_w=12e-3, U=6, J_desired=20e6, T_opCelsius=20, d_wireChosen=0.315e-3, w_chosen=140, h_w=l_air - 2*l_clear - l_car, l_avg=2*pi*(r_core + l_clear + l_car + coil.h_w/2)) "Calculation of coil parameters (wire diameter, number of turns et al.) and recalculation with optionally chosen wire diameter"; Modelica.Electrical.Analog.Sensors.CurrentSensor iSensor "coil current"; Modelica.Electrical.Analog.Sources.SignalVoltage u_i "induced voltage due to armature motion"; Utilities.VariableGain c_force "Motor constant (gain variable due to variability of B_Air)"; Utilities.VariableGain c_velocity "Motor constant (gain variable due to variability of B_Air)"; Modelica.Mechanics.Translational.Force MotorForce; Modelica.Mechanics.Translational.Sensors.SpeedSensor vSensor "armature velocity"; Utilities.TranslatoryArmature armature( m=m_a, x_max=x_max, x_min=x_min) "Inertia of armature and stoppers at end of stroke range"; Modelica.Electrical.Analog.Basic.VariableInductor L_coil; Modelica.Electrical.Analog.Basic.Resistor R_coil(R=coil.R_actual); Modelica_Magnetic.FluxTube.FixedShape.HollowCylinderRadialFlux R_mFeBot( redeclare record Material = Modelica_Magnetic.Material.SoftMagnetic.Steel.Steel_9SMnPb28, b=t_bot, r_i=r_core/2, r_o=R_mFeOut.r_i + t_out/2); equation c_force.k = R_mAir.B * coil.w_chosen*coil.l_avg; // Motor constant c_velocity.k = c_force.k; R_mTot = 1/(R_mPM.G_m/2 + R_mLeak.G_m) + R_mFeCore.R_m + R_mFeBot.R_m + R_mFeOut.R_m + 2*R_mAir.R_m; // see info L_coil.L = coil.w_chosen^2 / R_mTot; x = flange.s; connect(magGround.p, theta_PM.n); connect(theta_PM.p, R_mPM.p); connect(R_mLeak.p, R_mPM.n); connect(R_mAir.p, R_mFeOut.n); connect(iSensor.n,u_i. p); connect(c_velocity.y,u_i. v); connect(iSensor.i,c_force. u); connect(u_i.n, n); connect(MotorForce.flange_b,vSensor. flange_a); connect(armature.flange_b, flange); connect(vSensor.v, c_velocity.u); connect(MotorForce.f, c_force.y); connect(L_coil.n, iSensor.p); connect(R_coil.p, p); connect(R_coil.n, L_coil.p); connect(armature.flange_a, MotorForce.flange_b); connect(R_mLeak.n, theta_PM.n); connect(R_mLeak.n, R_mAir.n); connect(R_mFeOut.p, R_mFeBot.n); connect(R_mFeBot.p, R_mFeCore.n); connect(R_mFeCore.p, R_mPM.n); end MagneticCircuitModel;
Have a look at ElectrodynamicActuator for general comments and at MagneticCircuitModel for a detailed explanation of this actuator model.
With the armature position fixed, all variables can easily be analyzed during rough design of the actuator. Simulate for 0.1 s and analyze, e.g. plot vs. time variables of interest such as flux densities:
actuator.R_mFeCore.B // flux density in stator core actuator.R_mFeOut.B // flux density in outer stator section actuator.R_mAir.B // air gap flux density relevant for Lorentz force actuator.R_mPM.B // flux density in permanent magnet.Compare the coil parameters calculated for desired operating conditions with the ones obtained for a chosen, available wire diameter:
actuator.coil.d_wireCalculated vs. actuator.coil.d_wireChosen // wire diameter actuator.coil.w_calculated vs. actuator.coil.w_chosen // number of turns actuator.coil.c_condFillChosen vs. actuator.coil.c_condFillActual // conductor filling factor actuator.coil.J_desired vs. actuator.coil.J_actual // current density.Watch the current rise due to the inductance of the armature coil by plotting vs. time:
actuator.p.i // input current to actuator.
model FixedArmature "MagneticCircuitModel with fixed armature; suited for analysis of actuator model during magnetic design" extends Modelica.Icons.Example; Modelica.Electrical.Analog.Sources.StepVoltage u_step( startTime=0, V=actuator.coil.U) "Supply voltage set to value defined in actuator.coil"; Modelica.Electrical.Analog.Basic.Ground ground; MagneticCircuitModel actuator; Modelica.Mechanics.Translational.Fixed fixedPos(s0=(actuator.x_min + actuator.x_max)/2) "Fixed armature position"; equation connect(ground.p, u_step.n); connect(actuator.p, u_step.p); connect(actuator.n, u_step.n); connect(fixedPos.flange_b, actuator.flange); end FixedArmature;
Have a look at ElectrodynamicActuator for general comments and at MagneticCircuitModel for a detailed explanation of this actuator model.
A voltage step is applied to the detailed model of the moving coil actuator. The actuator's armature and a therewith connected load mass perform a stroke between the two stoppers included in actuator.armature. Simulate for 0.05 s and plot vs. time:
actuator.p.i // input current to actuator actuator.MotorForce.f // Lorentz force, proportional to current m_load.v // armature and load mass velocity actuator.x // armature and load mass positionThe initial current rise is due to the inductance of the actuator coil. After acceleration of armature and load, the actuator approaches to an equilibrium between the applied voltage and the motion-induced back-emf (idle operating conditions). Bouncing occurs when the armature arrives at the stopper actuator.armature.stopper_xMax. The bouncing is rather intense due to the absence of any kind of external friction in this simple example (apart from the nonlinear damping in the stopper elements). After decay of this bouncing, the actuator operates under conditions valid for a blocked armature.
model ArmatureStroke "Armature stroke of MagneticCircuitModel with load mass" extends Modelica.Icons.Example; Modelica.Electrical.Analog.Sources.StepVoltage u_step(V=actuator.coil.U, startTime=0); Modelica.Electrical.Analog.Basic.Ground ground; MagneticCircuitModel actuator; Modelica.Mechanics.Translational.SlidingMass m_load(m=0.05) "Load to be moved in addition to the armature mass"; equation connect(ground.p, u_step.n); connect(actuator.p, u_step.p); connect(actuator.n, u_step.n); connect(m_load.flange_a, actuator.flange); end ArmatureStroke;