sensorless field oriented control of pmsm...

30
© 2007 Microchip Technology Inc. DS01078A-page 1 AN1078 INTRODUCTION Designers can expect environmental demands to con- tinue to drive the need for advanced motor control tech- niques that produce energy efficient air conditioners, washing machines and other home appliances. Until now, sophisticated motor control solutions have only been available from proprietary sources. However, the implementation of advanced, cost-effective motor con- trol algorithms is now a reality thanks to the new generation of Digital Signal Controllers (DSCs). An air conditioner, for example, requires fast response for speed changes in the motor. Advanced motor con- trol algorithms are needed to produce quieter units that are more energy efficient. Field Oriented Control (FOC) has emerged as the leading method to achieve these environmental demands. This application note discusses implementation of a sensorless FOC algorithm for Permanent Magnet Syn- chronous Motors (PMSMs) using the Microchip dsPIC ® DSC family. Why Use the FOC Algorithm? The traditional control method for BLDC motors drives the stator in a six-step process, which generates oscil- lations on the produced torque. In six-step control, a pair of windings is energized until the rotor reaches the next position, then the motor is commutated to the next step. Hall sensors determine the rotor position to elec- tronically commutate the motor. Advanced sensorless algorithms use the back-EMF generated in the stator winding to determine the rotor position. The dynamic response of six-step control (also called trapezoidal control) is not suitable for washing machines because the load is changing dynamically within a wash cycle, and varies with different loads and selected wash cycle. Further, in a front load washing machine, the gravitational power works against the motor load when the load is on the top side of the drum. Only advanced algorithms such as FOC can handle these dynamic load changes. This application note focuses on the PMSM-based sen- sorless FOC control of appliances because this control technique offers the greatest cost benefit in appliance motor control. The sensorless FOC technique also overcomes restrictions placed on some applications that cannot deploy position or speed sensors because the motor is flooded, or because of wire harness place- ment constraints. With a constant rotor magnetic field produced by a permanent magnet on the rotor, the PMSM is very efficient when used in an appliance. In addition, its stator magnetic field is generated by sinu- soidal distribution of windings. When compared to induction motors, PMSM motors are powerful for their size. They are also electrically less noisy than DC motors, since brushes are not used. Why Use Digital Signal Controllers for Motor Control? dsPIC DSCs are suitable for appliances like washing machines and air conditioner compressors because they incorporate peripherals that are ideally suited for motor control, such as: Pulse-Width Modulation (PWM) Analog-to-Digital Converters (ADCs) Quadrature Encoder Interface (QEI) When performing controller routines and implementing digital filters, dsPIC DSCs enable designers to optimize code because MAC instructions and fractional opera- tions can be executed in a single cycle. Also, for oper- ations that require saturation capabilities, the dsPIC DSCs help avoid overflows by offering hardware saturation protection. DSCs need fast and flexible analog-to-digital (A/D) conversion for current sensing—a crucial function in motor control. The dsPIC DSCs feature ADCs that can convert input samples at 1 Msps rates, and handle up to four inputs simultaneously. Multiple trigger options on the ADCs enable use of inexpensive current sense resistors to measure winding currents. For example, the ability to trigger A/D conversions with the PWM module allows inexpensive current sensing circuitry to sense inputs at specific times (switching transistors allow current to flow through sense resistors). Author: Jorge Zambada Microchip Technology Inc. Sensorless Field Oriented Control of PMSM Motors

Upload: buikhuong

Post on 08-Feb-2018

243 views

Category:

Documents


3 download

TRANSCRIPT

Page 1: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078Sensorless Field Oriented Control of PMSM Motors

INTRODUCTIONDesigners can expect environmental demands to con-tinue to drive the need for advanced motor control tech-niques that produce energy efficient air conditioners,washing machines and other home appliances. Untilnow, sophisticated motor control solutions have onlybeen available from proprietary sources. However, theimplementation of advanced, cost-effective motor con-trol algorithms is now a reality thanks to the newgeneration of Digital Signal Controllers (DSCs).

An air conditioner, for example, requires fast responsefor speed changes in the motor. Advanced motor con-trol algorithms are needed to produce quieter units thatare more energy efficient. Field Oriented Control (FOC)has emerged as the leading method to achieve theseenvironmental demands.

This application note discusses implementation of asensorless FOC algorithm for Permanent Magnet Syn-chronous Motors (PMSMs) using the Microchip dsPIC®

DSC family.

Why Use the FOC Algorithm?The traditional control method for BLDC motors drivesthe stator in a six-step process, which generates oscil-lations on the produced torque. In six-step control, apair of windings is energized until the rotor reaches thenext position, then the motor is commutated to the nextstep. Hall sensors determine the rotor position to elec-tronically commutate the motor. Advanced sensorlessalgorithms use the back-EMF generated in the statorwinding to determine the rotor position.

The dynamic response of six-step control (also calledtrapezoidal control) is not suitable for washingmachines because the load is changing dynamicallywithin a wash cycle, and varies with different loads andselected wash cycle. Further, in a front load washingmachine, the gravitational power works against themotor load when the load is on the top side of the drum.Only advanced algorithms such as FOC can handlethese dynamic load changes.

This application note focuses on the PMSM-based sen-sorless FOC control of appliances because this controltechnique offers the greatest cost benefit in appliancemotor control. The sensorless FOC technique alsoovercomes restrictions placed on some applicationsthat cannot deploy position or speed sensors becausethe motor is flooded, or because of wire harness place-ment constraints. With a constant rotor magnetic fieldproduced by a permanent magnet on the rotor, thePMSM is very efficient when used in an appliance. Inaddition, its stator magnetic field is generated by sinu-soidal distribution of windings. When compared toinduction motors, PMSM motors are powerful for theirsize. They are also electrically less noisy than DCmotors, since brushes are not used.

Why Use Digital Signal Controllers for Motor Control?dsPIC DSCs are suitable for appliances like washingmachines and air conditioner compressors becausethey incorporate peripherals that are ideally suited formotor control, such as:

• Pulse-Width Modulation (PWM)• Analog-to-Digital Converters (ADCs) • Quadrature Encoder Interface (QEI)

When performing controller routines and implementingdigital filters, dsPIC DSCs enable designers to optimizecode because MAC instructions and fractional opera-tions can be executed in a single cycle. Also, for oper-ations that require saturation capabilities, the dsPICDSCs help avoid overflows by offering hardwaresaturation protection.

DSCs need fast and flexible analog-to-digital (A/D)conversion for current sensing—a crucial function inmotor control. The dsPIC DSCs feature ADCs that canconvert input samples at 1 Msps rates, and handle upto four inputs simultaneously. Multiple trigger optionson the ADCs enable use of inexpensive current senseresistors to measure winding currents. For example,the ability to trigger A/D conversions with the PWMmodule allows inexpensive current sensing circuitry tosense inputs at specific times (switching transistorsallow current to flow through sense resistors).

Author: Jorge ZambadaMicrochip Technology Inc.

© 2007 Microchip Technology Inc. DS01078A-page 1

Page 2: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

MOTOR CONTROL WITH DIGITAL SIGNAL CONTROLLERSThe dsPIC30F Motor Control family is specificallydesigned to control the most popular types of motors,including:

• AC Induction Motors (ACIM)• Brushed DC Motors (BDC)• Brushless DC Motors (BLDC)• Permanent Magnet Synchronous Motors (PMSM)

Several application notes have been published basedon the dsPIC30F motor control family (see “Refer-ences” Section). These application notes are availableon the Microchip web site (www.microchip.com).

This application note demonstrates how thedsPIC30F6010A takes advantage of peripheralsspecifically suited for motor control (motor control PWMand high-speed ADC) to execute sensorless field ori-ented control of PMSM. The DSP engine of thedsPIC30F6010A supports the necessary fastmathematical operations.

