Home
DRM140 - Freescale Semiconductor
Contents
1. 5 y6 FTMO counter ar E li A EN uS E C MM T FTMO Init trig PWM top channel PWM bottom channel PDBO CHO pee m ccs eme ena E co DC Bus voltage ADCO RA PDBOCH1 e coss PN AREA HL comm rM quM ee Phase current 1 ADCORB PDB1 CHO E C E Rc Phase current 2 gt ADC1 RA ADCI ISR ADCI ISR ADC1 ISR Interrupt AD channel conversion Result Register updated Figure 4 1 ADC conversion timing 4 3 4 Current measurement Closely related to the ADC conversion trigger timing is the assignment of the ADC channels to the measured analog signals For computation of the fast current control loop of the FOC it is necessary to know the values of all three motor phase currents Since there are only two ADC modules it is possible to sample only two analog quantities in one instance Assuming the motor represents a symmetrical 3 phase system the sum of all three instantaneous phase currents is zero O iA lp ic Equation 4 1 Since the phase currents are measured in the instance when the bottom transistors are conducting in cases of high duty cycle ratios current value is in the area of the maximum of the sine curve the time when the current can be measured is too short The bottom transistor must be switched on at least for a critical pulse width to get a stabilized current shunt resistor voltage drop The selection of the channels is done base
2. MSB Most Significant Bit NVIC Nested Vector Interrupt Controller an integral part of the ARMv7 core responsible for the interrupts processing PDB Programmable Delay Block PI controller Proportional integral controller PIT Periodic Interrupt Timer PMSM PM Synchronous Motor permanent magnet synchronous motor PWM Pulse width modulation RPM Revolutions per minute SCl Serial communication interface see also UART SPI Serial peripheral interface UART Universal Asynchronous Receiver Transmitter an MCU peripheral module allowing asynchronous serial communication between the MCU and other systems Section 2 System specification The system solution is designed to drive a 3 phase PM synchronous motor The application meets the following performance specification e Application is targeted at the MK60D100N Kinetis ARM Cortex M4 microcontroller e Freescale s Tower rapid prototyping system is used as the hardware platform e The control technique incorporates O O 0000000 0 O Vector control of a 3 phase PM synchronous motor Rotor position estimation using Back EMF observer and tracking observer algorithms Closed loop speed control Bi directional rotation Closed loop current control Flux and torque independent control Starting up with alignment Open loop start up until the motor speed reaches 1096 of nominal speed Field weakening is not implemented Reconstruction of 3 phase motor currents from two meas
3. Free wheel duration MCSTRUC EST STARTUP T The structure contains the necessary variables to perform the open loop start up The start up procedure is depicted in Figure 4 6 The structure description follows e Speed integration structure serves to integrate the speed resulting the position in the correct position scale e Position merging counter a variable representing the change of the weighing coefficient am from the Equation 3 2 e Open loop position generated position during open loop start up a result of the speed integration e Merged position the position that is result of the merging algorithm represents a result of the Equation 3 2 e Merging step an increment of which the merging counter ay is increased e Speed threshold when the position merging starts e current limitation during the open loop start up e Speed ramp increment during open loop e Free wheel duration duration of the free wheel sub state when during the start up process the required speed is changed to zero bOpenLoop Merging 100 f32PositionMergeCounter Speed f32speedReg f32SpeedReg f32SpeedEstimatedFilt f32spedRamp M1 SPEED START UP f32spedRamp M1 SPEED OBSERVER VALID i gt f32speedReq 0 Figure 4 6 Start up process More information on the startup process can be found in section 3 1 3 1 Open Loop Start up and Merging 4 6 4 5 Slow sp
4. DSC Digital signal controller DT Dead time a short time that must be inserted between the turning off of one transistor in the inverter half bridge and the turning on of the complementary transistor due to limited switching speed of the transistors FOC Field oriented control FTM FlexTimer module a timer module on the Kinetis K60 MCU which generates the 6 channel PWM GPIO General purpose input output IAR The name of the company producing compilers for different plattorms and MCU manufacturers including ARM IDE Integrated Development Environment UC Input output interfaces between a computer system and the external world A CPU reads an input to sense the level of an external signal and writes to an output to change the level of an external signal ISR Interrupt Service Routine a fragment of code a function that is executed when interrupts from the core or from the peripheral modules are generated LED Light emitting diode K60 Freescale Kinetis K60 ARM Cortex M4 32 bit microcontroller MCAT Motor Control Application Tuning Tool The PC application based on FreeMASTER allowing setting and tuning of the application parameters while observing the drive feedback signals MTPA Maximum Torque per Amp Algorithm A special algorithm used in vector control of AC motors This algorithm increases the efficiency and the power of the motor June 2013 Page 8 of 55 by utilizing the reluctance torque of the motor
5. The Figure 4 8 shows the snapshot of the Tool environment for tuning the sensorless algorithms It is recommended to use the MCAT tool and follow the methods of application parameters tuning described in the application notes related to the tool The developer can optimize the time needed for application tuning and achieve solid drive performance Before opening the tuning tool the FreeMASTER PC application has to be installed on the computer To start the tuning tool open the Kinetis_FOC_MCAT pmp from the gui MCAT directory Further information on tuning application constants and the tool itself can be found in the application notes related to the Motor Control Application Tuning Tool freescale Motor Control Application Tuning Tool Motor 1 PMSM o Expert y BEMF Observer DQ Position and Speed Calculation BEMF Observer Parameters BEMF Obsrv Constants TO Constants FO 250 H scale 0 915887 Kp gain 0 969696 t 8H U scale 0 759710 Kp scale a Tracking Observer Parameters Sg s am WI scale 0 065098 Ki scale e E 1H Kp gain 0 648612 Theta gain 0 66 Open Loop Start up Parameters Kpscue 2 ee 5 Start up ramp 1000 rpm sec Eis 0 957052 OL Start up Constants Start up current 1 A SE m Start up Inc 0 000303 Mergingspeed 300 rpm Start up Scaled 5 425000 Merging coeff so 96 Merging N Scaled 0 090909 Merging Coeff 0 008138 Data Type Frac32 Update FRM l
6. the results of AD conversion are read at the beginning of each particular State Machine Function even though the values are not used later in the program execution The flow chart depicted in Figure 4 9 gives an overview of the program flow during the execution of the ADC interrupt service routine when the application is in Run state and Spin sub state June 2013 Page 49 of 55 ADC ISR Start Functi Il Function call Clarke Transformation currents iti Function calls Position and en Cos ParkTransformation currents Park Transformation voltages Back EMF Observer IIR filter 1 order Tracking Observer MA filter speed estimation Clarke Transformation currents ParkTransformation currents D current PI controller Q current controller Limit Calculation incl SORT Q current PI controller U pdate PWM registers Inverse Park Transformation req voltages DCBus Ripple Elimination Space Vector Modulation ADC channel assignment Fast Control Function calls Loop SlowLoopCountDnCounter 0 Yes Slow Control Function calls Speed Ramp Loop Speed PI Controller FreeMASTER Recorder RETI Figure 4 9 ADC ISR flow chart 4 10 2 PORTC interrupt Button handling on the K60 tower board is performed in the ISR associated with the PORTC interrupt which is generated whenever one of the buttons is pressed At the beginning of the ISR simple logic is executed to evaluate which button was pressed and the inte
7. Freescale Inc 2012 Designed by Motor Control Teams Roznov pod Radhostem Figure 4 8 Motor Control Application Tuning Tool June 2013 Page 48 of 55 4 10 Interrupts The application requires the minimum number of interrupts due to the MCU hardware triggering the AD conversion 4 10 1 ADC1 Interrupt This interrupt request is triggered when the conversion of channel A of the ADC1 module is completed and has the highest priority As the interrupt is generated there are sampled values of physical quantities ready in the Result Registers A of the ADCO DC bus voltage Result Register B of the ADCO motor phase current 1 and Result Register A of the ADC1 module motor phase current 2 The interrupt is always enabled only for one module to avoid generating two interrupt requests at the same time because the triggers for motor phase currents are generated in the same instance In the beginning of the ADC1 ISR execution the Application State Machine function is called If the application is in the Run state the fast current control loop of the PMSM vector control algorithm is executed including the position and speed estimation As mentioned in previous chapter the slow speed control loop is also calculated based on the value of the software counter that is decremented each time the fast control loop is passed The interrupt flag is cleared by reading the result register of the ADC channel that triggered the interrupt Therefore
8. T eControl Frac32 f32UDcBus holds value of DCBus voltage scaled for DCB faults evaluation UWord32 uw32FaultId the number of fault that was latched This flag remains high also the next three seconds after the fault condition was removed UWord32 uw32FaultIdPending currently active fault UWord32 uw32CounterState the counter variable used for different application timing purposes UWord32 uw32TimeFullSpeedFreeWheel UWord32 uw32TimeFaultRelease UWordl6 uwl6CounterSlowLoop UWordl6 uwl6DividerSlowLoop J MCSTRUC FOC PMSM OBS DO T There is only one variable gsmi_prive within the application that has the declaration of this data type and stores all the application variables of PMSM FOC of one motor 4 7 Interface function The interface functions are used for the communication between the state machine and the master system These functions are called to control and monitor the motor 4 7 1 Switch control functions These functions control the switch of the motor The parameter is the boolean value determining the state of the switch ON true or OFF false void M1 SetAppSwitch bool bValue To read the status of the switch use the following function The state of the switch is returned as the boolean value bool M1 GetAppSwitch void 4 7 2 Command functions This function commands the speed of the motor The parameter is the Frac32 value void M1 SetSpeed Frac32
9. T sUDOReg Required voltage vector in d q coordinates MCLIB 2 COOR SYST ALPHA BETA T SUAlBeReq Required Alpha Beta voltage MCLIB ANGLE T sAnglePosEl Sine and Cosine values of the rotor angle for Park transformation GMCLIB ELIM DC BUS RIP T SElimDCBRip DCB ripple elimination parameters structure MCLIB 2 COOR SYST ALPHA BETA T sUA1BeDCBComp Compensated to DC bus Alpha Beta voltage MCLIB 3 COOR SYST T SDutyABC Applied duty cycles ABC GFLIB INTEGRATOR TR T sSpeedIntegrator structure contains the integrator parameters integrates the angular speed in order to get the position Frac32 f32VoltHertzRatio constant defining the applied voltage level based on actual frequency Frac32 f32BoostVoltage boost start up voltage Frac32 f32SpeedCmd required electrical frequency from master system Frac32 f32FrequencyRamp Required frequency limited by ramp the ramp output Frac32 32Angle Electrical angle of the rotor Frac32 32UDcBusFOC DC bus voltage scaled to phase voltage UWord16 uwl6SectorSVM SVM sector JMCSTRUCT SCALAR CTRL PMSM T The description of the variables contained in the structure follows e Frequency ramp structure serves to generate the frequency ramp e Required D Q voltage the D voltage is kept to zero level motor has permanent magnets the Q voltage is output from the Volt
10. The fast control loop executes all the necessary tasks to be able to achieve an independent control of the stator current components These include Three phase current reconstruction Forward Clarke transformation Forward and backward Park transformations Rotor magnetizing flux position evaluation DC bus voltage ripple elimination Space vector modulation SVM Furthermore algorithims for rotor position estimation are also executed in the fast control loop Forward Park transformation for currents and voltages Back EMF observer Tracking observer Moving average filter June 2013 Page 12 of 55 Merging algorithm for smooth transition from open loop start up to speed close loop operation The slow control loop executes the speed controller field weakening control if employed in the application and lower priority control tasks The PI speed controller output sets a reference for the torque producing quadrature axis component of the stator current ig reg The flux producing current ig reg is maintained at zero because the magnetizing flux is generated by permanent magnets on the rotor In the case when the field weakening is implemented in the application in order to reach higher than the nominal speed then the value of the ig rey current acquires negative values Thus it is acting against the flux of the rotor permanent magnets To achieve the goal of PM synchronous motor control the algorithm uses feedback signal
11. analog power supply J11 AN5 Signal Select Phase B current signal 1 2 1 2 J10 AN6 Signal Select 1 2 Phase C current signal 1 2 1 2 J12 AN2 Signal Select Phase A current signal Motor connector Power supply connector Encoder connector A L ET ad ch E eh L NX e ah gt 3 quen k 1 212 y Jumpers J2 J3 Jumpers J10 J11 J12 Figure 3 5 Jumpers and connectors positions on the TWR MC LV3PH Table 3 2 shows the signal assignment of the motor connector of the TWR MC LV3PH Table 3 2 Motor and encoder connectors on the TWR MC LV3PH Connector Pin Description Motor connector 1 Motor phase A June 2013 Page 17 of 55 J5 Motor phase B Motor phase C Cono Warning for Revision B of the TWR MC LV3PH Do not plug any other cables into the Tower system except for the power supply cable and serial communication cable Do not connect any USB cable to the Tower system while the power is applied to the power stage module TWR MC LV3PH The demo system can be powered only via the Tower Low Voltage Power Stage Connecting a USB cable to the Tower Elevator Module could cause damage to the Kinetis K60 See Errata for the revision B of the TWR MC LV3PH on how to correctly operate the board The motor used in the reference design is part of the TWR MC LV3PH kit It is a BLDC motor with trapezoidal shape of the back EMF voltage with sal
12. data is transferred to the PC side after the trigger condition is met June 2013 Page 27 of 55 The FreeMASTER scope is a similar visualization tool to the recorder but the data from the embedded side is downloaded in real time The sampling rate is limited by the speed of the communication protocol and also influenced by the number of displayed variables It is usually used for waveforms visualization of slow transient phenomena such as the speed profile during motor acceleration 4 6 Program flow 4 6 1 Application structure Figure 4 3 shows the application software structure ADC1 conversion complete ISR 63 ps done lt PORTC ISR asynchronous done Application State Machine PMSM FOC algorithm Critical Faults evaluation FreeMASTER Recorder Peripherals Init FreeMASTER poll Manual application control Run forever PDB Error ISR asynchronous done K Figure 4 3 Application structure PDB error flag clearing re enable PDB triggering The software structure consists of the application main routine entered after the CPU reset where the CPU and peripherals initialization is performed and the interrupts generated periodically where the motor control algorithms are executed 4 6 2 Application background loop The endless application background loop contains only the call to the FreeMASTER communication polling function FMSTR_Po11 The main application control task is executed
13. defined macros for conditional and parameter compilation The FreeMASTER driver does not perform any initialization or configuration of the SCI module it uses to communicate The communication between the MCU and the PC side can be performed with the help of the interrupt or via periodic calling of the polling function For a motor control application it is preferred to use the polling mode Both the communication and protocol decoding are handled in the application background loop The polling mode requires a periodic call of the FMSTR Poll function in the application main 4 5 3 FreeMASTER recorder and scope The recorder is a part of the FreeMASTER software that is able to sample the application variables at a specified sample rate The samples are stored in a buffer and read by the PC via an RS 232 serial port The sampled data can be displayed in a graph or the data can be stored The recorder behaves as a simple on chip oscilloscope with trigger pre trigger capabilities The size of the recorder buffer and the FreeMASTER recorder time base can be defined in the freemaster_cfg h configuration file The recorder routine must be called periodically from the loop in which you want to take the samples The following line must be added to the loop code Freemaster recorder FMSTR Recorder In this application the FreeMASTER recorder is called from the ADC1 interrupt which creates a 63 us time base for the recorder function Buffered
14. e Init Stop gt Fault the PWM output is disabled e Run gt Fault certain current and voltage variables are zeroed The PWM output is disabled The Run sub states are called when the state machine is in the Run state The Run sub state functions are as follows e Calib the current channels ADC offset calibration is performed The dc bus voltage is measured The PWM is set to 50 and its output is enabled e Ready the PWM is set to 50 and its output is enabled The current is measured and the ADC channels set up Certain variables are initialized June 2013 Page 32 of 55 e Align The current is measured and the ADC channels set up The rotor alignment algorithm is called The PWM is updated After the alignment time expiration the system is switched to Startup The dc bus voltage is measured e Startup The current is measured and the ADC channels set up The BEMF observer algorithm is called to estimate the speed and position The FOC algorithm is called The PWM is updated The dc bus voltage is measured and filtered The open loop start up algorithm is called The estimated speed is filtered e Spin The current is measured and the ADC channels set up The BEMF observer algorithm is called to estimate the speed and position The FOC algorithm is called The PWM is updated The motor spins The dc bus voltage is measured The estimated speed is filtered The speed ramp and the speed PI controller algorithm
15. f 32SpeedCmd It is called from the application state machine and PORTO interrupt service The inverse function is used to monitor the speed It returns the Frac32 value Frac32 M1 GetSpeed void June 2013 Page 45 of 55 4 8 Application parameters The application parameters to control the motors and application are written as macro definitions amp define The following list represents the parameters define I MAX 8 0 maximum measurable current define U_DCB_MAX 36 0 maximum measurable voltage define U_MAX 20 8 Maximum phase voltage define N_MAX 4400 0 max possible speed that the application can handle incl safety margin define E MAX 20 0 max value of Back EMF voltage define U_DCB_UNDERVOLTAGE FRAC32 0 4 undervoltage detection define U DCB OVERVOLTAGE FRAC32 0 8 overvoltage detection limit define i REQ MAX FRAC32 0 909090909091 motor nominal speed define JI PH NOM FRAC32 0 5 motor phase nominal current define OVERCURRENT LIMIT 3 0 motor overcurrent limit define OD_INDEX FRAC32 0 5 Mechanical Alignment define ALIGN_CURRENT FRAC32 0 25 current applied during alignment define ALIGN_DURATION 2000 1000x 1ms two seconds D current PI controller define D KP GAIN FRAC32 0 647937284946 controller proportiona
16. fast control loop is calculated would extend over one period of PWM This might happen if the user puts additional tasks into the ADC conversion complete interrupt In addition to the generation of PDB sequence error the more serious impact is on the quality of the control process as one of the key assumptions is not met the execution of control algorithms extends the sampling period The real time control application has to be designed in such a way that this situation never occurs 4 10 4 Project file structure The total number of source c and header files h in the project exceeds one hundred Therefore only the key project files will be described in more detail and the rest will be described in groups The main project folder is divided into three directories e build contains configuration files for the IAR compiler as well as the compiler s output executable and object files If the IAR Embedded Workbench for ARM is installed on your computer double clicking the workspace file TWRK60D100N PMSM SNSLESS eww located in the directory build iar launches the IAR IDE e gui contains the FreeMASTER configuration file Kinetis FOC pmp and supporting files control page in HTML format and the binary file with addresses of the variables It also contains FreeMASTER project for Motor Control Application Tuning Tool Kinetis FOC MCAT pmp located in the MCAT sub directory e Src contains the project source and header fil
17. following structure User state machine functions structure typedef struct PFCN_VOID_VOID Fault PFCN_VOID_VOID Init PFCN_VOID_VOID Stop PFCN_VOID_VOID Run SM APP STATE FCN T The user transient state machine functions are defined in the following structure User state transition functions structure typedef struct PFCN_VOID_VOID FaultInit PFCN_VOID_VOID InitFault PFCN_VOID_VOID InitStop PFCN VOID VOID StopFault PFCN VOID VOID StopInit PFCN VOID VOID StopRun PFCN VOID VOID RunFault PFCN VOID VOID RunStop SM APP TRANS FCN T The control flag s variable has the following definitions typedef unsigned short SM APP CTRI State machine control command flags define SM CTRL NONE 0x0 define SM CTRL PAULI 0x1 define SM CTRL FAULT CLEAR 0x2 define SM CTRL INIT DONE 0x4 define SM CTRL STOP 0x8 define SM CTRL STAR 0x10 define SM CTRL STOP ACK 0x20 define SM CTRL RUN ACK 0x40 The state identification variable has the following definitions Application state identification enum typedef enum FAULT 0 June 2013 Page 31 of 55 INIT STOP RUN SM APP STATE Woo H N H The state machine must be periodically called from the code using the following inline function This function input is the pointer to the above described state machine structure which is declared and ini
18. is called The speed command is evaluated e Freewheel the PWM output is disabled and the module is set to 50 96 The current is measured and the ADC channels set up The dc bus voltage is measured The system waits in this sub state for certain time which is given due to rotor inertia it means to wait until the rotor stops itself Then the system evaluates the conditions and proceeds into one of these sub states Align or Reagy The Run sub states have also the transition functions that are called in between the sub states transition The sub state transition functions are as follows e Calib gt Ready calibration done entering the Ready state e Ready gt Align non zero speed command entering the Align state Certain variables are initialized voltage speed position The alignment time is set up e Align gt Ready zero speed command entering the Ready state Certain voltage and current variables are zeroed The PWM is set to 50 e Align gt Startup alignment done entering the Startup state The filters and control variables are initialized The PWM is set to 50 e Startup gt Spin start up successful entering the Spin state e Startup gt Freewheel no action is done Can be used to handle the start up fail condition for more robust application e Spin gt Freewheel zero speed command entering the Freewheel state Certain variables are initialized voltage speed position The freewheel ti
19. loop start up until 10 of nominal speed e Targeted at the Tower rapid prototyping system K60 tower board Tower 3 phase low voltage power stage e Vector control with a speed closed loop e Rotation in both directions e Application speed ranges from 0 to 100 of nominal speed no field weakening e Operation via user s buttons on the Kinetis K60 tower board or via FreeMASTER software Benefits of our solution Kinetis is a mixed signal MCU family based on the new ARM Cortex M4 core and the most scalable portfolio of mixed signal ARM Cortex M4 MCUs in the industry Five performance options are available from 50 to 150 MHz with flash memory ranging from 32 KB to 1 MB and high RAM to flash ratios throughout Common peripherals memory maps and packages both within and across the MCU families allow for easy migration to greater less memory and functionality A vector control algorithm demonstrated in this application enables vector control of the PMSM with no need of position feedback sensor encoder or resolver while keeping high dynamic performance above 10 of nominal speed References 1 K60P144M150SF3RM K60 Sub Family Reference Manual Freescale Semiconductor 201 1 2 DRM110 Sensorless PMSM Control for an H axis Washing Machine Drive Designer Reference Manual Freescale Semiconductor 2010 3 DRM105 PM Sinusoidal Motor Vector Control with Quadrature Encoder Designer Reference Manual Freescale Semiconductor 2008 4 S
20. or sub structures for the field oriented control algorithm implementation The types used in this structure are defined in Freescale s Embedded Software Libraries FSLESL The following describes the items used in this application D and Q current PI controllers serves to control the D and Q current A B C currents measured 3 phase current input to the algorithm Alpha beta currents currents transformed into the alpha beta frame D Q currents currents transformed into the D Q frame Required D Q currents required currents in the D Q frame input to the algorithm D Q current error error difference between the required and measured D Q currents A B C duty cycles 3 phase duty cycles output from the algorithm Required alpha beta voltages required voltages in the alpha beta frame Compensated required alpha beta voltages the previous item recalculated on the actual level of the dc bus voltage Required D Q voltage required voltages in the alpha beta frame outputs from the PI controllers DC bus ripple elimination a sub structure containing parameters for calculation of the DC bus ripple elimination algorithm Angle electrical rotor angle sine cosine Alignment this sub structure contains items used at the alignment its detail description is in the chapter dedicated to the alignment Required DQ current and voltage structure entered from Motor Control Application Tuning tool Maximum ava
21. per Hertz equation e Required alpha beta voltage the required voltage vector in alpha beta coordinates e Angle electrical rotor angle sine cosine June 2013 Page 42 of 55 e DC bus ripple elimination a sub structure containing parameters for calculation of the DC bus ripple elimination algorithm e Compensated required alpha beta voltages e A B C duty cycles 3 phase duty cycles output from the algorithm Speed integration structure serves to integrate the speed resulting the position in the correct position scale The Volt Hertz ratio the constant given by ratio of nominal voltage to nominal speed Boost voltage the value of the voltage that is applied at zero frequency Required frequency proportional to required speed Ramped frequency frequency ramp algorithm output Angle required angle of the rotor result of the speed integration Actual value of DC bus voltage SVM sector sector information output from the SVM algorithm Kinetis K60 ARM Cortex M4 Fast control loop Inv Park Inverter Required Ramp speed Phase Currents FreeMASTER visualization m Blocks supported by Software Libraries C Peripherals Figure 4 7 Block diagram of the scalar control The Scalar Control function is also used for Voltage FOC when the motor can be controlled by direct change of the d and q portion of the required stator voltage 4 6 6 Control mode selector The control mode sel
22. provide a debugging diagnostic and demonstrational tool for the development of algorithms and applications Moreover it is very useful for tuning the application for different power stages and motors because almost all of the application parameters can be changed via the FreeMASTER interface The FreeMASTER consists of a component running on a PC and another part running on the target controller Different communication interfaces are supported RS 232 USB Ethernet OSBDM and the work on improvements and support for new families of microcontrollers is still in progress In the application the RS232 interface is used because it represents minimal communication overhead that has to be handled by the MCU and requires no interrupts working in polling mode which is important for motor control applications A detailed users guide of FreeMASTER software with useful hints for using it to develop a motor control application can be found in AN1948 10 4 5 2 FreeMASTER communication driver On the MCU side the FreeMASTER software driver is included in the project file structure It is a set of files supporting real time data capture Scope Recorder and handling the communication protocol There are some functions that are unique for each MCU family therefore FreeMASTER is issued for each MCU family separately In the freemaster_cfg h file the user can perform settings related to the communication and to the data buffer In the file are
23. with included motor e Tower Serial Module TWR SER All modules of the Tower system are available for order via the Freescale web page or from distributors so the user can easily build the hardware platform for which the application is targeted 3 2 1 Hardware set up and configuration Building the system using the modules of the Tower system is not difficult The peripheral modules and the MCU module are plugged into the elevator connectors while the white stripe on the side of the module boards determines the orientation to the Functional elevator the elevator with the mini USB connector power supplies and the switch see the following Figure 3 4 Functional Dummy Elevator zi Elevator Kinetis K60 Tower board Serial board Low voltage power stage Figure 3 4 Hardware built on the modules of the Tower system The MCU board should be placed on the top of the Tower system so the user s buttons are easily accessible June 2013 Page 16 of 55 It is necessary to configure the Tower 3 phase low voltage power stage The jumper settings are listed in the following table and the jumper positions are highlighted in Figure 3 5 See also the users manual 11 for more details e g hardware overcurrent threshold setting of the Tower low voltage power stage Table 3 1 Jumper settings of TWR MC LV3PH board Jumper Setting Note J2 VDDA Source Select Internal analog power supply J3 VSSA Source Select Internal
24. 8 ADC ISR EEOW CHARBT 22s ete dee ise e o eese teet ilte eere bea eh ate ni Da De dee eet etes 50 FIGURE 6 1 MOTOR STARTUP FROM ZERO SPEED TO 2000 BM 54 June 2013 Page 5 of 55 Table Title Page TABLE 1 1 ACRONYMS AND ABBREVIATED TERMS ne sn nnne siis sess ss sessi dass dass conocen anar anna caninas 8 TABLE 3 1 JUMPER SETTINGS OF TWR MC LV3PH BOARD nn nn etnies sss d sns nsa ss s sess sana ssa sas 17 TABLE 3 2 MOTOR AND ENCODER CONNECTORS ON THE TWRMGLVOPH nn nn nennen eis 17 TABLE 3 3 SPECIFICATION OF THE MOTOR EE 18 TABLE 4 1 KINETIS K60 PERIPHERALS ONVERVIENW nono nan EEEE nn none nnan anar sana ninia 19 TABLE 4 2 MEMORY USAGE VALUES IN BTS 53 June 2013 Page 6 of 55 Section 1 Introduction This paper describes the design of a sensorless vector control drive of the 3 phase permanent magnet synchronous motor PMSM The application runs on the Kinetis K60 ARM Cortex M4 microcontroller The document is more focused on the application implementation on the Kinetis K60 microcontroller and only briefly describes the theory of the PMSM vector control as itis well described in the referenced literature Although the paper describes implementation on the Kinetis K60 the application can successfully run on any of the microcontrollers from the Kinetis family Application features Sensorless vector control of a permanent magnet synchronous motor e e Back EMF observer used as a sensorless position estimator algorithm e Open
25. C and serves as the hardware trigger for the sampling In order to obtain a specified accuracy it is necessary to perform a self calibrating procedure of the ADC module before it is used in the application The calibration process also requires a programmer s intervention to generate the plus side and minus side gain calibration results and store them in the ADC plus side gain and minus side gain registers after the calibration function completes The calibration has to be performed for both the ADC modules After calibration the ADC modules are configured to a 12 bit accuracy The input clock of the ADC module is limited to 18 MHz according to the Kinetis K60 datasheet 9 The CPU frequency is set to 100 MHz so by using available prescaler value the input clock to the ADC module is set to 12 5 MHz That setting yields a conversion time of 2 2 us Finally the hardware trigger has to be enabled in the Status and Control Register 2 The Programmable Delay Block PDB provides controllable delays from either an internal or an external trigger or a programmable interval tick to the hardware trigger inputs of the ADCs so that a precise timing between ADC conversions is achieved The PDB module has an internal counter that overflows on a modulo value Because the input trigger comes periodically from the FTMO the input clock source and the modulo value is set identically as for the FTMO module The values in the channel delay registers are set to gene
26. C16 0 355579868709 define E SCALE FRAC16 0 341903719913 define WI SCALE FRAC16 0 056713652937 June 2013 Page 46 of 55 define N OBS VALID FRAC32 0 1 threshold speed value when the output from the Back EMF observer is considered Tracking observer define TO_KP_GAIN FRAC16 0 654545454545 define TO_KP_SHIFT 2 define TO_KI_GAIN FRAC16 0 789625033513 define TO KI SHIFT 7 11 define O_THETA_GAIN FRAC16 0 586666666667 define O THETA SHIFT 5 Open Loop Start up define OL_START_RAMP_INC FRAC32 0 000568181818 ramp increment define OL START I FRAC32 0 075000000000 max startup up current during open loop define MERG SPEED TRH FRAC32 0 102272727273 merging speed define MERG_COEFF FRAC32 0 008138020833 merging step Low pass filter for BEMF observer output filter coefficients set for cutoff frequency 70Hz define ERROR_B1 FRAC32 0 0017082 define ERROR_B2 FRAC32 0 0017082 define ERROR_A2 FRAC32 0 12352 Cascade Control Structure Module define SCALAR_INTEG_GAIN FRAC32 0 018333333333 speed integration for position generation used also for open loop startup define SCALAR VHZ CONST FRAC32 0 687500000000 define SCALAR_VHZ_U_BOOST FRAC32 0 187500000000 define SCALAR_RAMP_INC FRAC32 0 000014204545 The application constants are dependent on the
27. MC33937 gate driver is placed on the Tower low voltage power module and serves to drive the high side and low side MOSFET transistors of the 3 phase inverter In the application the initialization of the MC33937 has to be performed to set the dead time During the motor run there is also periodic checking of the status register of the driver in order to provide information on the latched faults The MC33937 driver requires precise timing of the SPI signals It is not possible to use the default setting of the SPI module on the MCU The exact timing of the SPI signals is listed in 7 4 3 6 SCI UART configuration The SCI is used in the application for the communication between the master system and the embedded application A master system is the notebook or the PC where the FreeMASTER software is installed in order to control the application and visualization of its state On the Kinetis K60 there are six UART modules implemented The UARTS is used because the hardware solution is based on the Tower modules The communication speed is set to 19200 Bd and in fact it is limited by the USB to Serial cable used The use of direct RS232 connection between the PC and the embedded side allows users to increase the communication speed to 115200 Bd The module configuration is performed in the FreeMASTER software driver included in the project 4 4 Enabling the interrupts on the core level The interrupt request enabled on the peripheral module must a
28. PGA 2 Commu SPI 3 1 MOSFET driver nications configuration UART 6 1 FreeMASTER communication CAN 2 USB 1 12C 2 SDHC 1 USB OTG 1 Ethernet 1 s ES 1 Timers FlexTimer 8 channels 6 channels Generation 6 channels PWM for motor control 2 channels a 2 channels PIT 4 PDB 2 channels for ADC 2 DC bus voltage and triggering phase current sampling initiation 2 channels for DAC triggering LPT 1 CMT 1 RTC 1 Other DMA 16 channels TSI 16 channels 4 3 1 FlexTimer0 configuration for generating a 6 channel PWM The FlexTimer Module FTM is a two to eight channel timer which supports input capture output compare and the generation of PWM signals to control an electric motor and power management applications The FTM time reference is a 16 bit counter that can be used as an June 2013 Page 20 of 55 unsigned or signed counter On the Kinetis K60 there are three instances of FTM One FTM has 8 channels the other two FTMs have 2 channels The procedure to configure the FlexTimer for generating a center aligned PWM with dead time insertion is described in the application note AN3729 6 Because the referenced application note supports an earlier version 1 0 of the FlexTimer implemented on the ColdFire V1 and with respect to the hardware used TWR MC LV3PH there are a few differences in the configuration as described below Initially it is necessary to enable the system clock for
29. PMSM Sensorless Vector Control on Kinetis Designer Reference Manual Document Number DRM140 Rev 1 1 06 2013 by Matus Plachy System Application Engineer Freescale To provide the most up to date information the revision of our documents on the World Wide Web will be the most current Your printed copy may be an earlier revision To verify you have the latest information available refer to http www freescale com The following revision history table summarizes changes contained in this document For your convenience the page number designators have been linked to the appropriate location June 2013 Page 1 of 55 Revision History Date Revision Description Page Level Number s 4 Jan 13 1 0 First Draft N A 6 7 2013 1 1 Renamed all instances of Motor Control Tuning N A Wizard to Motor Control Application Tuning Tool Renamed all instances of MCTW to MCAT June 2013 Page 2 of 55 Table of Contents SECTION 1 INTRODUCTION ccena vci ce cic eere eter coercere ee Application features iii e is 7 Benefits of oui solution iii 7 References O 7 Acronyms and Abbreviations eeeeeeees ee eeeeee eene nn nnne tn inse nnmnnn nnmnnn inse nnn nnn 8 SECTION 2 SYSTEM SPECIFICATION eeeees Y SECTION 3 SYSTEM DESIGN eene 10 3 1 enn eem 10 3 1 1 3 Phase Permanent Magnet Sync
30. a speed control loop It is used in the open loop start up because certain variables must be initialized to avoid speed drop outs when the system is switched from the speed open loop mode to the speed closed loop mode The structure description follows Speed PI controller structure serves to control the speed Speed ramp structure serves to generate the speed ramp Speed displays the speed of the motor Speed error error between the required and measured speed Ramped speed speed ramp algorithm output Required speed speed input to the ramp algorithm Ramp up and down increment entered from Motor Control Application Tuning tool Another structure that is described below is within the position speed estimation structure This structure serves for the open loop start up typedef struct GFLIB INTEGRATOR TR T sSpeedIntegrator Speed integrator structure Frac32 F32PositionMergeCounter incremented merging coefficient for position merging Frac32 32PositionOpenLoop generated open loop position from the speed ramp integration Frac32 f32MergedPosition merged position Frac32 f32MergingStep merging increment step Frac32 F32MergedSpeedThrs merging speed threshold Frac32 F32StartupCurrent required Iq current during open loop start up Frac32 F320LRampIncrement speed ramp limitation during startup June 2013 Page 40 of 55 UWord32 uw32TimeStartUpFreeWheel
31. achine amp gsM1 Ctrl Inside the user Run state function the sub state functions are called as follows Run sub state function mM1 STATE RUN TABLE meM1 StateRun where the parameter mem1_stateRun identifies the Run sub state 4 6 4 Sensorless PMS motor control The application controls one motor in sensorless mode It is designed so that enhancing the application to drive a second motor if CPU performance is adequate and the device possesses two motor control PWM timers does not require substantial modification For the second motor an additional application state machine is required which can be the same as for the first motor while the control process uses the same routine The inputs to this routine are the particular motors structures This approach saves the necessary program ROM in the application The following sections are dedicated to the motor control algorithm pieces 4 6 4 1 Field oriented control The field oriented control FOC alias vector control theory is described in the chapter 3 1 2 Introduction to Vector Control and in referenced literature A description of the FOC code implementation follows The FOC has been optimized into one function which has one input output pointer to a structure The prototype of the function is as follows void MCSTRUC FocPMSMCurrentCtrl MCSTRUC FOC PMSM T psFocPMSM The structure referred to by the input output structure pointer is defined as follows type
32. advanced position estimation algorithms can be found in the User s guide 5 and in the DRM110 2 The merging algorithm will be described in the following text June 2013 Page 13 of 55 Kinetis K60 ARM Cortex M4 slow control loop fast control loop Inv Park Trans la req m Ua Gei 0 a Inverter Required Ramp Lim speed x V la req Ae Ug Clarke Trans DC Bus Voltage Phase Currents CO MERGED lq req startup Dues GED El Blocks supported by Software Libraries Peripherals Figure 3 3 Block diagram of sensorless PMSM vector control As seen from the block diagram shown in Figure 3 3 the algorithm of PMSM vector control is represented as a chain of functions outputs of one function serve as inputs to the other functions Each body of the functions contains mathematical equations not involving the peripherals In order to speed up the development of any motor control applications these motor control functions together with some commonly used mathematic algorithms such as trigonometric functions controllers or limitations and digital filters were put into one set and they create the Motor Control Library The motor control libraries are available for some Freescale MCU platforms optimized for each platform in order to maximize the utilization of available core features The functions were tested and are well documented Therefore building the motor control application is for the developer simplified The de
33. ate Machine A 29 4 6 3 1 States Definition ete et eddie ette ER etie deus 29 4 6 3 2 Motor State Machine nii etate one e oe bg dee 32 4 6 4 Sensorless PMS Motor Control 36 4 6 4 1 Field Oriented Control 36 4 6 4 2 Position and speed estimation enne 38 4 6 4 3 Rotor alignment iota eee eie an Idee efe eee atti eee 39 4 6 4 4 Motor open loop Start Up ssssesseeeeee een eee nmen enn aurana aaraa niea 39 4 6 4 5 Slow speed control loop oooooooccconococonocononccononanononcnnncccnnnc nono cnn narran narran nennen 41 4 6 5 ro IEBerenirclbem EE 42 4 6 6 Control mode selector ssessssssssssssseseeennen nennen entere nnns nnne nene 43 4 7 Interface OO EE 45 4 7 1 Switch control functions esses ener nentes nnn snnt enne 45 4 7 2 Command functions esssssssssssessseeene enne enne nre rra 45 4 8 Application parameters eeeeeeeeeeeene enne ene enne nnnn nnne n nnn inne nnn innen innen 46 4 9 Application parameters modification cese ener 47 4 10 ue 48 June 2013 Page 3 of 55 4 10 1 ADCT Interr ptik etnia te vae era eg pec ea N vp e La eet aue A 49 430 2 PORTGnte rr pt e cereo Eege Y e puede ap hh ag oa tii 50 4 10 3 PDB Error interrupt ede ed eet e tee ene d oni n d n us 51 SECTION 5 APPLICATION SET UP AND OPERATION SECTION 6 RESULTS OF THE MEASUREMENT 6 1 CPU L
34. chine cycles The ADC1 interrupt is generated periodically with the same frequency as the PWM reload event when the values of the duty cycles are updated June 2013 Page 53 of 55 In this application the ADC ISR is generated once per 63 ps which corresponds to 16 kHz of the PWM frequency At 100 MHz on the Kinetis K60 device it consumes 42 4796 of CPU performance 6 2 Measured results using FreeMASTER 6 2 1 Motor startup The motor startup is presented in Figure 6 1 The required speed was changed from 0 to 2000 rpm The values are captured using the FreeMASTER scope quem Ss Estimated Speed Filt Required Speed Speed Ramp Position Merge Counter 20004 d 1500 e o o o o o Speed rpm o 1 00 0 75 0 50 Counter Frac o N a e o e 0 50 100 150 200 250 Index Figure 6 1 Motor startup from zero speed to 2000 rpm The Position Merge Counter variable identifies the time section where the generated open loop and the estimated positions are merged When the Merge Counter reaches 1 the application is running in the speed closed control loop The time gap between the step change of the Required Speed and the instance when the Speed Ramp becomes non zero represents the rotor alignment 6 2 2 Position merging The position merging process is shown in Figure 6 2 The chart was captured using the FreeMASTER recorder feature For reference an encoder positio
35. d on the section where the space vector of the stator current is generated This assignment is performed at the end of the ADC1 interrupt June 2013 Page 23 of 55 service routine Therefore it is enough to sample only two phase currents while the third is easily calculated according to Equation 4 2 Sector 1 6 in ig ic Sector 2 3 ig ia ic Equation 4 2 Sector 4 5 ig ip ia The following figure explains then in two cases case I at 60 case II at 30 why the calculation of the third current is necessary o 2 T i CO e gt mes A E mes B Phase C 0 60 120 180 240 300 360 angle Gb OD AD e A Oy Sector 1 Sector 2 Sector 3 Sector 4 Sector 5 Sector 6 gt PWM period PWM reload PhaseA j Bottom Phase B g i Transistors j i Phase C d Critical pulse width ADC sampling point Figure 4 2 Current sensing At 60 the user can sample all three currents because as mentioned above the currents are sampled when the bottom transistors are turned on The pulse width is sufficient to stabilize the current and to perform signal value acquisition by the AD converter At 30 the pulse is too short so the current of Phase A cannot be sampled June 2013 Page 24 of 55 4 3 5 SPI configuration The SPI interface is used in the application for communication between the intelligent MOSFET gate driver MC33937 and the K60 MCU The
36. d ripple A merging process assures smooth torque and speed ripple free transition from the open loop startup to full sensorless speed closed loop control The crossover merge function with weight coefficient ou is used to determine the position feedback signals During the merging process the ay coefficient is changing its value from O to 1 am OPEN LOOP CLOSED MERGING LOOP 0 Oy Du URamp Figure 3 4 Crossover function with weight coefficient aw The lower speed limit of crossover function uw is found through experimentation by evaluating the accuracy limits of the estimated values The upper speed limit wm2 is set in such a way that the merging process of the position will be performed during less than one electrical revolution The equation 3 1 shows the mathematical expression of the merging process for the position Oreck 1 ayu opru Loop Am X Yestim Equation 3 1 After the merging process is finished am 0 the equations above are no longer computed and estimated values of position and speed feedback are directly fed into the control process 3 2 Hardware The hardware solution of the PMSM Sensorless Vector Control on Kinetis is built on Freescale s Tower rapid prototyping system It consists of the following modules e Tower Elevator Modules TWR ELEV e Kinetis K60 Tower System Module TWR K60D100N June 2013 Page 15 of 55 e Low voltage 3 phase Motor Control Tower System Module TWR MC LV3PH
37. def struct June 2013 Page 36 of 55 GFLIB CONTROLLER PIAW P T sIdPiParams Id PI controller parameters GFLIB CONTROLLER PIAW P T sIqPiParams Iq PI controller parameters MCLIB 3 COOR SYST T SIABC Measured 3 phase current CLIB 2 COOR SYST ALPHA BETA T sIAlBe Alpha Beta current MCLIB 2 COOR SYST D Q T sIDQ DQ current CLIB 2 COOR SYST DO T sIDQReq DQ required current MCLIB 2 COOR SYST D Q T SIDQEr rfOr DQ current error MCLIB 3 COOR SYST T sDutyABC Applied duty cycles ABC CLIB 2 COOR SYST ALPHA BETA T sUAlBeReq Required Alpha Beta voltage MCLIB 2 COOR SYST ALPHA BETA T sUAlBeDCBComp Compensated to DC bus Alpha Beta voltage MCLIB 2 COOR SYST D OQ T sUDQReq Required DQ voltage GMCLIB_ELIM_DC_BUS_RIP_T SElimDCBRip DCB ripple elimination parameters structure MCLIB ANGLE T sAnglePosEl Electrical position sin cos CSTRUC_ALIGNMENT_ sAlignment Alignment structure params MCSTRUC_CASCADE_CNTR_T sCascadeControl Required DO voltage and current entered from MCAT Frac32 f32UAmplitudeMax Max available DC bus voltage Frac32 f32UDcBusFOC DC bus voltage scaled to phase voltage UWord16 uwl6SectorSVM SVM sector bool bOpenLoop Current control loop is open MCSTRUC FOC PMSM T This structure contains all the necessary variables
38. ector was added to the embedded software to enable the cooperation with Motor Control Application Tuning Tool By choosing different control topologies of the cascade structure the developer is able to tune the control parameters of the application in several steps In each step a few parameters have to be set or fine tuned Thus the developer can easily identify the physical quantity or application variable that causes the instability of the whole June 2013 Page 43 of 55 system The tool uses the FreeMASTER application as the platform for visualization of the measured quantities so the developer can directly observe the response of the tuned system when the application parameters are changed The control mode selector is defined as enumeration data type with the following definition typedef enum CONTROL_MODE_SCALAR CONTROL_MODE_VOLTAGE_FOC CONTROL MODE CURRENT FOC CONTROL MODE SPEED FOC MCSTRUC CONTROL MODE T GO BO po oN ON oS The procedures to set and fine tune the application parameters aredescribed in the application notes related to MCAT tool 4 6 7 Faults handling The application checks the following faults Phase over current Over DC bus voltage Under DC bus voltage MOSFET gate driver fault The faults are automatically cleared after the fault condition is removed Because the duration of some faults might by very short a three second time lag is added after the
39. ed displays the estimated speed output from the tracking observer Filtered estimated speed displays the filtered estimated speed Observer switch habilitates the use of the observer output Start up flag identifies if the system is in the open loop start up June 2013 Page 38 of 55 e Open loop flag identifies that the application is in open loop speed control This routine calculates the BEMF observer in the D Q frame and the tracking observer The necessary input parameters for the calculation are e the 3 phase current e required D Q voltages and e the speed from the previous step There are conditional switches and flags that manage the behavior of the function They determine whether the function is working at the open loop start up and or at the normal running The output of this routine is the electrical position the sine cosine angle of the estimated position and the estimated speed Prior to using this routine the observers and filters have structures which must be initialized This routine is called in the state machine prior to the FOC routine The function uses the algorithms from Freescale s Embedded Software Libraries FSLESL 4 6 4 8 Rotor alignment This application uses the rotor alignment before the motor is started which means the rotor is forced to a known position As in the previous algorithms the alignment has been optimized into one function which has one input output pointer to a structu
40. eed control loop June 2013 Page 41 of 55 The slow speed control loop is executed with a period of one millisecond and is performed in the Startup Spin and Freewheel sub states of the Run state It is calculated immediately after the fast current control loop and the exact instance of its execution is determined by the count down software timer gsM1 Drive uwl6CounterSlowLoop Which is updated after each pass of the fast current control loop The calculation comprises the ramp limitation of the required speed which determines the acceleration of the drive and the Pl speed controller whose output gives the required i current which enters the vector control algorithm and is directly proportional to output torque of the motor 4 6 5 Scalar control In order to evaluate the proper setting of the Back EMF observer and tracking observer parameters and the values and shapes of the sensed currents there is scalar control Volt per Hertz of the PMS motor incorporated into the control structure It is recommended to run the application in this mode only while the application is mastered by the MCAT tool because this tool automatically calculates the Voltage Frequency ratio based on the motor parameters The block diagram of the scalar control is shown on Figure 4 7 The structure listed below serves for the scalar control typedef struct GFLIB RAMP T sFrequencyRampParams Parameters of frequency ramp MCLIB 2 COOR SYST D O
41. es Its contents will be described in the following section Files in the root of the src folder main c main h contain basic application initialization enabling interrupts subroutines accessing the MCU peripherals and interrupt service routines In the background infinite loop the FreeMASTER communication is performed state machine c and state machine h contain the application state machine structure definition and handle switching between the application states and application states transitions June 2013 Page 51 of 55 motor structure c and motor structure h contain the structures definitions and subroutines dedicated to performing the motor control algorithm vector control algorithm position and speed estimation algorithm speed control loop M1 statemachine c and M1 statemachine h contain the software routines that are executed when the application is in the particular state or state transition freemaster cfg h is the configuration file for the FreeMASTER interface PMSMFOC appconfig h contains the definitions of constants in the application control processes parameters of the motor and regulators and the constants for other vector control related algorithms The content of the file is listed in chapter 4 8 Application parameters When the application is tailored for another motor using the Motor Control Application Tuning Tool this file is generated by the Tool at the end of the tuning process PMSM HWoconfig h conta
42. etof General Math and Motor Control Functions for Cortex M4 Core User Reference Manual Freescale Semiconductor 201 1 5 ACLCMAUG Advanced Control Library for Cortex M4 Core User Reference Manual Freescale Semiconductor 2012 6 AN3729 Using FlexTimer in ACIM PMSM Motor Control Applications Freescale Semiconductor 2008 June 2013 Page 7 of 55 7 MC33937 Three Phase Field Effect Transistor Pre driver Freescale Semiconductor 2009 8 ARM v7 M Architecture Reference Manual ARM Limited 2010 9 K60P144M100SF2V2 K60 Sub Family Data Sheet Freescale Semiconductor 2012 10 AN1948 Real Time Development of MC Applications using the PC Master Software Visualization Tool Freescale Semiconductor 2005 11 TWR MC LV3PH User s Manual Freescale Semiconductor 201 1 12 PMSM Vector Control with Encoder on Kinetis Demo Set up Guide Freescale Semiconductor 201 1 Acronyms and abbreviations Table 1 1 summarizes the acronyms used in the documents Table 1 1 Acronyms and abbreviated terms TERM MEANING AC Alternating current ADC Analog to digital converter Back EMF Back electromotive force a voltage generated by a spinning motor BDM Background debug mode BLDC motor Brushless DC motor DC Direct current DMA Direct Memory Access Controller an MCU module capable of performing complex data transfers with minimal intervention from a host processor
43. f struct MCLIB_ANGLE_T sAnglePosElEstim Electrical position sin cos GDFLIB FILTER IIRI T sBEMFfilterDQerror Estimated error filter GDFLIB FILTER MA T sSpeedEstFilter Estimated speed filter MCSTRUC EST STARTUP T sStartUp Start up structure Frac32 f32FilteredError Filtered output from Bemf obsrv Frac32 f32PositionEstim Fractional electrical position Frac32 f32SpeedEstimated Speed by BEMF and TO Frac32 f32SpeedEstimatedFilt Speed by BEMF and TO filtered bool bStartUp Start up mode bool bOpenLoop Speed control loop is open MCSTRUC POS SPEED EST DO T The first structure contains the necessary structures to calculate the BEMF observer in the D Q frame and the tracking observer The second structure holds the speed and position variables and structures Their descriptions follow Angle electrical rotor angle sine cosine 1 order IIR filter filters the output from the Back EMF observer error Estimated speed moving average filter serves to filter the estimated speed Start up structure contains the parameters to control the open loop start up it will be described in the chapter dedicated to the open loop start up Filtered error displays the output from the Back EMF observer Estimated position displays the estimated position output from the tracking observer Estimated spe
44. fault flag is removed and the application is switched from FAULT to STOP state This allows the user to see the actual fault flag The intelligent MOSFET gate drive MC33879 that is placed on the Tower MC power module latches different faults They are described in the datasheet 7 Faults are cleared via SPI communication protocol by software In some situations the automatic software clearing of the MOSFT pre driver faults does not perform well For example after hard over current faults when the over current protection of the power supply acts and decreases the supply voltage level under the value of the MOSFET gate driver reliable operation In such a case the application has to be reset by disconnecting the supply voltage 4 6 8 Main application motor control structure The structures described above together with some other application state variables and fault structures create the uppermost layer of data structure Its definition follows typedef struct CSTRUC_FAULT_THRESHOLDS_T sFaultThresholds threshold values of faults detected by software CSTRUC_ADC_CURRENT_CH_OFFSET_T sADCOffset Offset values for AD currents sensing CSTRUC_FOC_PMSM_T SFocPMSM CSTRUCT SCALAR CTRL PMSM T sScalarPMSM CSTRUC_POS_SPEED_EST_DQ_T sPositionEstDQ CSTRUC_BEMF_OBS_DO_T sObserverDOQ June 2013 Page 44 of 55 CSTRUC SPEED T sSpeed CSTRUC CONTROL MODE
45. g the suitability of its products for any particular purpose nor does Freescale assume any liability arising out of the application or use of any product or circuit and specifically disclaims any and all liability including without limitation consequential or incidental damages Typical parameters that may be provided in Freescale data sheets and or specifications can and do vary in different applications and actual performance may vary over time All operating parameters including typicals must be validated for each customer application by customer s technical experts Freescale does not convey any license under its patent rights nor the rights of others Freescale sells products pursuant to standard terms and conditions of sale which can be found at the following address freescale com SalesTermsandConditions Freescale and the Freescale logo are trademarks of Freescale Semiconductor Inc Reg U S Pat amp Tm Off All other product or service names are the property of their respective owners O Freescale Semiconductor Inc 2013 All rights reserved e Sa 9 9 freescale
46. h every update after the duty cycle value is computed in the vector control algorithm As mentioned in section 4 3 4 in the application hardware triggering of the A D converter is employed The Initialization Trigger signal from the FlexTimer is used as the primary triggering signal which is fed into the Programmable Delay Block that services the timing of the AD conversion initiation FTMO EXTTRIG FTM EXTTRIG INITTRIGEN MASK Finally the output pins of the MCU have to be configured in order to send the signals out of the chip The assignment of signals to output pins is set in the Pin Control Register while the available signals are listed in the Signal Multiplexing chapter of 1 and are package dependent PORTC_PCR1 PORT PCR MUX 4 FTMO CHO PORTC PCR2 PORT PCR MUX 4 FTMO CH1 PORTC PCR3 PORT PCR MUX 4 FTMO CH2 3 3 PORTA PCR6 PORT PCR MUX FTMO CH3 PORTA PCR7 PORT PCR MUX FTMO CH4 June 2013 Page 21 of 55 PORTD PCR5 PORT PCR MUX 4 FTMO CH5 The port settings implemented in the application code reflect the hardware solution built on the Tower system modules 4 3 2 ADC and PDB modules configuration The on chip ADC module is used to sample feedback signals motor phase currents and DC bus voltage that are necessary to successfully perform the vector control algorithm The Programmable Delay Block closely cooperates with the AD
47. he whole drive June 2013 Page 10 of 55 Maximum torque is Rotor generated when the quadrature axis stator field is developed in line with q axis Rotor direct axis Rotor with permanent magnets Stator P winding Figure 3 1 Synchronous machine and the main principle of the vector control As already mentioned the required torque is proportional to the q portion of the orthogonal d q currents system The d portion reflects the generation of the rotor magnetic flux Because there are permanent magnets mounted on the PMSM rotor this current is usually kept at a zero level unless the field weakening is performed in order to accelerate the motor above the nominal speed or while performing the MTPA algorithm In such cases the required d current possesses a negative value Therefore the control process regulation is focused on maintaining the desired values of the d and q currents Since the d q system is referenced to the rotor the measured stator currents have to be transformed from the 3 phase a b c stationary frame into the 2 phase d q rotary frame before they enter the regulator block At first the Clarke transformation is calculated which transforms the quantities from the 3 phase to 2 phase systems Because the space vector is defined in the plane 2D it is sufficient to describe it in the 2 axis alpha beta coordinate system Consequently the result of the transformation into the 2 phase synchronous frame Park t
48. his ISR the speed is calculated as a position derivation and the speed controller slow speed control loop is calculated The individual processes of the control routines are described in the following sections 4 3 Kinetis K60 peripheral modules configuration In this section the configuration procedures of the peripherals used are described or referenced On all devices of the Kinetis family it is necessary to enable the system clock for the module before any access to the peripheral registers is performed The modules are enabled by writing 1 to the particular bit in the System Clock Gate Control Register Any write or read attempt to the peripheral register before enabling the clock for the particular peripheral module will yield a hard fault Refer to 1 for a detailed description of each peripheral module Table 4 1 shows an overview of the Kinetis K60 peripheral modules used by the application The number of modules and module channels reflect a 144 pin package Table 4 1 Kinetis K60 peripherals overview June 2013 Page 19 of 55 Kinetis K60 peripherals Group Module Number of modules penes nie Purpose application or channels Analog ADCO 23 channels single 3 channels DC bus voltage and ended 3 motor phase currents differential pairs sensing ADC1 21 channels single 2 channels ended 3 differential pairs Comparators 3 DAC 2
49. hronous Motor 10 3 1 2 Introduction to Vector Control 10 3 1 3 Sensorless Vector Control Implementation nn nara nnnn cnn nc 12 3 1 3 1 Open Loop Start up and Merging sse 14 3 2 HardWare pee d 15 3 2 1 Hardware Set up and Configuration sees 16 SECTION 4 SOFTWARE DESIQN eere 19 4 1 Fractional Numbers Representation eese eene 19 4 2 Application Overview seeeeeeeeeeeees seen nennen rr 19 4 3 Kinetis K60 Peripheral Modules Configuration eese 19 4 3 1 FlexTimerO Configuration for Generating a 6 channel DM 20 4 3 2 ADC and PDB Modules Configuration esses 22 4 3 3 ADC Conversion Timing Currents and Voltage Sampling sssssss 22 4 3 4 Current Measurement esee entente nennen nnns esten enn sinn snnt senes 23 4 3 5 SPI Configuration TTT 25 4 3 6 SGI UART Gonfiguration cuore Gali hei Ad aie aie 25 4 4 Enabling the Interrupts on the Core Lewvel eese 25 4 5 FreeMASTER Software aerae a aer arar aa ae a ata cr 27 4 5 1 dude Hengen NEE 27 4 5 2 FreeMASTER Communication Driver 27 4 5 3 FreeMASTER Recorder and Gcope sse 27 4 6 AAA cete eee Urs tete es ee e 28 4 6 1 Application SLtlcture ete E 28 4 6 2 Application Background Loopre sereset i a nono nc cnn e S E E 28 4 6 3 Application St
50. id static void M1 TransStopFault void static void M1 TransStopInit void static void M1 TransStopRun void static void M1 TransRunFault void static void M1 TransRunStop void The main states functions table initialization State machine functions field static const SM APP STATE FCN T msSTATE M1 StateFault M1 StateInit M1 StateStop M1_StateRun The main state transient functions table initialization State transition functions field June 2013 Page 34 of 55 static const SM APP TRANS FCN T msTRANS M1 TransFaultInit Ml_TransInitFault MI TransInitStop M1 TransStopFault M1 TransStopInit M1 TransStopRun M1 TransRunFault M1 TransRunStop Finally the main state machine structure initialization State machine structure declaration and initialization SM APP CTRL T gsM1 Ctrl gsM1_Ctrl psState User state functions amp msSTATE gsM1 Ctrl psTrans User state transition functions amp msTRANS gsM1 Ctrl uiCtrl Deafult no control command SM CTRL NONE gsM1 Ctrl eState Default state after reset INIT Hi Similarly the Run sub state machine is declared The Run sub state identification variable has the following definitions typedef enum CALIB READY ALIGN STARTUP SPIN FREEWHEEL M1_RUN_SUBSTAT ll ll OBWNFO Sos sos Gl T Run sub states For the Run sub states the following set
51. ient poles on the stator This difference from the PM synchronous motor has distributed winding on the stator forming the sinusoidal shape of the magnetic field The construction of a rotor is the same for both types of motors salient poles on the shaft Even though the vector control algorithm was originally developed for PM synchronous motor assuming sinusoidal shape of the magnetic field it is possible to employ the same control strategy for the BLDC motor The performance will not be optimal but the drive will possess less audible noise compared to a traditional six step commutation control The main benefit is that the customer can learn and adopt sensorless vector control on a cost effective hardware solution The motor has the following specification Table 3 3 Specification of the motor Manufacturer name Linix Type 45ZWN24 40 Motor specification Nominal voltage line to line 24 V DC Nominal speed 4000 rpm Rated power 40W Stator winding resistance 1 Ohm line to line Stator winding inductance Motor model parameters d axis EEN Stator winding inductance 775 8 uH q axis Number of pole pairs 2 NOTE June 2013 Page 18 of 55 The application parameters speed Pl controller and value of the startup current are set for the motor that has a plastic circle part of the kit mounted on the shaft otherwise speed oscillation might occur Section 4 Software design The applicat
52. ilable DC bus voltage DC bus voltage measured dc bus voltage SVM sector sector information output from the SVM algorithm This routine calculates the field oriented control At its input are the 3 phase current the dc bus voltage the electrical position the required D and Q currents and the logical switch open loop June 2013 Page 37 of 55 control The output of this routine is the 3 phase duty cycle SVM sector The Pl controllers have structures which must be initialized prior to this routine use The function uses the algorithms from Freescale s Embedded Software Libraries FSLESL 4 6 4 2 Position and speed estimation This application uses the BEMF observer in the D Q reference frame Similar to the FOC algorithm the position and speed estimation has been optimized into one function which has One input output pointer to a structure The prototype of the function is as follows void MCSTRUC PMSMPositionObsDQ MCSTRUC FOC PMSM T psFocPMSM MCSTRUC BEMF OBS DO T psObserverDQ MCSTRUC POS SPEED EST T psPositionEstDQ The function uses the FOC structure described in the previous chapter There are two additional structures referred to by the input output structure pointers Their definitions are as follows typedef struct ACLIB BEMF OBSRV DQ T sBemfObsrvDQ BEMF observer in DQ ACLIB TRACK OBSRV T sTor Tracking observer MCSTRUC BEMF OBS DO T typede
53. in the interrupt service routine that interrupts the background loop June 2013 Page 28 of 55 4 6 3 Application state machine A simple application state machine handles the switching between the application states and application state transitions This is executed at the beginning of the ADC1 interrupt service routine The following figure gives an overview of the program flow through the application states and transitions RESET SM CTRL INIT DONE Transition Init Stop Transition Fault Init SM CTRL FAULT CLEAR SM CTRL FAULT Transition Init gt Fault Transition Stop Fault SM CTRL START Transition Stop Run SM CTRL RUN ACK SM CTRL FAULT SM CTRL STOP ACK Transition Run gt Stop SM_CTRL_STOP Transition Run gt Fault SM_CTRL_FAULT Figure 4 4 Application state machine diagram The application states represent a steady state Usually that means the application is waiting for some trigger or condition to be met to change the state The particular function is called each time the program makes one pass of the infinite background loop The application state transitions contain instructions that are executed only once when the application state is changed Typically the settings in the peripheral registers are performed only once and it is not necessary to repeat them 4 6 3 1 States definition The state machine structure consists of four main s
54. ins definitions of the application constants that are not generated by the MCAT tool Files and subdirectories in the src mcu_Init folder common and pu folders contain CPU initialization routines cpu vectors h is an important file that contains the definition of the peripherals interrupt service routines assigned to the interrupt vectors In this file the user can add the definition of an ISR for an additional peripheral interrupt drivers subdirectories contain generic source and header files for UART and watchdog configuration as well as the CPU clock settings routines W eripherals contains important files for static configuration of the peripherals used in the application FlexTimers ADC PDB SPI PIT platforms tower h contains the Kinetis Tower card definitions CPU speed and UART parameters Files in the srcMwrk60d100 folder MK60N512VMD100 h is the header file containing macro definitions of all the MCU registers and registers bits Files in the srcWMC Lib folder Cortex M4 a is a software library containing motor control general math and filter algorithms Other files in the folder and subfolders are associated header files each one for a particular function of the library June 2013 Page 52 of 55 Cortex M4 ACLIB a contains the advanced control algorithms for rotor position and speed estimation Back EMF observer and Tracking observer Other subdirectories in the src folder s src FreeMASTER contai
55. ion software was designed using the compiler AR Embedded Workbench for ARM v 6 40 2 4 1 Fractional numbers representation As mentioned in a previous paragraph in the development of the vector control algorithm software libraries were used a Set of the General Maths and Motor Control Functions for the Cortex M4 Core Most of the mathematical calculations were performed with the numbers represented in Q1 15 or Q1 31 signed fractional format so all physical quantities were scaled to the lt 1 1 interval For more on the fractional format and variables scaling see DRM105 3 4 2 Application overview The application is real time interrupt driven with the background infinite loop handling the application states Initialization Run Fault and FreeMASTER communication polling There are two periodic interrupt service routines where the control process is executed Their timing is given by the requirements of the vector control algorithm The control process is composed of two control loops The execution of the fast current control loop is performed in the ADC1 interrupt service routine which is executed after the values of the sampled DC bus voltage and motor phase currents are put into the ADC result registers The sampling instance is precisely defined by the hardware trigger of FlexTimerO that is configured to generate six PWM signals of frequency 16 kHz The PITO interrupt service routine is triggered every one millisecond In t
56. l gain define D KP SHIFT 7 1 controller proportional gain shift define D KI GAIN FRAC32 0 808548360551 controller integral gain define D_KI_SHIFT 5 controller integral gain shift Q current PI controller define Q_KP_GAIN FRAC32 0 70593591855 controller proportional gain define Q KP SHIFT 1 controller proportional gain shift define Q KI GAIN FRAC32 0 854100380864 controller integral gain define Q KI SHIFT 5 controller integral gain shift Speed PI controller define SPEED_KP_GAIN FRAC32 0 1 controller proportional gain define SPEED_KP_SHIFT 2 controller proportional gain shift define SPEED_KI_GAIN FRAC32 0 1 controller integral gain define SPEED_KI_SHIFT 7 controller integral gain shift define SPEED_LOOP_HIGH_LIMIT FRAC32 0 275 max required iq output from the speed controller define SPEED_LOOP_LOW_LIMIT FRAC32 0 275 Speed ramp define SPEED_RAMP_UP FRAC32 0 000227272727 define SPEED_RAMP_DOWN FRAC32 0 000227272727 define SPEED_LOOP_CNTR 16 speed control loop divisor define SPEED_FILTER_MA 4 size of speed filter buffer 2 4 BEMF observer define BEMF DO KP GAIN FRAC16 0 673854776343 define BEMF DQ KP SHIFT 7 1 define BEMF DQ KI GAIN FRAC16 0 840890294973 define BEMF DQ KI SHIFT 5 define I_SCALE FRAC16 0 93216630197 define U_SCALE FRA
57. lso be enabled on the core level otherwise the interrupt request will not be generated The process is not straightforward and the necessary information is spread over several documents In order to help the user to enable any interrupt while enhancing the application to other features the process of setting up the PIT interrupt is described in this section as an example The interrupt request on the module level is enabled by writing 1 to the TIE bit of the Timer Control Register PIT TCTRLO PIT TCTRL TIE MASKE Now it is necessary to find out the number of the interrupt and the IRQ vector Both values can be found in the K60 Sub Family Reference Manual 1 in the section 3 2 2 3 Interrupt channel assignments For the PIT channel 1 interrupt the interrupt vector is 84 and the interrupt number is 68 This is always 16 less than the vector number because the first 16 interrupt vectors are ARM core system handler exception vectors The next step is to redefine the vector pointer in the vectors h file from the default ISR to the function that contains the code to be executed after an interrupt is generated Replace define VECTOR 084 default isr with define VECTOR 084 PIT CHO ISR Handler and add at the end of the file June 2013 Page 25 of 55 extern void PIT CHO ISR Handler void because the ISR is defined in the other file e g in main c Next set up the ARM core NVIC register Each interrup
58. me is set up e Freewheel gt Ready zero speed command entering the Ready state The PWM output is enabled e Freewheel gt Align non zero speed command entering the Align state The PWM output is enabled Certain variables are initialized voltage speed position The alignment time is set up June 2013 Page 33 of 55 Stop Run Calibration time passed Transition Calib Ready Transition Freewheel Ready Speed command 0 Speed command Speed command 0 Transition Align Ready Speed command 0 Transition Ready Align Transition Spin Freewheel Speed command amp Speed min speed Transition Startup Freewheel Startup fail Transition Freewheel Align Alignment time passed Transition Align Startup Startup ok Transition Startup Spin Figure 4 5 Motor Run sub state diagram The implementation of this structure of motor state machine is made in the M1 statemachine c h The main motor state machine structure is as follows The main states user function prototypes static void M1 StateFault void static void M1 StateInit void static void M1 StateStop void static void M1 StateRun void The main states user transient function prototypes static void M1 TransFaultInit void static void M1 TransInitFault void static void M1 TransInitStop vo
59. n is also depicted June 2013 Page 54 of 55 E Open Loop Position a Merged Position Reme ae Estimated Position Pest Encoder Position Frac o e eo o De a Position o a o Start of the End of the merging Difference is merging process process decreasing Figure 6 2 Position Merging Process The start of the position merging process is when the motor speed reaches 1096 of the nominal speed During the merging process the merged position blue is approaching the estimated position red At the end of the merging process the application enters the Spin sub state of the Run state and the open loop and merged positions are no longer calculated As the speed of the motor increases the difference between the encoder position which is used here as the reference and provides the real physical rotor position and the estimated position decreases June 2013 Page 55 of 55 How to Reach Us Information contained in this document is provided solely to enable system and software implementers to use Freescale products There are no express or implied copyright licenses Home Page granted hereunder to design or fabricate any integrated http www freescale com circuits based on the information in this document Freescale reserves the right to make changes without further notice to Web Support any products herein www freescale com support Freescale makes no warranty representation or guarantee regardin
60. ned on SM CTRL RUN ACK this flag acknowledges that the system can proceed from the Stop state to the Run state SM CTRL STOP this flag informs the system that there is a command to go from the Run state to the Stop state The transition function is called but the action must be acknowledged because it may take time to properly turn off the system SM CTRL STOP ACK this flag acknowledges that the system can proceed from the Run state to the Stop state This structure is implemented in the state machine c h files The state machine structure is as follows State machine control structure typedef struct SM APP CTRL T SM APP STATE FCN T const psState State functions SM APP TRANS FCN T const psTrans Transition functions SM APP CTRL uittrl Control flags SM APP STATE T eState State There are four components June 2013 Page 30 of 55 psState pointer to the user state machine functions The particular state machine function from this table is called when the state machine is in that state psTrans pointer to the user transient functions The particular transient function is called when the system goes from one state to another uiCtrl this variable is used to control the state machine behavior using the above mentioned flags eState this variable determines the actual state of the state machine The user state machine functions are defined in the
61. ns all source files of the FreeMASTER application It is not necessary to access it or change anything inside The interface to the programmer is only via freemaster cfg h file src MC_Lib Common contains specific header files associated with the software libraries Wrc app init contains the routines for MOSFET gate driver initialization GPIO ports and FreeMASTER initialization 4 10 5 Memory usage The following table summarizes the chip memory usage Table 4 2 Memory Usage Values in Bytes Memory Total Available on the Kinetis Used by the MK60N512VMD 1 00 Application Program Flash application code 512 KB 23 854 B Data Flash application constants 2046 B Data RAM application variables 128 KB 2845 B Section 5 Application set up and operation The application can be operated via the user s buttons on the K60 tower module or via the FreeMASTER interface The set up procedure of the FreeMASTER software on the PC as well as the application operation is described in the User s Manual 12 Section 6 Results of the measurement 6 1 CPU load and the execution time The CPU load is influenced mainly by the execution of the ADC1 ISR in which the execution of the application state machine and calculation of the fast current control loop of the PMSM vector control is performed The complete ADC1 ISR requires 2656 state machine and fast control loop to 2962 with the slow control loop calculation ma
62. oad and the Execution Time eeseseesseeseeeeeeeeee ener nnns 53 6 2 Measured Results Using FreeMASTER cssscssecesseeeeeseeesseesesneeeneeeeseeeseseaeenseeeeeneenss 54 6 2 1 eres 54 6 2 2 POSITION MERGING RE 54 June 2013 Page 4 of 55 List of Figures and Tables Figure Title Page FIGURE 3 1 SYNCHRONOUS MACHINE AND THE MAIN PRINCIPLE OF THE VECTOR CONTROL eene 11 FIGURE 3 2 TRANSFORMATION SEQUENCING ene nennen ener AAAA ne AAAA assess se sesesesesese sese se sese se sese se assess sedes s sedia 12 FIGURE 3 3 BLOCK DIAGRAM OF SENSORLESS PMSM VECTOR CONTROL en nnt rtr eis sess sane sala lna 14 FIGURE 3 4 HARDWARE BUILT ON THE MODULES OF THE TOWER SYSTEM sess nnne sinn ens 16 FIGURE 3 5 JUMPERS AND CONNECTORS POSITIONS ON THE TWR MC LV3PH eene nnns 17 FIGURE 4 1 ADC CONVERSION TIMING esee a a a a nsns sinensis sans nn cnn da sedis s sss nan cane ss anar nn sss caninas 23 FIGURE4 2 CURRENT SENSING dere eege Eed ege 24 E GUHE Deeg Reg 28 FIGURE 4 4 APPLICATION STATE MACHINE DIAGRAM ne nenhnnnnn asuttu ttnn anenun nnne siis sss sss conocen ss dada saa sa ssa sna 29 FIGURE 4 5 MOTOR RUN SUB STATE DIAGRAM eene Rnmnnn nn nn entr nhhiss sess ne e isis sss dass set nan nn anna sss ns sis sss sd ss a s den aa 34 FIGURE 4 6 START UP PROGESS E EE 41 FIGURE 4 7 BLOCK DIAGRAM OF THE SCALAR CONTROL nennt naeun uA EEEE EAn AAEE nnna conocen ana c anna nn ninia 43 FIGURE 4
63. of user functions is defined static void M1 _StateRunCalib void static void M1_StateRunReady void static void M1_StateRunAlign void static void M1 StateRunStartup void static void M1 StateRunSpin void static void M1 StateRunFreewheel void static void M1 StateRunCalibSlow void static void M1 StateRunReadySlow void static void M1 StateRunAlignSlow void static void M1 StateRunStartupSlow void static void M1 StateRunSpinSlow void static void M1 StateRunFreewheelSlow void The Run sub states user transient function prototypes static void M1 TransRunCalibReady void static void M1 TransRunReadyAlign void static void M1 TransRunAlignStartup void static void M1 TransRunAlignReady void static void M1 TransRunStartupSpin void static void M1 TransRunStartupFreewheel void static void M1 TransRunSpinFreewheel void June 2013 Page 35 of 55 static void M1 TransRunFreewheelAlign void static void M1 TransRunFreewheelReady void The Run sub states functions table initialization Sub state machine functions field in pmem static const PFCN VOID VOID mM1 STATE RUN TABLE 6 M1 StateRunCalib M1 StateRunReady M1 StateRunAlign M1 StateRunStartup M1 StateRunSpin M1 StateRunFreewheel The state machine is called from the interrupt service routine as mentioned in a previous chapter The method to call the state machine is StateMachine call SM StateM
64. parameters of the controlled motor and are provided in this design for motor LINIX 45ZWN24 40 which is part of the TWR MC LV3PH kit Most of these definitions are generated by the Motor Control Tuning Tool and are placed in the generated file PMSMFOC_APPconfig h NOTE The application parameters speed PI controller and value of the start up current are set for the motor which has a plastic circle part of the kit mounted on the shaft otherwise speed oscillation might occur NOTE Because the motor inertia J and torque constant kt are not known for a given motor the speed PI controller has been tuned experimentally Motor Control Application Tuning tool was used only for current PI controllers and sensorless algorithms tuning The constants of the speed PI controller are defined in the PMSM_HWconfig h file 4 9 Application parameters modification When using a different motor the application constants have to be changed The designer can use the Motor Control Application Tuning Tool that is part of the source code provided with this June 2013 Page 47 of 55 Reference design The Tool is based on the FreeMASTER application and allows calculation of the application constants based on the motor parameters Calculated values are updated directly to the running application so there is no need to build the whole application when the developer wants to observe the response of the drive on a change of the application parameter
65. pen loop mode The start up method assumes June 2013 Page 39 of 55 similar conditions for each start up The method consists of a generated rotating field with the Q current profile that will spin the rotor according to the generated speed Similarly to the previous algorithms the open loop start up has been optimized into one function which has one input output pointer to a structure The prototype of the function is the following void MCSTRUC PMSMOpenLoopStartUp MCSTRUC FOC PMSM T psFocPMSM MCSTRUC POS SPEED EST T psPosition MCSTRUC SPEED T psSpeed The function uses the FOC and position speed estimation structures which are described in the previous chapter There is an additional structure referred to by the input output structure pointers Its definition follows typedef struct GFLIB CONTROLLER PI P PARAMS T sSpeedPiParams Speed PI controller parameters GFLIB RAMP T sSpeedRampParams Speed ramp parameters Frac32 32Speed Speed Frac32 F32SpeedError Speed error Frac32 F32SpeedRamp Required speed ramp output Frac32 F32SpeedReg Required speed ramp input Frac32 32RampUpMCAT ramp increment entered from motor control application tuning tool Frac32 f32RampDownMCAT ramp decrement entered from motor control application tuning tool MCSTRUC_SPEED_T The structure contains the necessary variables to perform
66. ransformation is two DC values the d q currents It is much easier to regulate two DC variables than two variables changing in time The following picture shows the transformation sequencing June 2013 Page 11 of 55 Phase A Phase B 3 Phase Stationary Rotating to to to Phase C 2 Phase Rotating Stationary 3 Phase l l From measurement AC l Stationary Reference Frame l Rotating Reference Frame l Stationary Reference Frame l Figure 3 2 Transformation sequencing 3 1 3 Sensorless vector control implementation Figure 3 3 shows a block diagram of the vector control algorithm with sensorless position estimation The aim of this control is to regulate the motor speed at a predefined level The speed command value is set by a high level control The algorithm is executed in two control loops The fast inner control loop is executed within a hundred usec period The slow outer control loop is executed within a period of an msec The fast control loop executes two independent current control loops They are the direct and quadrature axis current Ga sel PI controllers The direct axis current is used to control the rotor magnetizing flux The quadrature axis current corresponds to the motor torque The current P controllers outputs are summed with the corresponding d and q axis components of the decoupling stator voltage Thus the desired space vector for the stator voltage is obtained and then applied to the motor
67. rate triggers to start sampling the DC bus voltage and the motor phase AD conversions The PDB module on the K60 MCU allows 15 different input trigger sources They are listed in the chapter Chip configuration in the section PDB Configuration in device reference manual 1 Similarly as for the FTMO the LDOK bit has to be set in order to acknowledge the changes in the modulo and the delay registers 4 3 3 ADC conversion timing currents and voltage sampling The FlexTimerO is configured to trigger an internal hardware signal when its counter is reset after overflow to the initialization value This signal is fed into the Programmable Delay Block PDB that consequently triggers the AD conversion of the voltage and currents with a predefined delay On the Kinetis K60 100 MHz MCU two ADC modules are implemented Each ADC module associates to one channel of the PDB module Each ADC module has two result registers two channels and they correspond to two programmable pre trigger delays of the PDB channels It is possible to perform four AD conversions without requesting an interrupt provided that the DMA is not used for data transfer In this application only 3 conversions need to be triggered without CPU intervention two motor phase currents and the DC Bus voltage The following time diagram shows the modules interconnection and the ADC interrupt generation June 2013 Page 22 of 55 FTMO VAL1 feck y6 5 y6
68. re The prototype of the function is the following void MCSTRUC AlignmentPMSM MCSTRUC FOC PMSM T psFocPMSM The function uses the FOC structure which is described in the previous chapter In this structure there is a sub structure that is dedicated to the alignment Its definition follows typedef struct Frac32 f32IMax Max D current at alignment UWord32 uw32TimeAlignment Alignment time duration MCSTRUC_ALIGNMENT_T The structure contains the necessary variable to perform the simple rotor alignment The structure description follows e Maximum current limit of the required D current at the alignment e Duration defines the duration of the alignment in the number of tick of the fast loop The routine rotates the rotor with the defined level of d axis current a fraction of the nominal motor current The q axis current is kept at zero and the rotor moves to the position where the stator and rotor poles are aligned in one axis The speed control loop is not calculated At the end of the routine the application continues to the start up When the application is in the scalar or in voltage FOC control mode voltage alignment is applied by defining the d axis voltage The value of this voltage equals the value of the boost voltage used for scalar control 4 6 4 4 Motor open loop start up Because the BEMF observer does not give reliable feedback at very low speeds the motor needs to be started at certain speed in the o
69. rrupt flag is cleared Because there are only two user s buttons control is limited In the application the assigned functions are RUN and STOP and they control rotation only in one direction Pressing the RUN button causes the speed to increase in 1096 increments Pressing the STOP button causes the speed to decrease in 1096 increments June 2013 Page 50 of 55 For more information about the application control via the users buttons see the chapter Application control Using the FreeMASTER control interface allows for enhanced control and diagnostic 4 10 3 PDB error interrupt The PDB error ISR serves to clear the sequence error fault generated when PDB initiates the sampling of the AD converter but the COCO flag in the particular ADCx SC1n register of the ADC module was not cleared because the values from result registers were not read In these cases the PDB counter stops working and an interrupt is asserted The PDB module is then reinitiated in the ISR The PDB generates trigger signals with the same period as the ADC conversion complete interrupt which is also the same as the PWM period If the user places an interrupt in the code this will stop the execution The PDB will generate triggers for the next conversion even when the program execution stops The COCO flags are not cleared and the PDB generates a sequence error Another reason for the unread register is that the execution of the ADC conversion complete interrupt where the
70. s The essential feedback signals are 3 phase stator current and stator voltage For correct operation the presented control structure estimates the rotor shaft position from the phase currents and voltages employing advanced position estimation algorithms Back EMF observer and the Tracking observer The back EMF observer is based on the mathematical model of the synchronous motor with an extended electro motive force function which is realized in the estimated quasi synchronous reference frame The back EMF observer detects the generated motor voltages induced by the permanent magnets A tracking observer uses the back EMF signals to calculate the position and speed of the rotor Since the back EMF force is depending on the value of the angular speed of the motor at the low speed drive operation the output of the algorithm does not provide accurate position information Therefore in this application the motor runs in the open loop mode with forced rotor position values until the motor reaches 10 of its nominal speed The merging algorithm then allows smooth transition from open loop mode to speed closed loop control without any torque ripples During the open loop start up the motor operates with limited output torque When the drive application requires full torque at the motor start up you must use an additional method for position estimation that can detect the rotor position at stand still and low speed operation The description of the
71. scription of the libraries functions can be found in 4 3 1 8 1 Open loop start up and merging As mentioned the output of the back EMF observer does not provide reliable values at low speed motor operation It is obvious from one of the motor operation fundamentals at the zero speed there is no back EMF generated For this reason the motor spins in the open loop mode The output of the speed regulator is disconnected and required startup current ig req startup IS kept on constant level The value of the startup current has to be carefully tuned It has to be high June 2013 Page 14 of 55 enough in order to put the rotor into the motion but not too high when there could be observed speed oscillations during the transition to speed closed loop operation After a non zero value of required speed is entered the speed ramp block provides prescribed acceleration dynamic of the motor by smoothly increasing its output value The required speed value then enters the integrator block which gives the generated open loop position of the rotor This is essential to the performance of the vector control algorithm This strategy moves the motor up to the speed threshold when the output of the back EMF observer algorithm is giving confident results of the rotor position and the speed Because the open loop values of speed and position are not equal to estimated ones direct switching the feedback from open loop to estimated values causes torque and spee
72. t vector must be independently enabled or disabled by setting the corresponding bit in the complementary pair of registers the Interrupt Set Enable Register NVIC ISERx or the Interrupt Clear Enable Register NVIC ICERx NVIC_ISERO contains the enable bits for IRQ numbers 0 through 31 NVIC_ISER1 contains the enable bits for IRQ 32 through 63 and so on To enable the PIT channel 0 interrupt interrupt number 68 it is necessary to write 0x00000010 b10000 to the NVIC ISER2 register It is an advisable approach to clear any pending interrupt before it is enabled This is usually not necessary right after the reset when the MCU initialization is performed but during the program execution when certain a interrupt is disabled and later re enabled Sometimes if an interrupt flag has been set before the interrupt was enabled the interrupt controller might generate an unhandled exception fault if the interrupt flag has not been cleared before NVICICPR2 0x00000010 clear pending interrupts first NVICISER2 0x00000010 enable the PIT CHO interrupt NOTE The ARM document 8 indicates that the registers have an underscore between NVIC and ISER NVIC ISER1 However in the current header files used in the application the NVIC register names do not have the underscore NVICISER1 or NVICICPR1 NVIC interrupts are prioritized by updating an 8 bit field within the 32 bit NVIC_IPRx registers Macros contained in the Kine
73. tates e Fault system faced a fault condition e Init variables initialization June 2013 Page 29 of 55 Stop system is initialized and waiting for the Run command Run system is running can be stopped by the Stop command There are transition functions between these state functions Init gt Stop initialization has been done the system is entering the Stop state Stop Run the Run command has been applied the system is entering the Run state if the Run command has been acknowledged Run Stop the Stop command has been applied the system is entering the Stop state if the Stop command has been acknowledged Fault gt Init fault flag has been cleared the system is entering the Init state Init Stop Run Fault a fault condition has occurred the system is entering the Fault state The state machine structure uses the following flags to switch between the states SM CTRL INIT DONE when this flag is set the system goes from the Init to the Stop state SM CTRL FAULT when this flag is set the system goes from any state to the Fault state SM CTRL FAULT CLEAR when this flag is set the system goes from the Fault state to the Init state SM CTRL START this flag informs the system that there is a command to go from the Stop state to the Run state The transition function is called but the action must be acknowledged due to the amount of time it may take before the system is ready to be tur
74. the FlexTimer module in the Clock Gating Control Register SIM SCGC6 SIM SCGC6 FTMO MASK It is necessary to disable the write protection of some registers before they can be updated FTMO MODE FTM MODE WPDIS MASK It is advisable to enable the internal FlexTimer counter to run in debug mode FTMO CONF FTM CONF BDMMODE 3 While the HW debugging interface jLink Multilink is connected to the microcontroller the MCU is in debug mode This does not depend on whether the running code containing breakpoints or not The PWM signals generated by the FlexTimerO are directly connected to the MOSFET driver Due to safety reasons the input signals for the top transistors on the MOSFET driver used on the Tower low voltage power stage have inversed polarity Therefore it is also necessary to set the right polarity of the PWM signals FTMO POL FTM POL POLO MASK FTM POL POL2 MASK FTM POL POLA4 MASK The duty cycle is changed by changing the value of the FlexTimer Value registers These registers are double buffered meaning that their values are updated not only by writing the number but it is necessary to confirm the change by setting the Load Enable LDOK bit This ensures that all values are updated at the same instance FTMO PWMLOAD FTM PWMLOAD LDOK MASK It is necessary to write the LDOK bit every time the value registers are changed not only at the initial stage of loading them with values but wit
75. tialized in the code where the state machine is called State machine function extern inline void SM StateMachine 5M APP CTRL T sAppCtrl gSM STATE TABLE sAppCtrl gt eState sAppCtrl 4 6 3 2 Motor state machine The motor state machine is based on the main state machine structure The Run state sub states have been added on top of the main structure to control the motor properly These are the descriptions of the main states user functions e Fault system faced a fault condition and waits until the fault flags are cleared The dc bus voltage is measured e Init variables initialization e Stop system is initialized and waiting for the Run command The PWM output is disabled The dc bus voltage is measured e Run system is running and can be stopped by the Stop command The Run sub state functions are called from here There are transition functions between these state functions e Init gt Stop blue LED is lit on the K60 tower board e Stop gt Run duty cycle is initialized to 50 the PWM output is enabled The current ADC channels are initialized The Calib sub state is set as the initial Run sub state e Run gt Stop the Stop command has been applied the system is entering the Stop state if the Stop command has been acknowledged The system does not go directly to Stop if the system is in certain Run sub states e Fault gt Init nothing is processed in this function
76. tion is orthogonal to the direction of the magnetic flux generated by the stator permanent magnets or excitation coils The PMSM has the inverse construction the excitation is on the rotor and the motor has no commutator Due to the decomposition of the stator current into a magnetic field generating part and a torque generating part it is possible to control these two components independently and to reach the required performance In order to keep the constant desired torque the magnetic field generated by the stator coils has to follow the rotor at the same synchronous speed Therefore to successfully perform the vector control the rotor shaft position must be known and is one of the key variables in the vector control algorithm For this purpose either the mechanical position sensors are used encoders resolvers or the position of the shaft is calculated estimated from the motor phase currents and voltage This is is called sensorless control Using the mechanical position sensors brings several benefits The position is known over the entire speed range with the same precision and there is no need to compute highly mathematically intensive algorithms that estimate the rotor shaft position Vector control with a position sensor can be implemented on less powerful microcontrollers or the performance of the MCU can be used for other tasks On the other hand the cost of the mechanical sensor is a significant portion of the cost of t
77. tis K60 header file used in the project make setting the priority of the interrupt simpler The number of the interrupt is used as one of the parameters of the NVIC IP macro The assigned value then determines the priority the higher the number the higher the priority of the interrupt If the interrupt priority is not specified explicitly the lower the number of the interrupt vector the higher priority the interrupt has by default On the Kinetis K family there are 16 levels of interrupt priority implemented However the priority is set in the four MSBs of the 8 bit field NVIC IP 68 OxF0 set the highest priority for PIT ch 0 interrupt The next step is to enable the interrupts globally by clearing a 1 bit special purpose mask register PRIMASK The PRIMASK is cleared to O by the execution of the instruction CPSIE i In the application this is defined as the macro fdefine EnableInterrupts asm CPSIE i Finally the interrupt service routine has to be defined PTT CHO ISR Handler and inside the body of the function the source of the interrupt must be cleared in order to leave the interrupt service routine For the PIT channel 0 interrupt it means that the interrupt flag is cleared by writing 1 to the TIF bit of the Timer Flag Register PIT TFLGO PIT TFLG TIF MASK June 2013 Page 26 of 55 4 5 FreeMASTER software 4 5 1 Introduction The FreeMASTER software was designed to
78. ured values 63 us sampling period on the MK60 with the FreeMASTER recorder e Works with the FreeMASTER software interface for application control and monitoring O O Required speed setting start stop status motor current system status faults acknowledgment Includes FreeMASTER software speed scope observes actual and desired speeds Includes FreeMASTER software high speed currents voltages Application includes overcurrent protection different faults latched by the MOSFET driver and motor phase disconnection recorder reconstructed motor e User s buttons for manual control June 2013 Page 9 of 55 Section 3 System design 3 1 Control theory 3 1 1 3 Phase permanent magnet synchronous motor The construction of the PM synchronous motor and its mathematical description using space model can be found in DRM105 3 3 1 2 Introduction to vector control The features of the permanent magnet synchronous motor high efficiency high torque capability high power density and durability are attractive for using the PMSM in motion control applications The invention of the vector control algorithm of the AC motors came from the attempt to achieve an AC motor torque speed characteristic similar to that characteristic of the separately excited DC motor In the DC motor the maximum torque is generated automatically because of the mechanical switch called the commutator that feeds current only to that coil whose posi
Download Pdf Manuals
Related Search
Related Contents
Bedienungsanleitung Pioneer CDJ-2000 als pdf ANTICONGELANTE-REFRIGERANTE ENGINE MAX 50 User Guide - Helpdesk Communications Ltd CPH 6200 CPH 6200-D CPH 6200-Ex Precaución ヒゲトリマー&スキンケア 厚生労働省医薬食品局安全対策課 医療機器の添付文書の記載例について 説明書 - pb ピービー Nikon 6MA03711-A Camcorder User Manual CGV - My Easy Code Copyright © All rights reserved.
Failed to retrieve file