The content of this article is identical to the AN13902: 3-Phase Sensorless PMSM Motor Control Kit with S32K344 using MBDT Blocks
The Model-Based Design Toolbox (MBDT) enables the Model-Based Design workflow targeting NXP processors via the MATLAB® and Simulink® environments.
The toolbox was created to help in the development of increasingly complex applications. It is a collection of tools and libraries designed to assist customers with prototyping and accelerating algorithm development on MCUs and processors.
MBDT integrates NXP tools (Real-Time Drivers, Configuration Tools, Automotive Math and Motor Control Library (AMMCLib), Compilers and Toolchain), offering a complete development solution, with the following benefits:
S32K3 is an Arm® Cortex®-M7-based Microcontrollers family in single, dual, and lockstep core configurations, supporting up to ASIL (Automotive Safety Integrity Level) D functional safety automotive and industrial applications, running up to 240MHz, with FPU (Floating Point Unit). S32K3 is suitable for applications like Motor Control, Battery Management Systems (BMS) or Body Control Module (BCM).
The MBDT plug-in for S32K3 includes a motor control example (s32k3xx_mc_pmsm.mdl) which supports the following features:
To install the MBDT plug-in for S32K3, please check the Model-Based Design Toolbox for S32K3xx - Quick Start Guide under NXP MBDT page.
The s32k3xx_mc_pmsm.mdl example illustrates how the MCSPTE1AK344 BLDC and PMSM Motor Control Development Kit are used to run the Permanent Magnet Synchronous Motor (PMSM) vector control using Field Oriented Control (FOC) with two shunt current sensors. This Simulink® model is configured to work with a Sunrise 42BLY3A78-24110 motor, but users can load the "s32k3xx_mc_pmsm_data_linix.m" script to use the Linix 45ZWN24-40 motor.
After the application is deployed on target, the RGBLED0_GREEN should stay on. Select the desired motor speed, utilizing the provided project, and press the "On/Off" button in FreeMASTER. Alternatively, you can start the motor in CW mode by pressing the USER_SW0 button (SW6 on board), or in CCW mode by pressing the USER_SW1 button (SW5 on board). Pressing both buttons at the same time or the reset button stops the motor.
If there is no error, the motor should start to spin and the RGBLED0_GREEN will start to blink. If there is any error, the motor will not run, and the RGBLED0 will switch from GREEN to solid RED.
The model overview with all the blocks is presented in the picture below:
These are the main blocks:
The first block to run in the generated code has the purpose of configuring:
The hardware interrupt handler, which is set up to be activated by the ADC (Analog to Digital Converter) and to make a recurrent call to sample FOC state variables with a 100 μs period, serves as the primary driver for this motor control application.
The shunt resistors on the DEVKIT-MOTORGD are used to measure the motor stator phase currents. Current flows through each leg of the invertor (R56, R57, and R58) and produces a voltage drop that is fed into the Operational Amplifier for adding gain and signal filtering and read using the Analog-to-Digital Converter (ADC) peripheral. R60 is used as the low-side shunt resistor for the DC bus current.
Even though S32K344 includes three ADCs, and the board has three shunt resistors (R56, R57, and R58), only two currents are monitored concurrently in this application to illustrate ADC Single-shot mode and BCTU control mode in parallel. The following equation is used to get the third stator current:
More details about the specific hardware for the current measurements can be found in Chapter 3.3, "Phase Current Measurement," of the document “3-Phase Sensorless PMSM Motor Control Kit with S32K344 using RTD Low Level API” in Application Note AN13767.
The hardware interrupt handler calls the Measurements block subsystem:
The Measurement block reads the ADC FIFO (First In First Out) buffer, and using the MUX, it creates a bus with 3 signals, each containing the values from the respective ADC channel:
This subsystem also generates function calls for the other subsystems:
The block provides functionality to start the motor in a clockwise (CW) or counter-clockwise (CCW) direction and stop the motor:
When the USER_SW0 button is pressed, the motor starts in the CW direction, and when the USER_SW1 button is pressed, it starts in the CCW direction.
Pressing both buttons stops the motor and rearm the system to start again.
The FreeMASTER tool can read the two global variables (btSpeedUp and btSpeedDown) for starting or stopping the motor in CW or CCW.
The speed step increase/decrease is done by sequentially pressing the same button and this triggers the If Action subsystem below:
If the “cntSpeedUp” value is greater than the “MBD_SPEED_UP_CNT,” the counter value is reset to 0. Otherwise, it increases with each run of the subsystem.
This is the main motor control block and the most complex one from the MATLAB model:
The main state machine block controls the flow of the motor control application:
The application state machine consists of the following six states:
The INIT state, in which the PWM outputs are disabled, and the variables are reset to zero, is the first to execute.
Following initialization, the RGBLED0_GREEN is set to "On" and the "MBD_ready" is set before the device enters the "READY" state.
After the system enters CALIB state, where the offsets for phase A and phase B currents are measured.
Continuing with the ALIGN phase of the motor, the start-up ramp is initiated, and the motor enters in RUN state, where the motor switches from open loop to closed loop.
Every state will make a call to a model subsystem; therefore, we will examine these building elements next.
This block calculates all the stator currents based on the raw ADC readings and computes the Event and DC bus voltage:
Looking into the Compute Events and ADCs block:
An event is generated only when the motor starts with OnOffState set to OFF and the OnOffSwitch set to true, or when the motor stops with OnOffState set to ON and the OnOffSwitch set to false.
This subsystem checks if the OnOffState is equal to 1, and if it is true, it will set MBD_e_app_on as the output for the event; otherwise, it will be off.
Calc_iABC obtains the ADC raw values and converts them to real currents:
It also determines the third stator current, using the following formula:
The UDC_filt block gets the raw ADC value and computes the raw and filtered DC bus voltage:
The raw ADC values are shifted and multiplied with the constant MBD_U_DCB_MAX that is present in the MATLAB script “s32k3xx_mc_pmsm_data.m”.
The AMMCLib function GDFLIB_FilterMA implements an exponential moving average filter. The filter will initialize the internal state according to the preset value.
The purpose of this preset is to avoid excessive transients and, in this case, the constant 12 is used because the nominal DC voltage is 12 volts.
The output of UDC_filt block updates two global variables:
These variables are particularly important because they are used in the current loop in the fault state to check for overvoltage, the align state, and to eliminate the DC bus ripple.
This block resets all variables to their default init state and calls a function to disable the PWMs:
InitLeds block sets to zero the RGBLED0, along with OnOffState, OnOffSwitch, and SwitchFaultClear:
After all the variables are set, MBD_e_init_done is sent to the global variable Event.
This block checks if the MBD_State is faulted and then check for various errors that might have appeared, such as Overcurrent, Overvoltage, and Undervoltage:
Overcurrent is also checked for each phase A, B, or C, as well as overDCBusVoltage and overcurrent on the DC bus.
If any of the limits are reached, then a function call to disable PWM's outputs will be triggered.
This subsystem aligns the motor shaft by setting a constant value for the D and Q references:
The SetStates subsystem sets variables and resets the counter needed for the align process:
The inverse Park transformation is used by the Calc_uAIBReq to calculate the Ud and Uq voltages:
The Wait_to_align block is using a counter to wait until the motor shaft is mechanically aligned:
The align subsystem is using a timer to wait until the counter is negative, and then it resets all the following variables: DutyCycleValues(:), uDQReq1, uDQReq2, iDQReq1, iDQReq2, Rst_FastLoop, Rst_SlowLoop, trackingToSensorless, speedLoopCntr, openLoop_wRotEl, pospeControl_wRotEl, sensorless_wRotEl, sensorless_thRotEl, openLoop_thRotEl:
After all values are set, the MBD_e_align_done will be sent to the Event global variable.
The last subsystem eliminates the DC bus ripple and calculates the PWM duty cycle:
It uses two AMMCLib functions “GMCLIB_ElimDcBusRip” and “GMCLIB_SvmStd_FLT”.
The “GMCLIB_ElimDcBusRip” function provides a computational method for the recalculation of the direct Uα and Uβ quadrature components of the required stator voltage vector, to compensate for voltage ripples on the DC bus of the power stage.
The “GMCLIB_SvmStd_FLT” function transforms the values from the two-phase (α-β) orthogonal coordinate system to the six-phase system consisting of the two sets of star connected three phase stator windings (f32A-f32B-f32C) and (f32D-f32E-f32F) using the Space Vector Modulation (SVM) algorithm.
To illustrate the transformation from the Stator Reference voltages (alpha and beta) to the modified Space Vector Modulation SVM, we can take a closer look at the waveforms below:
We are using Modified Space Vector Modulation in order to achieve full DC bus voltage utilization by continuously shifting up and down the 3-phase voltage system.
This shifting is called “3rd harmonic injection” and allows us to change the amplitude of the first harmonic by 15.5%, which will allow us to get to a higher speed region or deliver more torque compared to the standard sinusoidal PWM modulation.
This state contains 2 blocks GreenLedOn and ReadyStateSetStates described in the picture below:
The GreenLedOn sets the RGBLED0 to a solid GREEN color and turns off the other two color LEDs.
The “ReadyStateSetStates” sends the value “MBD_e_ready” to Event and the constant “MBD_ready” to the “MBD_State” global variable.
The Ready state subsystem also creates a function call to disable the PWM outputs.
This block calculates the offsets for phase A and phase B currents and uses a counter to wait until it can reset variables:
The “Calculate_I_ABCoffsets” uses the “IphaseAB_raw” values and the constant “MBD_I_MAX” from the MATLAB script as inputs for the AMMCLib blocks.
The “GDFLIB_FilterMA_FLT” function block implements an exponential moving average filter used to calculate the offset between the raw phase currents and the maximum current “MBD_I_MAX” set as a constant in the script “s32k3xx_mc_pmsm_data.m” file.
The function returns a single precision floating-point value, representing the filtered value of the input signal in step (k).
The counter implementation is simple, using a decrement for each step and comparing:
If the “CalibCnt” counter value is higher than the “CalibTimer” value, it will trigger the subsystem “ResetVariables”:
This sets all variables above and sends the value “MBD_e_calib_done” to the Event global state.
This the main application block and contains the reset function, and the motor control loops:
The “Rst_FastLoop” variable is used to reset the motor control algorithm when the user wants to stop and restart the motor.
The motor control algorithm is pictured below, going from the current acquisition, Clark+Park transforms, BEMF observer, Current loop, Inverse Park plus DC bus ripple compensation and PWM out:
The schematic above is similar to the motor control application from the document “3-Phase Sensorless PMSM Motor Control Kit with S32K344 using RTD Low Level API” Application Note AN13767:
To simplify a bit the control system, we can take a “linear” look at this motor control algorithm from a block-set point of view:
The first step is the acquisition of the motor stator phase current.
The voltage drop on the shunt resistors is sent into the Op-Amp for amplification and signal filtering before being input for the ADC.
Then the ADC is used to sense two of the phase currents, and then the motor control algorithm calculates the third current based on Kirchhoff's Law, which states that the sum of currents entering a node is equal to zero:
The forward Clark transform is then used to convert the three-phase system to a two-phase orthogonal system (α, β).
The stationary system is then translated into a rotating d-q reference frame using the Park transform, after which it is fed into the back-EMF and Angle tracking Observer to compute the command voltages for the next PWM commutation.
The d-q coordinates are transformed to the alpha and beta stationary frames using the inverse Park.
The space vector modulation (SVM) block uses the inverse Clark transformation to produce the three-phase voltages for the motor windings, completing the motor control loop from current acquisition to the generated voltage command.
For more information about the equations, stationary and rotating reference frames, please read Chapter 3.2, “PMSM model in quadrature phase synchronous reference frame,” in the Application Note AN13767.
Current control is essential in a variable-frequency drive control method known as field-oriented control (FOC). The transformation of the stator phase currents into the orthogonal rotational two-phase system results in two independent current components.
The direct (d-axis) current component is known as the flux-producing component, and the orthogonal (q-axis) component to the magnetic flux is known as the torque-producing component.
The current control loop is used to control the torque and magnetic flux of the 3-phase motor with high accuracy, dynamics, and bandwidth.
Looking back into the MATLAB model, let’s follow the same logic from the ADC signal acquisition until the PWM output voltage commands.
First, we have the ADC raw values fed into the “Calc_iABC“ block that computes the three-phase currents, which are then converted to single-precision floating point using the “CurrentSenseProcessing” block.
Second, we have the Forward Clark transformation subsystem:
This uses the “GMCLIB_Clark_FLT” single precision floating point function, which is used to transform values from the three-phase (A-B-C) coordinate system to the two-phase (α-β) orthogonal coordinate system according to the following equations:
Next is the Park transformation, which uses “GMCLIB_Park_FLT” function:
This transforms values from the two-phase (α-β) stationary orthogonal coordinate system to the two-phase (d-q) rotational orthogonal coordinate system, according to these equations:
Were (theta_e) represents the electrical position of the rotor flux.
The Current loop block gets the d-q current coordinates as input, see below:
The “AMCLIB_CurrentLoop” function implements the current control loop, which is an integral part of FOC and represents the most inner loop in the motor control structure.
The current control loop contains two PI controllers in recurrent form, and the parameters are configurable inside the AMCLib block:
These parameters can be modified in the script “s32k3xx_mc_pmsm_data.m” from the model folder.
The output of the Current Loop is the Ud and Uq required command voltages, which are fed into the Invers Park block:
The “GMCLIB_ParkInv” function calculates the Inverse Park Transformation, which transforms quantities from the two-phase (d-q) rotational orthogonal coordinate system to the two-phase (α-β) stationary orthogonal coordinate system using the equations:
Next, the two signals feed the DC bus Ripple Compensation block:
Next, these signals are passed into the PWM modulation block:
The DutyCycleValues values are used to update the MCU timer that generates the PWM signals, which are fed into the GD3000 MOSFETs driver.
The “sin-cos” block calculates the sine, cosine of the rotor position (theta_e):
These signals are needed for the angle estimation and are fed into the Park and inverse Park blocks.
The top part of the back-EMF and Angle tracking Observer block contains the following:
The “AMCLIB_BemfObsrvDQ” function returns the phase error between the real and the estimated rotating reference frames:
The bottom part of the back-EMF and Angle tracking Observer block contains the “AMCLIB_TrackObsrv_FLT” function:
The position tracking observer has a PI controller that is calculating a linear approximation around the operating point Θestim = Θe.
The parameters of the block are:
The Observer feeds the “Omega_e” to the Speed Loop, called Slow Loop in this model.
All the above blocks are part of the “Fast Loop” of the motor control algorithm and are essential for the current control logic.
This function takes the phase error (Θerr) calculated by the “AMCLIB_BemfObsrvDQ” and uses it to estimate the angular velocity and position of the rotor.
The estimated rotor position is obtained by driving the phase error (Θerr) of the γ-δ reference frame towards zero in a phase-locked loop (PLL).
The PLL structure is depicted in the following diagram:
Further, we will present the other blocks or subsystems needed.
The Speed Loop subsystem is running at a much lower speed than the Current Loop:
The counter “speedLoopCntr” is used to run the Slow Loop subsystem when it is equal to the variable “MBD_SPEED_LOOP_CNTR”, executed 10 times slower than the Fast Loop:
First, the counter “speedLoopCntr” is reset to zero upon entering this subsystem, then it checks:
If “PosMode” equals two, it means that the motor is in sensorless mode, and it will set the speed:
Inside “PosMode1” there is a small state machine that works as a speed limiter:
This limits the speed output between two limits: “-HighLimSpeed” and “+HighLimSpeed”.
The Speed Loop block implements the function “AMCLIB_FWSpeedLoop”:
The “AMCLIB_FWSpeedLoop” function implements the speed PI controller in the FOC outer control loop and the field-weakening algorithm for permanent magnet synchronous motors:
The speed PI controller and the field weakening controller are implemented by the "AMCLIB FWSpeedLoop" function in the outer control loop shown in the preceding diagram.
This block calculates the open loop “theta_e” using a couple of AMMCLib functions:
In order to calculate theta, we know that omega (ω) or angular velocity is equal to the rate of change of the angular position θ with respect to time:
Furthermore, we can integrate omega based on the formula:
Now let us look at the MATLAB implementation:
This divides the "FwSpeedLoop_pRamp_fltState" variable value by the constant "MBD_WEL_MAX" and converts it to a 32-bit fractional data type.
The second part of the Open Loop is comprised of:
The function “GFLIB_IntegratorTR” implements a discrete integrator using the trapezoidal (bilinear) transform.
The result is converted to a 32-bit fractional data type and multiplied with the “pi” constant.
There are four running modes in the system:
Depending on the scenario, each mode modifies different parameters.
The force mode imposes the open loop omega, and zero for the other variables:
The tracking mode sets control omega to zero and theta to open loop:
When the motor is running in a closed loop (sensorless), the position mode is in case two.
This divides “theta_e” from the variable “sensorless_thRotEl” with the constant “pi” and convert it to a 32-bit fractional data type.
The default mode is:
The Automatic Mode consists of a state machine that switches the “PosMode” based on the open loop speed:
The function “MLIB_Abs_FLT” returns the absolute value of the open loop omega electrical.
The “PosMode” state machine has the following states:
There are 3 states based on the Open Loop Speed:
This ensures that the motor control algorithm automatically switches the operating mode based on the speed.
This block implements a timer that toggles the RGBLED0_GREEN.
The second function of this subsystem is to also shut down the other two LEDs, giving the value 0 for the NXP function block: Dio_WriteChannel for RGBLED0_BLUE and RGBLED0_RED.
The timer uses the variable "LEDCounter," which is incremented each period of the fast loop and compares it with the value 2500.
If it is higher, it will reinitialize the counter value to 0, and it will trigger the If Action Subsystem:
In this subsystem, the LEDState is compared with logic “1” and masked bitwise XORed, giving the resulting value to the variable and function Dio_WriteChannel for RGBLED0_GREEN.
This block generates the corresponding PWM duty cycle values based on the hardware scaling and the pre-calculated values for each channel.
The duty cycles are stored in a data variable as an array for the three channels.
They are multiplied by the constant "32768" for the duty cycle shift and then fed into the input for each PWM channel.
Also, the “DutyCycleValues” are adjusted for the Phase Shift input of the same PWM blocks and the Sync Update is fed with a constant "1," meaning that each channel is synchronized.
This subsystem uses the NXP PWM block and the function "PWM_SetDutyPhaseShift" for alignment of the three channels: PWM0, PWM1, and PWM2.
Open the "S32K_PMSM_Sensorless" project, click on the "App Control" page, select the desired speed using the gauge speed, and click on the "On/Off" button:
Furthermore, the user can look at various parameters, for example the IDQ currents below:
We can also take a close look at the three-phase motor currents:
The 3-phase currents are represented in RGB colors and show a peak of 1.4 [A] depending on the motor load.
The MCSPTE1AK344 Development Kit offers a complete set of hardware features that work together with the s32k3xx_mc_pmsm.mdl example, presented above, and creates a complete out-of-the-box experience for modeling the motor control algorithm using the NXP Model-Based Design Toolbox for S32K3.
MBDT enables the NXP tools like Automotive Math and Motor Control Library (AMMCLib), Compilers, Configuration Tools, Real-Time Drivers (RTD), and Toolchain in the Simulink® environment. Together with the Embedded Coder®, it generates optimized code for the microcontroller, ensuring that the most advanced software loops can run on the NXP MCUs with maximum performance.
Please visit the MBDT Community Page to learn more about the features of the Model-Based Design Toolbox for S32K3. You may start a topic here and have a direct conversation with the engineers that created MBDT toolboxes. Aside from typical application demos concentrating on Battery Management Systems, AUTOSAR, or Motor Control Applications, you can also follow the NXP MBDT training and courses such as the Beginner's Guide Series.
You might also visit NXP.com for additional information on the development ecosystem that NXP offers.