Data Monitoring and Control Interface The Data Monitor and Control Interface (DMCI) pro-vides quick dynamic integration with MPLAB® IDE forprojects in which operational constraints of the applica-tion depend on variable control of range values, on/offstates or discrete values. If needed, application feed-back can be represented graphically. Examples includemotor control and audio processing applications.

The DMCI provides:

• 9 slider controls and 9 boolean (on/off) controls shown in Figure 1

• 35 input controls (see Figure 2)• 4 graphs (see Figure 3)

The interface provides project aware navigation of pro-gram symbols (variables) that can be dynamicallyassigned to any combination of slider, direct input orboolean controls. The controls can then be used inter-actively to change values of program variables withinMPLAB IDE. The graphs can be dynamicallyconfigured for viewing program generated data.

Application HighlightsThe purpose of this application note is to illustrate asoftware-based implementation of sensorless, field ori-ented control for permanent magnet synchronousmotors using Microchip digital signal controllers.

The control software offers these features:

• Implements vector control of a Permanent Magnet Synchronous Motor.

• Position and speed estimation algorithm eliminates the need for position sensors.

• An air conditioner compressor rated at 1.5 kW is targeted as the main motor.

• The speed range is from 500 to 7300 RPM.• With a 50 μsec control loop period, the software

requires approximately 21 MIPS of CPU overhead (about 2/3 of the total available CPU).

• The application requires 450 bytes of data mem-ory storage. With the user interface, approxi-mately 6 Kbytes of program memory are required. The memory requirements of the application allow it to run on the dsPIC30F2010, which is the small-est and least expensive dsPIC30F device at the time of this writing.

• An optional diagnostics mode can be enabled to allow real-time observation of internal program variables on an oscilloscope. This feature facilitates control loop adjustment.

• This application note applies to all motor control devices in the dsPIC30F and dsPIC33F families.

Note: The characteristics of the DMCI tool aresubject to change. This description of theDMCI tool is accurate at the date ofpublication.

DS01078A-page 2 © 2007 Microchip Technology Inc.

Page 3: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 1: DYNAMIC DATA CONTROL INTERFACE

FIGURE 2: USER-DEFINED DATA INPUT CONTROLS

© 2007 Microchip Technology Inc. DS01078A-page 3

Page 4: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 3: GRAPHICAL DATA VIEW

DS01078A-page 4 © 2007 Microchip Technology Inc.

Page 5: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

SYSTEM OVERVIEWAs shown in Figure 4, there are no position sensorsattached to the motor shaft. Instead, low inductanceresistors, which are part of the inverter, are used forcurrent measurements on the motor. A 3-phaseinverter is used as the power stage to drive motor wind-ings. Current sensing and fault generation circuitry builtinto the power inverter protects the overall systemagainst over currents.

Figure 5 shows how the 3-phase topology, as well asthe current detection and fault generation circuitry, areimplemented.

The first transistor shown on the left side of the inverteris used for Power Factor Correction (PFC), which is notpart of this application note.

Hardware referenced in this application note is thedsPICDEM™ MC1 Motor Control Development Board(DM300020), available at the Microchip website(www.microchip.com). Two power modules are avail-able: one for low voltages (up to 50V) and one for highvoltages (up to 400V). A modified High-voltage PowerModule (DM3000021) was used for this applicationnote. These modules are explained in the appendix.

FIGURE 4: SYSTEM OVERVIEW

PWM1H

PWM1L

PWM2H

PWM2L

PWM3H

PWM3L

Buffer

OE

RD11

3-PhaseInverter

RE9

AN0

AN1

FLTA

Ia

Ib

Over Current

3-PhasePMSM

Starting Torque Demand

VR1

VR2

Speed Demand

AN7

AN2

S4Start/StopRG6

RD0

RD1

RD2

RD3

LCD

DB4

DB5

DB6

DB7

EN

RS

R/W

RD13

RC3

RC1

dSPI

C30

F601

0A

Faul

t Res

et

User’s Interface

© 2007 Microchip Technology Inc. DS01078A-page 5

Page 6: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 5: 3-PHASE TOPOLOGY

PWM1H

PWM1L

PWM2H

PWM2L

PWM3H

PWM3L

115/230 VAC

PMSMMotor

Ia

Ib

< CurrentLimit

Fault

Optional Power Factor Correction

DS01078A-page 6 © 2007 Microchip Technology Inc.

Page 7: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIELD ORIENTED CONTROL

A Matter of PerspectiveOne way to understand how FOC (sometimes referredto as vector control) works is to form a mental image ofthe coordinate reference transformation process. If youpicture an AC motor operation from the perspective ofthe stator, you see a sinusoidal input current applied tothe stator. This time variant signal generates a rotatingmagnetic flux. The speed of the rotor is a function of therotating flux vector. From a stationary perspective, thestator currents and the rotating flux vector look like ACquantities.

Now, imagine being inside the motor and runningalongside the spinning rotor at the same speed as therotating flux vector generated by the stator currents. Ifyou were to look at the motor from this perspective dur-ing steady state conditions, the stator currents look likeconstant values, and the rotating flux vector is station-ary.

Ultimately, you want to control the stator currents toobtain the desired rotor currents (which cannot bemeasured directly). With coordinate reference transfor-mation, the stator currents can be controlled like DCvalues using standard control loops.

Vector Control SummaryIndirect vector control can be summarized as follows:

1. The 3-phase stator currents are measured.These measurements provide values ia and ib. Icis calculated because ia, ib and ic have thisrelationship:ia + ib + ic = 0.

2. The 3-phase currents are converted to a twoaxis system. This conversion provides the vari-ables iα and iβ from the measured ia and ib andthe calculated ic values. iα and iβ are time-vary-ing quadrature current values as viewed fromthe perspective of the stator.

3. The two axis coordinate system is rotated toalign with the rotor flux using a transformationangle calculated at the last iteration of the con-trol loop. This conversion provides the Id and Iqvariables from iα and iβ. Id and Iq are the quadra-ture currents transformed to the rotating coordi-nate system. For steady state conditions, Id andIq are constant.

4. Error signals are formed using Id, Iq andreference values for each. • The Id reference controls rotor magnetizing

flux.• The Iq reference controls the torque output of

the motor. • The error signals are input to PI controllers. • The output of the controllers provide Vd and

Vq, which is a voltage vector that will be sent to the motor.

5. A new transformation angle is estimated wherevα, vβ, iα and iβ are the inputs. The new angleguides the FOC algorithm as to where to placethe next voltage vector.

6. The Vd and Vq output values from the PI control-lers are rotated back to the stationary referenceframe using the new angle. This calculation pro-vides the next quadrature voltage values vα andvβ.

7. The vα and vβ values are transformed back to 3-phase values va, vb and vc. The 3-phase voltagevalues are used to calculate new PWM dutycycle values that generate the desired voltagevector. The entire process of transforming, PIiteration, transforming back and generatingPWM is illustrated in Figure 6.

The next sections of this application note describethese steps in greater detail.

© 2007 Microchip Technology Inc. DS01078A-page 7

Page 8: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 6: VECTOR CONTROL BLOCK DIAGRAM

α,β

α,β

α,β

d,q

d,q

a,b,c

PI PI

SVM3-Phase Bridge

NREF IQREF

PI

Vq

Vd

ia

ib

Motor

Speed (ω)

∑ ∑

- -

-

IDREF

Position and Speed

Estimator

Position Vα

Iq

Id

Θ

InverseParkTransform

InverseClarkeTransform

ParkTransform

ClarkeTransform

DS01078A-page 8 © 2007 Microchip Technology Inc.

Page 9: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

COORDINATE TRANSFORMSThrough a series of coordinate transforms, you canindirectly determine and control the time invariant val-ues of torque and flux with classic PI control loops. Theprocess begins by measuring the 3-phase motor cur-rents. In practice, the instantaneous sum of the threecurrent values is zero. Thus by measuring only two ofthe three currents, you can determine the third.Because of this fact, hardware cost can be reduced bythe expense of the third current sensor.

A single shunt implementation for 3-phase currentmeasurement is also possible with the dsPIC DSC.Contact Microchip for more information.

Clarke TransformThe first coordinate transform, called the Clarke Trans-form, moves a three axis, two dimensional coordinatesystem, referenced to the stator, onto a two axis sys-tem, keeping the same reference (see Figure 7, whereia, ib and ic are the individual phase currents).

FIGURE 7: CLARKE TRANSFORM

Park TransformsAt this point, you have the stator current representedon a two axis orthogonal system with the axis called α-β. The next step is to transform into another two axissystem that is rotating with the rotor flux. This transfor-mation uses the Park Transform, as illustrated inFigure 8. This two axis rotating coordinate system iscalled the d-q axis. Θ represents the rotor angle.

FIGURE 8: PARK TRANSFORM

PI ControlThree PI loops are used to control three interactivevariables independently. The rotor speed, rotor flux androtor torque are each controlled by a separate PI mod-ule. The implementation is conventional and includesterm (Kc*Excess) to limit integral windup, as illustratedin Figure 9. Excess is calculated by subtracting theunlimited output (U) and limited output (Out). The termKc multiplies the Excess, and limits the accumulatedintegral portion (Sum).

FIGURE 9: PI CONTROL

PID CONTROLLER BACKGROUNDA complete discussion of Proportional Integral Deriva-tive (PID) controllers is beyond the scope of this appli-cation note, but this section provides you with somebasics of PID operation.

A PID controller responds to an error signal in a closedcontrol loop and attempts to adjust the controlled quan-tity to achieve the desired system response. The con-trolled parameter can be any measurable systemquantity such as speed, torque or flux. The benefit ofthe PID controller is that it can be adjusted empiricallyby varying one or more gain values and observing thechange in system response.

A digital PID controller is executed at a periodic sam-pling interval. It is assumed that the controller is exe-cuted frequently enough so that the system can beproperly controlled. The error signal is formed by sub-tracting the desired setting of the parameter to be con-trolled from the actual measured value of thatparameter. The sign of the error indicates the directionof change required by the control input.

The Proportional (P) term of the controller is formed bymultiplying the error signal by a P gain, causing the PIDcontroller to produce a control response that is a func-tion of the error magnitude. As the error signalbecomes larger, the P term of the controller becomeslarger to provide more correction.

α

βClarke

ab

(c)

ia + ib + ic = 0iα = iaiβ = (ia +2ib)/√ 3

βb

a,α

c

iβ is

IqIdPark

iαiβθ

Id = iα cosθ + iβ sinθIq = -iα sinθ + iβ cosθ

βq

αiα

is θIqId

d

Kp* Err + Ki * ∫Err * dtInRef

FB (Feedback)

Out

-

Err = InRef - FB U = Sum + Kp*Err If (U > Outmax) Out = Outmax else if (U < Outmin) Out = Outmin else Out = U Excess = U - Out Sum = Sum + (Ki*Err)-(Kc*Excess)

© 2007 Microchip Technology Inc. DS01078A-page 9

Page 10: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

The effect of the P term tends to reduce the overallerror as time elapses. However, the effect of the P termdiminishes as the error approaches zero. In mostsystems, the error of the controlled parameter gets veryclose to zero but does not converge. The result is asmall remaining steady state error.

The Integral (I) term of the controller is used to elimi-nate small steady state errors. The I term calculates acontinuous running total of the error signal. Therefore,a small steady state error accumulates into a largeerror value over time. This accumulated error signal ismultiplied by an I gain factor and becomes the I outputterm of the PID controller.

The Differential (D) term of the PID controller is used toenhance the speed of the controller and responds tothe rate of change of the error signal. The D term inputis calculated by subtracting the present error valuefrom a prior value. This delta error value is multiplied bya D gain factor that becomes the D output term of thePID controller.

The D term of the controller produces more control out-put as the system error changes more rapidly. Not allPID controllers will implement the D or, less commonly,the I terms. For example, this application does not useD terms due to the relatively slow response time ofmotor speed changes. In this case, the D term couldcause excessive changes in PWM duty cycle that couldaffect the operation of the algorithms and produce overcurrent trips.

Adjusting the PID GainsThe P gain of a PID controller sets the overall systemresponse. When you first tune a controller, set the I andD gains to zero. You can then increase the P gain untilthe system responds well to set point changes withoutexcessive overshoot or oscillations. Using lower valuesof P gain will ‘loosely’ control the system, while highervalues will give ‘tighter’ control. At this point, the systemwill probably not converge to the set point.

After you select a reasonable P gain, you can slowlyincrease the I gain to force the system error to zero.Only a small amount of I gain is required in most sys-tems. The effect of the I gain, if large enough, can over-come the action of the P term, slow the overall controlresponse and cause the system to oscillate around theset point. If oscillation occurs, reducing the I gain andincreasing the P gain will usually solve the problem.

This application includes a term to limit integral windup,which occurs if the integrated error saturates the outputparameter. Any further increase in the integrated errordoes not affect the output. The accumulated error,when it does decrease, will have to fall (or unwind) tobelow the value that caused the output to saturate. TheKc coefficient limits this unwanted accumulation. Formost situations, this coefficient can be set equal to Ki.

All three controllers have a maximum value for the out-put parameter. These values can be found in theUserParms.h file and are set by default to avoidsaturation in the SVGen() routine.

Control Loop DependenciesThere are three interdependent PI control loops in thisapplication. The outer loop controls the motor velocity.The two inner loops control the transformed motor cur-rents, Id and Iq. As mentioned previously, the Id loop isresponsible for controlling flux, and the Iq value isresponsible for controlling the motor torque.

Inverse ParkAfter the PI iteration you have two voltage componentvectors in the rotating d-q axis. You will need to gothrough complementary inverse transforms to get backto the 3-phase motor voltage. First you transform fromthe two axis rotating d-q frame to the two axis stationaryframe α-β. This transformation uses the Inverse ParkTransform, as illustrated in Figure 10.

FIGURE 10: INVERSE PARK

Inverse ClarkeThe next step is to transform from the stationary twoaxis α-β frame to the stationary three axis, 3-phase ref-erence frame of the stator. Mathematically, this trans-formation is accomplished with the Inverse ClarkTransform, as illustrated in Figure 11.

FIGURE 11: INVERSE CLARKE

VαVβ

InverseVdVq

θ

Vα = Vd * cosθ - Vq * sinθVβ = Vd * sinθ + Vq * Cosθ

βq

αVα

Vs θVq Vd

dPark

Vr1Vr2Vr3

Vr1 = VβVr2 = (-Vβ + √ 3 * Vα)/2Vr3 = (-Vβ - √ 3 * Vα)/2

βVr2

Vr1,α

Vr3

Vβ Vs

Inverse Clarke

DS01078A-page 10 © 2007 Microchip Technology Inc.

Page 11: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Space Vector Modulation (SVM)The final step in the vector control process is togenerate pulse-width modulation signals for the 3-phase motor voltage signals. If you use Space VectorModulation (SVM) techniques, the process of generat-ing the pulse width for each of the three phases isreduced to a few simple equations. In this implementa-tion, the Inverse Clarke Transform has been folded intothe SVM routine, which further simplifies thecalculations.

Each of the three inverter outputs can be in one of twostates. The inverter output can be connected to eitherthe + bus rail or the - bus rail, which allows for 23 = 8possible states that the output can be in (see Table 1).

The two states in which all three outputs are connectedto either the + bus or the - bus are considered nullstates because there is no line-to-line voltage acrossany of the phases. These are plotted at the origin of theSVM Star. The remaining six states are represented asvectors with 60 degree rotation between each state, asshown in Figure 12.

FIGURE 12: SPACE VECTOR MODULATION

The process of Space Vector Modulation allows therepresentation of any resultant vector by the sum of thecomponents of the two adjacent vectors. In Figure 13,UOUT is the desired resultant. It lies in the sector

between U60 and U0. If during a given PWM period T,U0 is output for T1/T and U60 is output for T2/T, theaverage for the period will be UOUT.

FIGURE 13: AVERAGE SPACE VECTOR MODULATION

T0 represents a time where no effective voltage isapplied into the windings; that is, where a null vector isapplied. The values for T1 and T2 can be extracted withno extra calculations by using a modified Inverse Clarktransformation. If you reverse Vα and Vβ, a referenceaxis is generated that is shifted by 30 degrees from theSVM star. As a result, for each of the six segments, oneaxis is exactly opposite that segment and the other twoaxes symmetrically bound the segment. The values ofthe vector components along those two bounding axesare equal to T1 and T2. See the CalcRef.s andSVGen.s files in the source code for details of thecalculations.

You can see from Figure 14 that for the PWM period T,the vector T1 is output for T1/T and the vector T2 isoutput for T2/T. During the remaining time the nullvectors are output. The dsPIC DSC is configured forcenter-aligned PWM, which forces symmetry about thecenter of the period. This configuration produces twopulses line-to-line during each period. The effectiveswitching frequency is doubled, reducing the ripplecurrent while not increasing the switching losses in thepower devices.

TABLE 1: SPACE VECTOR MODULATION INVERTER STATES

U60(011)U120(010)

U180(110)U(111) U(000)

U0(001)

U240(100) U300(101)

U60(011)

UOUT

T2/T * U60

T1/T * U0 U0(001)

T0 = Null VectorT = T1 + T2 + T0 = PWM PeriodUOUT = (T1/T * U0) + (T2/T * U60)

Phase C Phase B Phase A Vab Vbc Vca Vds Vqs Vector

0 0 0 0 0 0 0 0 U(000)0 0 1 VDC 0 -VDC 2/3VDC 0 U00 1 1 0 VDC -VDC VDC/3 VDC/3 U600 1 0 -VDC VDC 0 -VDC/3 VDC/3 U1201 1 0 -VDC 0 VDC -2VDC/3 0 U1801 0 0 0 -VDC VDC -VDC/3 - VDC/3 U2401 0 1 VDC -VDC 0 VDC/3 - VDC/3 U3001 1 1 0 0 0 0 0 U(111)

© 2007 Microchip Technology Inc. DS01078A-page 11

Page 12: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 14: PWM FOR PERIOD T

PWM1

PWM2

PWM3

T0/4 T1/2 T2/2 T0/4 T2/2 T1/2 T0/4T0/4

T

DS01078A-page 12 © 2007 Microchip Technology Inc.

Page 13: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

SENSORLESS FIELD ORIENTED CONTROL FOR PMSM MOTORSAn important piece of the algorithm is how to calculatethe commutation angle needed for FOC. This section ofthe application note explains the process of estimatingcommutation angle (θ) and motor speed (ω).

The sensorless control technique implements the FOCalgorithm by estimating the position of the motor with-out using position sensors. Figure 15 is a simplifiedblock diagram of the position estimator function.

Motor position and speed are estimated based onmeasured currents and calculated voltages.

FIGURE 15: POSITION ESTIMATOR FUNCTION BLOCK DIAGRAM

InverterPWM1H

Fault

Ia

Ib

PMSMMotor

Position and Speed Estimation

I

FOC Control

V

Vcc

θω

ω REF

dsPIC® DSC

PWM1LPWM2HPWM2LPWM3HPWM3LP

WM

A/D

A/D

© 2007 Microchip Technology Inc. DS01078A-page 13

Page 14: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Motor ModelYou can estimate the PMSM Motor position by using amodel of a DC Motor, which can be represented bywinding resistance, winding inductance and back-EMF,as shown in Figure 16.

FIGURE 16: MOTOR MODEL

From the motor model, the input voltage can beobtained by Equation 1.

EQUATION 1: DIGITIZED MOTOR MODEL

Calculating F and G ParametersThe motor model has two parameters that need to bemodified for a particular motor. These two parametersare F and G gains, where:

Constants R and L are measured using a simple multi-meter. For example, if a line to line resistance is mea-sured, the R used for F and G gains is themeasurement divided by two, since the phase resis-tance is needed. The same procedure applies to induc-tance calculation L. For example, if a new motor is runwith this algorithm at 8 kHz control frequency, wherethe line to line resistance measured is 5.0Ω, and line toline inductance is 10 mH, then the motor model param-eters are:

es

Motor

R L

vs

is

vs Ris L ddt-----is es+ +=

Where:

Motor current is obtained by solving for is:

In the digital domain, this equation becomes:

Solving for is:

or

is (n + 1) = F•is(n) + G•(vs(n) - es(n))

where

is = Motor Current Vectorvs = Input Voltage Vectores = Back-EMF VectorR = Winding ResistanceL = Winding InductanceTs = Control Period

ddt----- is

RL---–⎝ ⎠

⎛ ⎞ is1L--- vs es–( )+=

is n 1+( ) is n( )–Ts

--------------------------------------- RL---–⎝ ⎠

⎛ ⎞ is n( ) 1L--- vs n( ) es n( )–( )+=

is n 1+( ) 1 Ts– RL---⋅⎝ ⎠

⎛ ⎞ is n( )TsL----- vs n( ) es n( )–( )+=

F = 1 – T •RL

s

G = TLs

F = 1 – T •RL

s

G = TLs

F = 1 – Ts•RL = 1 – (1/8 kHz)• (5.0Ω/2)

(10 mH/2)= 0.9375

G = TsL =

(1/8 kHz)(10 mH/2) = 0.025

DS01078A-page 14 © 2007 Microchip Technology Inc.

Page 15: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Current ObserverThe position and speed estimator is based on a currentobserver. This observer is a digitized model of themotor, as represented by Equation 1. Variables andconstants include:

• Motor Phase Current (is) • Input voltage (vs) • back-EMF (es) • Winding resistance (R) • Winding inductance (L) • Control period (Ts)• Output Correction Factor Voltage (z)

The digitized model provides a software representationof the hardware. However, in order to match measuredcurrent and estimated current, the digitized motormodel needs to be corrected using the closed loopshown in Figure 17.

Considering two motor representations, one in hard-ware (shaded area) and one in software, with the sameinput (vs) fed into both systems, and matching the mea-sured current (is) with estimated current (is*) from themodel, we can presume that back-EMF (es*) from ourdigitized model is the same as the back-EMF (es) fromthe motor.

FIGURE 17: CURRENT OBSERVER BLOCK DIAGRAM

A slide mode controller, or SMC, is used to compensatethe digitized motor model. An SMC consists of a sum-mation point that calculates the sign of the errorbetween measured current from the motor and esti-mated current from the digitized motor model. Thecomputed sign of the error (+1 or -1) is multiplied by anSMC gain (K). The output of the SMC controller is thecorrection factor (Z). This gain is added to the voltageterm from the digitized model, and the process repeatsevery control cycle until the error between measuredcurrent (is) and estimated current (is*) is zero (i.e., untilmeasured current and estimated current match).

Back-EMF EstimationAfter compensating the digitized model, you have amotor model with the same variable values for the inputvoltage (Vs) and for current (is*). Once the digitizedmodel is compensated, the next step is to estimateback-EMF (es*) by filtering the correction factor (Z), asshown in Figure 18. The back-EMF estimation (e*s) isfed back to the model to update the variable es* afterevery control cycle. Values eα and eβ (vector compo-nents of es) are used for the estimated thetacalculation.

FIGURE 18: BACK-EMF ESTIMATION MODEL

PMSM+K

-K

Slide-ModeControlleris

is*

z

-

+ Sign(is* - is)

Vs

*Estimated variable

ddt

i*s =RL

i*s + 1L

(v - e* - z)s s

Hardware

-

arctaneαeβ

efiltered*s θ*LPF

e*s

LPFz

ddt i*s = R

Li*s + 1

L(v - e* - z)s s-

From Slide-ModeController

© 2007 Microchip Technology Inc. DS01078A-page 15

Page 16: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Back-EMF FilteringTo provide the filtering, a first-order, digital low-passfilter is used with Equation 2.

EQUATION 2: FIRST-ORDER DIGITAL LOW-PASS FILTER:

The value of the cutoff frequency depends on theselection of the slide-mode controller gain and is setexperimentally.

The output of the first filter is used in two blocks. Thefirst block is the model itself, used to calculate the nextestimated current (is*), and also to calculate the esti-mated theta (θ∗). A second, first-order filter is used tocalculate a smoother signal coming out of the motormodel.

Relationship Between Back-EMF and Rotor PositionOnce the back-EMF has been filtered for the secondtime, theta is calculated. The relationship between esand θ can be explained based on the graph shown inFigure 19.

FIGURE 19: BACK-EMF AND THETA RELATIONSHIP

The plot shows a trigonometric function relating thevector components of the back-EMF (eα and eβ ) androtor angle (θ). Arctangent is computed on the back-EMF vector components to calculate theta. Equation 3illustrates how the function is implemented in software:

EQUATION 3: THETA CALCULATION

The actual implementation uses a numeric and iterativealgorithm called CORDIC (COordinate Rotation by DIg-ital Computer), which is fast, yet takes less memorythan a floating point implementation. Discussion of theCORDIC algorithm is beyond the scope of thisapplication note.

y n( ) y n 1–( ) T2πfc x n( ) y n( )–( )⋅+=

To filter z to obtain e*, we substitute in the equation for8 kHz and we get:

Where:

e(n) = Next estimated back-EMF valuee(n-1) = Last estimated back-EMF valuefpwm = PWM frequency at which the digital

filter is being calculatedfc = Cutoff frequency of the filterz(n) = Unfiltered back-EMF, which is output

from the slide mode controller

e n( ) e n 1–( ) 1fpwm-----------⎝ ⎠⎛ ⎞ 2πfc z n( ) e n( )–( )⋅+=

eα eβ θ1

0.5

0

-1.5

-1

-1.5

11 21 31 41 51 61 71 81 91 101|||||||||||||||||||| |||||||||||||||||||| |||||||||||||||||||| |||||||||||||||||||||||||||||||||||||||||||||||||

1.5

θ = arctan (eα , eβ)

DS01078A-page 16 © 2007 Microchip Technology Inc.

Page 17: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Speed CalculationDue to the filtering function applied during the theta cal-culation, some phase compensation is needed beforethe calculated angle is used to energize the motorwindings. The amount of theta compensation dependson the rate of change of theta, or speed of the motor.The theta compensation is performed in two steps:

• First, the speed of the motor is calculated based on the uncompensated theta calculation.

• Then the calculated speed is filtered and used to calculate the amount of compensation, as shown in Figure 20.

FIGURE 20: SPEED CALCULATION BLOCK DIAGRAM

Speed is calculated by accumulating theta values overm samples and then multiplying the accumulated thetaby a constant. The formula used in this application notefor speed calculation is shown in Equation 4.

EQUATION 4: SPEED CALCULATION

Where:

To secure a smoother signal on the speed calculation,a first order filter is applied to Omega (ω*)to obtain Fil-teredOmega (ω*filtered). First order filter topology is thesame as the ones used for back-EMF filtering.

Phase CompensationAfter uncompensated theta and filtered speed havebeen calculated, the delays introduced in the filteringprocess must be removed. This is accomplished byadding a compensating offset theta (_OffsetTheta),which is determined by motor speed, to theuncompensated theta, as follows:

It is recommended that phase compensation be finetuned for any particular motor. In this application, weseparated phase compensation into eight speedranges. Each speed range has its own slope and con-stant phase compensation component. Table 2 lists thephase compensation formulas used in this equation.

TABLE 2: PHASE COMPENSATION FORMULAS

arctaneαeβ

ω = Σm-1

i=0(θ(n) - θ(n-1)) . Kspeed LPF

θ* +

+

θ*comp

ω*

ω*filtered

Omega (ω) = Angular velocity of the motor

Theta (θn) = Current Theta valuePrevTheta (θn-1) = Previous Theta valueKspeed = Amplification factor for

desired speed rangem = Number of accumulated

Theta deltas

ω θn θn 1––( )i 0=

m

∑= Kspeed⋅

Speed Range(FilteredOmega)

Phase Compensation Formula (__OffsetTheta)

Minimum – 0.09375 θoffset = 00.09375 – 0.1875 θoffset = 4ωfiltered + 0.3750.1875 - 0.2876 θoffset = 2ωfiltered 0.2876 - 0.38095 θoffset = ωfiltered + 0.28760.38095 - 0.475 θoffset = ωfiltered + 0.28760.475 - 0.568 θoffset = 0.5ωfiltered + 0.52510.568 - 0.756 θoffset = 0.25ωfiltered + 0.66710.756 - Maximum θoffset = 0.125ωfiltered + 0.748275

θ*comp = θ* + θoffset

© 2007 Microchip Technology Inc. DS01078A-page 17

Page 18: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

Changing Phase Compensation FormulasIn the ZIP file containing the source code of this appli-cation note, there is a spreadsheet that will help theusers calculate the angle compensation formulas. Theuser is required to type Speed in RPMs and Theta to becompensated at that particular speed. For example, ifat 500 RPMs the phase compensation needs to be 30degrees, then the user needs to type 500 under the“Speed (RPMs)” field, and 30 under the “Angle Com-pensation (Degrees)” field. The spreadsheet will calcu-late the slope and constant for the line equation.

In the same spreadsheet, the user needs to define thefollowing parameters to translate speed from RPMs toQ15 format:

Ts: PWM Period

Kspeed: Speed Constant

m: Number of Accumulated Theta Deltas perSpeed Calculation

Pole Pairs: Number of Motor Pole Pairs

FLOW CHARTSThe FOC algorithm is executed at the same rate as thePWM. It is configured so that the PWM triggers A/Dconversions for two windings using two shunt resistorsand a potentiometer that sets the reference speed ofthe motor. Interrupts of the A/D are enabled to performthe algorithm. Figure 21 shows the general executionof the A/D Interrupt subroutine.

FIGURE 21: A/D INTERRUPT SUBROUTINE

Figure 22 shows the process of using the Slide ModeController to estimate the position and speed of themotor.

A/D Interrupt

-

Use Clarke Transform to Convert

Phase CurrentsFrom 3-Axis to 2-Axis

Use Park Transformto Convert

2-Axis Currents to Rotating Coordinate System

Use Slide Mode Controllerto Estimate

Motor Position and Speed

Run PI Controllersfor

Currents and Speed

Use Inverse Park Transformto Convert

Rotating Coordinate Systemto Axis Stationary System

Use Inverse Clarke Transformto Convert

2-Axis to 3-Axis

Use Space Vector Modulationto Update

PWM Duty Cycle

End of A/D Interrupt

DS01078A-page 18 © 2007 Microchip Technology Inc.

Page 19: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 22: MOTOR POSITION AND

SPEED ESTIMATIONMOTOR START-UPSince the sensorless FOC algorithm is based on theback-EMF estimation, a minimum speed is needed toget the estimated back-EMF value. Therefore, themotor windings must be energized with the appropriateestimated angle. To handle this, a motor start-up sub-routine (see Figure 23) was developed.

When the motor is at standstill, and the start/stop but-ton has been pressed, the dsPIC DSC generates aseries of sinusoidal voltages to get the motor spinning.The motor spins at a fixed acceleration rate, and theFOC algorithm controls the currents Id and Iq. Theangle Theta (commutation angle) is incremented basedon the acceleration rate.

As shown in the diagram, phase angle is incrementedat a squared rate to get a constant acceleration on themotor. Even if Theta is being generated by the openloop-state machine, Field Oriented Control blocks arestill being executed and are controlling torque compo-nent current and flux component current. An externalpotentiometer is used to set the desired torque requiredto start the motor. This potentiometer is set experimen-tally depending on mechanical load characteristics.This start-up subroutine provides a constant torque tostart up the motor. At the end of the start-up ramp, thesoftware switches over to closed-loop, sensorlesscontrol, taking Theta from the position and speedestimator shown in Figure 6.

Filter Output FromSlide Mode Controller

to EstimateBack-EMF

Use Slide Mode Controllerand Motor Model

to EstimateMotor Currents

Slide Mode Controller

Accumulated Theta count = m?

Yes

No

Filter EstimatedBack-EMFto Create

Smoother Signal

UseEstimated Rotor Position

to CalculateRotor Speed

Compensate ThetaBased on

Speed Calculation

End ofSlide Mode Controller

Subroutine

FilterEstimated

Speed

Use Arctangent to ComputeEstimated Motor Position

Based onEstimated Back-EMF

© 2007 Microchip Technology Inc. DS01078A-page 19

Page 20: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 23: MOTOR START-UP

Motor Start Up

PI

PI

-

-

θ

d,q

α,β

Motor

α,β

a,b,c

Position

Iq ref 3-PhaseBridgeSVM

Iq

Id

ia

Id ref

Vq

Vd

d, q

α, β

ib

t

θ

(VR1)

DS01078A-page 20 © 2007 Microchip Technology Inc.

Page 21: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

MAIN SOFTWARE STATE MACHINEIt is helpful to visualize the FOC algorithm as a softwarestate machine (see Figure 24). First, the motor wind-ings are de-energized and the system waits for the userto press the start/stop button (S4 on the developmentboard). Once the user presses start/stop button, thesystem enters initialization state, where all variablesare set to their initial value and interrupts are enabled.Then the start-up subroutine is executed, where cur-rent components for torque (Iq) and flux production (Id)are being controlled, and commutation angle (Theta) isbeing generated in a ramp fashion to get the motorspinning.

After going through the start-up subroutine, the systemswitches over to sensorless FOC control, where thespeed controller is added to the execution thread, andthe Slide Mode Controller (SMC) starts estimating thetaas previously explained. When the motor enters sen-sorless FOC control state, the reference speed is con-tinuously read from an external potentiometer and thestart/stop button is monitored to stop the motor.

Any fault in the system causes the motor to stop andreturn to Motor Stopped state until S4 is pressed again.The state diagram shows all the different states of thesoftware and the conditions that make the system tran-sition to a different state.

FIGURE 24: MAIN SOFTWARE STATE MACHINE

Reset

Initialize Variables and

Peripherals

Motor Stopped

InitializeVariables forRunning the

Initialize PI ControllerParameters

EnableInterrupts

Motor Running Start Up

ReadReference

Torque fromVR1

MeasureWindingCurrents

ConvertCurrents

Iq and IdExecute

PI Controllers

Iq and Id

IncrementTheta

Ramp

Set NewDuty Cycles

SVM

Motor Running

Sensorless FOC

ReadReference

Speed

MeasureWindingCurrents

ConvertCurrents

Iq and IdEstimate

usingCalculate

Speed

CompensateTheta

Speed

ExecutePI Controllers

for Speed,

Set NewDuty Cycles

SVM

Stop Motor

A/D Interrupt

A/D InterruptEnd of Start Up Ramp

S4 Pressed

S4 Pressed or FAULT

S4 Pressed or FAULT

Motor

to

for

Based onusing

Iq and Id

using

Based onTheta

SMC

from VR2

to

Initialization State

Start-Up State

Sensorless FOC State

© 2007 Microchip Technology Inc. DS01078A-page 21

Page 22: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

BENEFITS OF DSC-BASED FOC CONTROLA major advantage of deploying DSCs in motor controlis the practicality of a common design platform, whichmakes the production of appliances more efficient. Thismeans appliance makers now have an economical wayto offer a range of appliance models that use PMSM orother type of motors with sensorless FOC algorithmcontrol.

These software-based motor control designs enablerapid customization to address multiple markets bychanging only the control parameters.

Protection of firmware Intellectual Property (IP) isanother major issue for manufacturers who frequentlydeploy appliance design teams that collaborate acrossmany geographies. It is easy to imagine a scenario inwhich the implementation of FOC for an appliancemight have come from place A, user-interface boardfrom place B and final system integration being done inplace C.

In developing their designs, it is more than likely thatthese design teams will have claims to their own IP.Microchip's dsPIC DSC family offers the CodeGuard™Security feature, which helps to protect IP in collabora-tive design environments (for more information, seewww.microchip.com/codeguard).

CONCLUSIONThis application note illustrates how designers can takeadvantage of DSCs to implement advanced motor con-trol techniques such as the Sensorless FOC algorithmin appliance applications. Since programming thedsPIC DSCs is similar to programming the MCUs,appliance designers can quickly design their motorcontrol algorithm and test their prototypes.

Fine tuning motor control is made easy, thanks to thepowerful IDE-based tools such as the DMCI, whichallows the designers to easily port their algorithmsacross a variety of motor platforms including PMSM,BLDC, Brushed DC (BDC) and ACIM motors.

Microchip has various resources to assist you in tuningthese parameters. Contact your Microchip sales orapplication engineer if you would like further support.

DS01078A-page 22 © 2007 Microchip Technology Inc.

Page 23: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

APPENDIX

Hardware ResourcesThe hardware used to implement this sensorless FOCapplication consists of the following components:

• dsPICDEM™ MC1 Motor Control Development Board (DM300020)

• dsPICDEM™ MC1H 3-Phase High Voltage Power Module (DM300021)

• Toshiba Compressor Model HD187X1-S12FD.

MC1 Development tools can be obtained from theMicrochip web site (www.microchip.com). Customerswith their own compressor may refer to the followingmotor parameters:

Hardware ModificationsOut of the box, the high voltage power module has anominal power output of 0.8 kVA. To drive a PMSM airconditioner compressor with a load represented by thelisted parameters, the module must be modified. Theboard must be removed from its housing to completeportions of this modification.

Certain modifications, as described below, have beenallowed for in the design of the system. Clearly, anyadditional modifications that the user chooses to makecan not be guaranteed to be functional or safe. It isassumed that relevant qualified personnel only will usethe system.

MODIFYING THE BOARD (REFER TO FIGURE 25)Step One:

Establish a common power and digital groundby adding a high-current jumper

Step Two:Replace the existing motor current-sensingshunt resistors

Step Three:Configure power module jumper settings

Step Four:Bypass Fault signals from Hall Effect sensors

Step Five:Activate feedback current-sensing circuit byinstalling selection resistors

Hall type current sensors cannot be used for currentsensing after these modifications. Hall over-currentfault is also disabled with these modifications; however,shunt over-current fault is still active for over-currentfaults.

ACCESSING THE BOARDBefore removing the lid (see Figure 25), the followingprocedure should be rigidly followed:

• Turn off all power to the system.

• Wait a minimum of 3 minutes so that the internal dis-charge circuit has reduced the DC bus voltage to a safelevel. The red LED bus voltage indicator visible throughthe top ventilation holes should be out.

• Verify with a voltmeter that discharge has taken placeby checking the potential between the + and - DC ter-minals of the 7-pin output connector before proceeding.The voltage should be less than 10V.

• The system is now safe to work on.

• Remove all cables from the system.

• Remove the screws fixing the lid to the chassis andheat sink on the top and bottom.

• Slide the lid forwards while holding the unit by the heatsink.

After the board is out of the housing, follow the detailedprocedures shown in Figures 26 through 30.

Number of poles: 4 (2 pole pairs)Speed range: 900 to 7200 RPMNominal Output Power (P): 750 WWinding Resistance (R): 0.70 Winding Inductance Average (L): 7.35 mHNominal Current (I): 6.0 ± 0.3 ALine-to-line back-EMF constant: 0.0228 Vrms/RPMTorque constant: 0.39 N m/A

Note: Refer to the “dsPICDEM™ MC1H 3-Phase High Voltage Power Module User’sGuide” (DS70096) for additional informa-tion.

© 2007 Microchip Technology Inc. DS01078A-page 23

Page 24: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FI

GU

RE

25:

dsPI

CD

EM™

MC

1H 3

-PH

ASE

HIG

H V

OLT

AG

E PO

WER

MO

DU

LE W

ITH

CO

VER

REM

OVE

D

Step

One

Est

ablis

h co

mm

on p

ower

and

dig

ital g

roun

dby

add

ing

high

-cur

rent

jum

per

(See

Fig

ure

26)

Step

Tw

oR

epla

ce

mot

or

curr

ent

sens

ing

shun

t res

isto

rs(s

ee F

igur

e27

)

Step

Fou

rB

ypas

s Fa

ult

sign

als

from

H

all

Effe

ct s

enso

rs(s

ee F

igur

e29

)

Step

Fiv

eIn

stal

l fe

edba

ck c

urre

nt s

ensi

ngse

lect

ion

resi

stor

s(s

ee F

igur

e30

)

Step

Thr

eeC

onfig

ure

Pow

er M

odul

e ju

mpe

rse

tting

s(s

ee F

igur

e28

)

DS01078A-page 24 © 2007 Microchip Technology Inc.

Page 25: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 26: ESTABLISH COMMON POWER AND DIGITAL SIGNAL GROUND

FIGURE 27: REPLACE CURRENT-SENSING SHUNT RESISTORS

FIGURE 28: CONFIGURE JUMPER SETTINGS

J13

J5

Step One: Establish common power and digital signal ground

BEFORE AFTER

J13

J5BEFOREJ5

J13

Because shunt resistors are used tosense current from the motor,power and digital signals must usethe same ground.

Solder a high-current jumper wire(AWG 18 minimum) between J5and J13.

JUMPER

Step Two: Replace motor current-sensing shunt resistors

R3

R5

R4

UNDERSIDE OF BOARD

R3R5R4

BEFORE AFTER

To accommodate higher current, thecurrent-sensing shunt resistors mustbe changed from the default value of25 mΩ/3W to 10 mΩ/3W.

The recommended method is to cutshunt resistors R3, R4 and R5 fromthe top side of the board and solderreplacement shunt resistors on theunderside of the board.

Step Three: Configure Power Module jumper settings

123

LK4

LK5

LK6

LK7

LK8

LK9

LK10

LK11

LK12

The illustrated jumper settings ensure a gain of 16.67, whichprovides a feedback of 6A per 1V. Jumper LK4 provides anoffset of 2.5V to enable measurement of both positive andnegative currents.

The new formula for current measurement is:

V = 2.5 + I/6

© 2007 Microchip Technology Inc. DS01078A-page 25

Page 26: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

FIGURE 29: DISABLE HALL EFFECT SENSORS

FIGURE 30: INSTALL FEEDBACK CURRENT SELECTION RESISTORS

Step Four: Bypass Fault signals from Hall Effect sensors

BEFORE

J11

J15

AFTER

LK15

LK18

The dsPICDEM™ MC1H 3-Phase HighVoltage Power Module uses three HallEffect sensors. Two sensors are usedwith winding currents; the third is usedwith the IBUS current. These sensors,and their associated feedback circuitry,generate Fault signals that must bebypassed for the air conditioning com-pressor application. Follow these steps:

1. To bypass Sensor U3, unsolderthe wire at J11 and unloop it fromthe sensor.

2. Resolder wire to the right side ofjumper LK15.

2a. Cut the jumper on LK15.

2b. Cut the jumper on LK18.

3. Repeat for U4, moving from J15 toLK18.

4. To bypass the IBUS sensor (U2),cut the jumper on LK2.

5. Solder a high-current (AWG 18)wire from the right side of jumperLK2 to pin 1 of the input diodebridge

WINDING CURRENT LOOPSTHROUGH LEM SENSORS SENSORS

BYPASSED

BEFORE AFTER

LEM OUTPUTON LK2 JUMPER

U3

U4

U3

U4

U2

INPUT DIODE BRIDGEPIN 1

LK2

AFTERStep Five: Install feedback current sensing selection resistors

To obtain feedback current, the circuitlinks must be completed.

To activate the current feedback forthis application, populate links LK20and LK21 with 5.6 kΩ resistors.

AFTERBEFORE

LK20 & LK21 LINKS 5.6 kΩ SHUNT RESISTORS

DS01078A-page 26 © 2007 Microchip Technology Inc.

Page 27: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

REFERENCES Several application notes have been published byMicrochip Technology describing the use of DSCs formotor control.

For ACIM control see:

• AN984, “An Introduction to AC Induction Motor Control Using the dsPIC30F MCU” (DS00984)

• AN908, “Using the dsPIC30F for Vector Control of an ACIM” (DS00908)

• GS004, “Driving an ACIM with the dsPIC® DSC MCPWM Module” (DS93004)

For BLDC motor control see:

• AN901, “Using the dsPIC30F for Sensorless BLDC Control” (DS00901)

• AN957, “Sensored BLDC Motor Control Using dsPIC30F2010” (DS00957)

• AN992, “Sensorless BLDC Motor Control Using dsPIC30F2010” (DS00992)

• AN1083, “Sensorless BLDC Control with Back-EMF Filtering” (DS01083)

For PMSM control see:

• AN1017, “Sinusoidal Control of PMSM Motors with dsPIC30F DSC” (DS01017)

For information on the dsPICDEM MC1 Motor ControlDevelopment Board see:

• “dsPICDEM™ MC1 Motor Control Development Board User’s Guide” (DS70098)

• “dsPICDEM™ MC1H 3-Phase High Voltage Power Module User’s Guide” (DS70096)

• “dsPICDEM™ MC1L 3-Phase Low Voltage Power Module User’s Guide” (DS70097)

These documents are available on the Microchip website (www.microchip.com).

© 2007 Microchip Technology Inc. DS01078A-page 27

Page 28: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

AN1078

NOTES:

DS01078A-page 28 © 2007 Microchip Technology Inc.

Page 29: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

Note the following details of the code protection feature on Microchip devices:• Microchip products meet the specification contained in their particular Microchip Data Sheet.

• Microchip believes that its family of products is one of the most secure families of its kind on the market today, when used in the intended manner and under normal conditions.

• There are dishonest and possibly illegal methods used to breach the code protection feature. All of these methods, to our knowledge, require using the Microchip products in a manner outside the operating specifications contained in Microchip’s Data Sheets. Most likely, the person doing so is engaged in theft of intellectual property.

• Microchip is willing to work with the customer who is concerned about the integrity of their code.

• Neither Microchip nor any other semiconductor manufacturer can guarantee the security of their code. Code protection does not mean that we are guaranteeing the product as “unbreakable.”

Code protection is constantly evolving. We at Microchip are committed to continuously improving the code protection features of ourproducts. Attempts to break Microchip’s code protection feature may be a violation of the Digital Millennium Copyright Act. If such actsallow unauthorized access to your software or other copyrighted work, you may have a right to sue for relief under that Act.

Information contained in this publication regarding deviceapplications and the like is provided only for your convenienceand may be superseded by updates. It is your responsibility toensure that your application meets with your specifications.MICROCHIP MAKES NO REPRESENTATIONS ORWARRANTIES OF ANY KIND WHETHER EXPRESS ORIMPLIED, WRITTEN OR ORAL, STATUTORY OROTHERWISE, RELATED TO THE INFORMATION,INCLUDING BUT NOT LIMITED TO ITS CONDITION,QUALITY, PERFORMANCE, MERCHANTABILITY ORFITNESS FOR PURPOSE. Microchip disclaims all liabilityarising from this information and its use. Use of Microchipdevices in life support and/or safety applications is entirely atthe buyer’s risk, and the buyer agrees to defend, indemnify andhold harmless Microchip from any and all damages, claims,suits, or expenses resulting from such use. No licenses areconveyed, implicitly or otherwise, under any Microchipintellectual property rights.

© 2007 Microchip Technology Inc.

Trademarks

The Microchip name and logo, the Microchip logo, Accuron, dsPIC, KEELOQ, KEELOQ logo, microID, MPLAB, PIC, PICmicro, PICSTART, PRO MATE, PowerSmart, rfPIC, and SmartShunt are registered trademarks of Microchip Technology Incorporated in the U.S.A. and other countries.

AmpLab, FilterLab, Linear Active Thermistor, Migratable Memory, MXDEV, MXLAB, PS logo, SEEVAL, SmartSensor and The Embedded Control Solutions Company are registered trademarks of Microchip Technology Incorporated in the U.S.A.

Analog-for-the-Digital Age, Application Maestro, CodeGuard, dsPICDEM, dsPICDEM.net, dsPICworks, ECAN, ECONOMONITOR, FanSense, FlexROM, fuzzyLAB, In-Circuit Serial Programming, ICSP, ICEPIC, Mindi, MiWi, MPASM, MPLAB Certified logo, MPLIB, MPLINK, PICkit, PICDEM, PICDEM.net, PICLAB, PICtail, PowerCal, PowerInfo, PowerMate, PowerTool, REAL ICE, rfLAB, rfPICDEM, Select Mode, Smart Serial, SmartTel, Total Endurance, UNI/O, WiperLock and ZENA are trademarks of Microchip Technology Incorporated in the U.S.A. and other countries.

SQTP is a service mark of Microchip Technology Incorporated in the U.S.A.

All other trademarks mentioned herein are property of their respective companies.

© 2007, Microchip Technology Incorporated, Printed in the U.S.A., All Rights Reserved.

Printed on recycled paper.

DS01078A-page 29

Microchip received ISO/TS-16949:2002 certification for its worldwide headquarters, design and wafer fabrication facilities in Chandler and Tempe, Arizona, Gresham, Oregon and Mountain View, California. The Company’s quality system processes and procedures are for its PIC®

MCUs and dsPIC® DSCs, KEELOQ® code hopping devices, Serial EEPROMs, microperipherals, nonvolatile memory and analog products. In addition, Microchip’s quality system for the design and manufacture of development systems is ISO 9001:2000 certified.

Page 30: Sensorless Field Oriented Control of PMSM Motorsww1.microchip.com/downloads/en/AppNotes/01078A.pdf · Sensorless Field Oriented Control of ... to execute sensorless field ori-ented

DS01078A-page 30 © 2007 Microchip Technology Inc.

AMERICASCorporate Office2355 West Chandler Blvd.Chandler, AZ 85224-6199Tel: 480-792-7200 Fax: 480-792-7277Technical Support: http://support.microchip.comWeb Address: www.microchip.comAtlantaDuluth, GA Tel: 678-957-9614 Fax: 678-957-1455BostonWestborough, MA Tel: 774-760-0087 Fax: 774-760-0088ChicagoItasca, IL Tel: 630-285-0071 Fax: 630-285-0075DallasAddison, TX Tel: 972-818-7423 Fax: 972-818-2924DetroitFarmington Hills, MI Tel: 248-538-2250Fax: 248-538-2260KokomoKokomo, IN Tel: 765-864-8360Fax: 765-864-8387Los AngelesMission Viejo, CA Tel: 949-462-9523 Fax: 949-462-9608Santa ClaraSanta Clara, CA Tel: 408-961-6444Fax: 408-961-6445TorontoMississauga, Ontario, CanadaTel: 905-673-0699 Fax: 905-673-6509

ASIA/PACIFICAsia Pacific OfficeSuites 3707-14, 37th FloorTower 6, The GatewayHabour City, KowloonHong KongTel: 852-2401-1200Fax: 852-2401-3431Australia - SydneyTel: 61-2-9868-6733Fax: 61-2-9868-6755China - BeijingTel: 86-10-8528-2100 Fax: 86-10-8528-2104China - ChengduTel: 86-28-8665-5511Fax: 86-28-8665-7889China - FuzhouTel: 86-591-8750-3506 Fax: 86-591-8750-3521China - Hong Kong SARTel: 852-2401-1200 Fax: 852-2401-3431China - QingdaoTel: 86-532-8502-7355Fax: 86-532-8502-7205China - ShanghaiTel: 86-21-5407-5533 Fax: 86-21-5407-5066China - ShenyangTel: 86-24-2334-2829Fax: 86-24-2334-2393China - ShenzhenTel: 86-755-8203-2660 Fax: 86-755-8203-1760China - ShundeTel: 86-757-2839-5507 Fax: 86-757-2839-5571China - WuhanTel: 86-27-5980-5300Fax: 86-27-5980-5118China - XianTel: 86-29-8833-7250Fax: 86-29-8833-7256

ASIA/PACIFICIndia - BangaloreTel: 91-80-4182-8400 Fax: 91-80-4182-8422India - New DelhiTel: 91-11-4160-8631Fax: 91-11-4160-8632India - PuneTel: 91-20-2566-1512Fax: 91-20-2566-1513Japan - YokohamaTel: 81-45-471- 6166 Fax: 81-45-471-6122Korea - GumiTel: 82-54-473-4301Fax: 82-54-473-4302Korea - SeoulTel: 82-2-554-7200Fax: 82-2-558-5932 or 82-2-558-5934Malaysia - PenangTel: 60-4-646-8870Fax: 60-4-646-5086Philippines - ManilaTel: 63-2-634-9065Fax: 63-2-634-9069SingaporeTel: 65-6334-8870Fax: 65-6334-8850Taiwan - Hsin ChuTel: 886-3-572-9526Fax: 886-3-572-6459Taiwan - KaohsiungTel: 886-7-536-4818Fax: 886-7-536-4803Taiwan - TaipeiTel: 886-2-2500-6610 Fax: 886-2-2508-0102Thailand - BangkokTel: 66-2-694-1351Fax: 66-2-694-1350

EUROPEAustria - WelsTel: 43-7242-2244-39Fax: 43-7242-2244-393Denmark - CopenhagenTel: 45-4450-2828 Fax: 45-4485-2829France - ParisTel: 33-1-69-53-63-20 Fax: 33-1-69-30-90-79Germany - MunichTel: 49-89-627-144-0 Fax: 49-89-627-144-44Italy - Milan Tel: 39-0331-742611 Fax: 39-0331-466781Netherlands - DrunenTel: 31-416-690399 Fax: 31-416-690340Spain - MadridTel: 34-91-708-08-90Fax: 34-91-708-08-91UK - WokinghamTel: 44-118-921-5869Fax: 44-118-921-5820

WORLDWIDE SALES AND SERVICE

12/08/06