AN204394 FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution.pdf

THIS SPEC IS OBSOLETE
Spec No:
002-04394
Spec Title:
AN204394 - FM0+ Family, 3-Phase ACIM Scalar Control
with Slip Speed Control Solution
Replaced by:
None
AN204394
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
This application note introduces scalar control of a 3-phase ACIM solution with slip speed control scheme. The slip
speed control scheme is known as an easy constructed, high efficiency, and medium dynamic response control
algorithm.
Contents
1
2
3
4
5
Introduction ...............................................................1
1.1
Document Overview ........................................1
System Hardware Environment ................................2
Development Environment .......................................2
Firmware Introduction ...............................................3
4.1
Firmware Features ...........................................3
4.2
Firmware Architecture ......................................3
Getting Started .........................................................8
1
5.1
Hardware Configuration ................................... 8
5.2
Firmware Configuration ................................... 9
5.3
Debug Slip Speed Control System ................ 11
5.4
Troubleshooting ............................................. 16
6
Reference Documents ............................................ 16
7
Document History ................................................... 17
Introduction
This application note introduces scalar control of a 3-phase ACIM solution with slip speed control scheme. The slip
speed control scheme is known as an easy constructed, high efficiency, and medium dynamic response control
algorithm.
In this document, the slip speed control is realized by capturing rotor speed by hall sensor to form speed close loop
control. Further utilizing one channel ADC to sample DC bus voltage, SVPWM is generated. According to one PI
regulator for voltage control, and one PI regulator for slip speed control, this scheme is realized for full speed range.
To prevent abnormal operations, over/under voltage protection, hall lost/lock rotor protection, and motor lose phase
protection are dedicatedly designed and implemented.
1.1
Document Overview
The rest of this document is organized as below:
Chapter 2 explains System Hardware Environment
Chapter 3 explains Development Environment
Chapter 4 explains Firmware Introduction
Chapter 5 explains Getting Started
Chapter 6 explains Reference Documents
www.cypress.com
Document No. 002-04394Rev.*A
1
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
2
System Hardware Environment
Table 1. Demo System Hardware Environment
Name
Type
Description
Remark
32-bit ARM Cortex-M0+ Core
32 Pins
MCU Series
S6E1A12B0AGP2
Maximum operating frequency: 40MHz
On-chip flash memory: 88 Kbyte
On-chip SRAM: 6 Kbyte
Maximum carrier frequency: 20 kHz
Maximum main supply voltage: 400 V
IPM Module
SCM1559M
Maximum output current (continued): 10 A
Logic supply voltage: 13.5~16.5 V
Minimum dead time: 1.0 us
3
Development Environment
Table 2. Development Environment
Name
Description
Part Number
Manufacturer
Remark
IAR Embedded
Workbench 6.6
Code edit, compile, and online debug
N/A
N/A
N/A
Cypress Flash
Loader
Flash download program
N/A
N/A
N/A
J-Link
IAR connection to target board
N/A
N/A
N/A
Eclipse
Code edit
N/A
N/A
N/A
Windows 7
Enterprise
Operation system (service pack 1, 64bit)
N/A
N/A
N/A
www.cypress.com
Document No. 002-04394Rev.*A
2
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
4
Firmware Introduction
4.1
Firmware Features
Table 3. Firmware Features
No.
4.2
Feature
Description
1
Slip speed control
ACIM is controlled with optimized efficiency with slip speed
controller.
2
Braking function
Braking down motor with no additional hardware.
3
Field weakening control
Speed range of motor is extended by slip speed regulation.
4
Bi-direction rotation
Both clockwise and counter-clockwise rotations are OK.
5
Over current protection
Hardware over current protection. (Software protection is available
if current sensor is implemented)
6
Voltage protection
Irregular HIGH/LOW voltage protection, normal over/under voltage
protection.
7
Hall lost/Lock rotor protection
Prevent long time operation in no speed signal case.
8
Phase lose protection
Motor phase lose case will be protected.
9
Variable carrier frequency
Maximum 16kHz
10
UART communication
UART communication with host machine
11
OOB function
Out-of balance for washing machine application
12
Weighting function
Weight measurement for washing machine application
Remark
Speed
sensor is
required.
Firmware Architecture
Figure 1. Overview of Firmware File System
www.cypress.com
Document No. 002-04394Rev.*A
3
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
4.2.1
Firmware Execution Flow
Figure 2 shows the execution flow of firmware that controls an ACIM by slip speed controller.
In main function, after MCU and control system are initialized, a while loop is executed that starts/stops motor
according to user command speed. In another hand, UART communication and timer event are processed for user
defined operations.
In normal control occasion, three main interrupt routines are executed. FRT zero interrupt occurs at a frequency
named carries frequency, and once FRT interrupt happens, an ADC interrupt is triggered to sample DC bus voltage
and current. After AD sample, motor control is executed in FRT interrupt routine, with the knowledge of sampled
voltage and rotor speed. Another interrupt is triggered by Hall signal to capture rotor speed, and both the falling edge
and rising edge are captured to calculate rotor speed.
In abnormal ISR routines, a DTTI interrupt is triggered by a fault signal from IPM, and activates hardware over current
protection and immediately stop the motor. The WDT(watch dog timer) interrupt is triggered by both hardware and
software WDT, and once this interrupt is triggered, motor will be stopped immediately.
Figure 3 shows the block diagram of slip speed control system. For more information of slip speed control, please
refer to S6E1A1_AN710-00001-1v0-E-3Phase_ACIM_Scalar_Control.pdf.
www.cypress.com
Document No. 002-04394Rev.*A
4
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Figure 2. Firmware Execution Flow
Main function entrance
Initialize MCU
Initialize control
Main Loop
Abnormal ISR Routines
Start/Stop motor control
UART communication
Timer event
1. Speed set
2. Protection
3. Parameter tuning
DTTI ISR
Stop motor
WDT ISR
Stop motor
Normal ISR Routines
Trig ADC sample
BT ISR
Speed calculate
Rotor
speed
FRT ISR
ADC ISR
Return sample
1. Vbus Sample
2. Ibus Sample
Motor Control
1. Voltage regulate
2. Slip regulate
3. Brake control
4. SVPWM generate
www.cypress.com
Document No. 002-04394Rev.*A
5
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Figure 3. Block Diagram of Slip Speed Control System
π‘‰π‘žβˆ— = 0
πœ”π‘Ÿβˆ— +
πœ”π‘Ÿ
-
Inv.
Park
π‘‰π‘‘βˆ—
PI
πœƒπ‘’
π‘€π‘Žπ‘₯ π‘‰π‘‘βˆ—
PI
πœ”π‘ βˆ—
+
πœ”π‘ π‘ π‘’π‘‘
1
𝑠
+
Enable/disable
field weakening
4.2.2
PWM
πœ”π‘Ÿ
ACIM
Files Description
Figure 4. Firmware Layers Introduction
User
Layer
User interface
Main program entrance
Interrupt vectors
App Layer
AcimSlipCtrl
Brake
Hall Speed Detect
Speed Set
Protection
A/D Sample
InitMcu
Isr
OOB
Weight
Timer Event
UART
Crc
Module Layer
Equivalent Transformation
Math
Filter
PI Regulator
SVPWM
Drive Layer
Global Layer
www.cypress.com
Document No. 002-04394Rev.*A
6
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Table 4. Source Files Description
Layer
Files
Description
interrupts.c
S01_global
pdl.c
MCU related files.
system_s6e1a1.c
adc.c
bt.c
hwwdg.c
mft_adcmp.c
S02_driver
MCU drivers.
mft_frt.c
mft_ocu.c
mft_wfg.c
swwdg.c
EquivalentTransformation.c
Filter.c
Math.c
S03_module
Basic functions for motor control.
Pid.c
PidReg_cm0_64bit.asm
Scpwm_cm0.asm
AdcSample.c
ADC sample parameter initialization and offset check.
Brake.c
Braking function of ACIM.
crc.c
crc check for UART communication
HallSpeedDetect.c
Hall speed detection called in BT ISR for speed measurement.
InitMcu.c
Initialize MCU peripherals.
Isr.c
ISR interrupt entrance.
MotorCtrl.c
Motor control files, including initialization, startup motor, stop motor,
and FRT routine called by FRT ISR.
OOB.c
OOB function of washing machine.
Protection.c
Protection functions, including voltage protection, Hall lost/Lock rotor
protection, and lose phase protection
SpeedSet.c
Command and target speed set functions.
TimerEvent.c
Timer triggered functions, including speed set, protection, and
parameter self-adjustment.
UART.c
UART communication
Weight.c
Weight measure of washing machine
Main.c
main function
startup_s6xxxx.s
Vector table of target MCU.
CustomerInterface.c
Customer interface for parameter configuration.
S04_app
S05_user
The firmware consists with five layers, and each layer places header files and source files separately. Figure 4
shows the functions of each layer, and Table 4 describes the details.
www.cypress.com
Document No. 002-04394Rev.*A
7
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5
Getting Started
5.1
Hardware Configuration
Figure 5. Top View of Demo PCB
Motor Temperature
Protection Port
L
N
U
V
W
Hall Sensor
UART
J-Link
Figure 5 shows the top view of demo PCB. First connect motor cables and motor temperature protection port. If there
is no temperature port, short this port. Insert J-Link wire, and connect AC cables. Now the PCB is ready for your
debug.
If your hardware is different from demo PCB, please configure your hardware infomation in
H05_user\HardwareConfig.c.For further information of your hardware, please find H04_user\InitMcu.cto adapt your
hardware.
Figure 6. Hardware Information Configuration
#define
#define
#define
#define
ADC_VOLT_REF
ADC_VALUE_MAX
VDC_FACTOR
ADC_CH_VDC
5.0f
4096.0f
93.3
2
//reference voltage of ADC sample
//4096 for 12bit ADC
//gain of DC bus voltage samplling
//ADC channel of DC bus voltage
#define ADC_CH_I_BUS
1
//ADC channel of DC bus current
#define ADC_I_BUS_FACTOR
15.6
// gain of DC bus current sampling
#define ADC_I_BUS_BIAS
2048
// bias of DC bus current sampling
// configure hall I/O and Pin
#define USER_BT_TIMER_SIZE
PwcSize16Bit; //base timer PWC size
#define HALL_A_TIMER_LOW_CH FM0P_BT0_PWC //base timer unit for hall speed
/** UART Select */
#define FM0P_MFSx_UART
FM0P_MFS3_UART //MFS unit for UART communication
www.cypress.com
Document No. 002-04394Rev.*A
8
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5.2
Firmware Configuration
Before startup your motor, please configure your control target to make sure motor is operated correctly. You can find
firmware configuration parameters in S05_user\CustomerInterface.c.
5.2.1
B a s i c D r i ve P a r a m e t e r s
//
// carrier frequency and dead time
//
uint16_t
MotorCtrl_u16CarrierFreq
float32_t
MotorCtrl_f32DeadTimeUs
uint32_t
RelayDelayOnTms
switched
= 16000;
= 2.0f;
= 2000;
// carrier frequency (Hz)
// Dead timer us
// the time delay for relay
//on,unit:ms
First of all, select your carrier frequency and dead time for motor drive. Set a time delay for relay open when system
power is on.
5.2.2
Motor Parameters
//
// motor parameters
//
int32_t
MotorCtrl_i32PolePairs
float32_t
Motor_f32TransRate
float32_t
MotorCtrl_f32MaxVf
int32_t
MotorCtrl_i32RpmMin
int32_t
MotorCtrl_i32RpmMax
5.2.3
=
=
=
=
=
2;
11.6;
3.0;
30;
1200;
//
//
//
//
//
pole pairs
TransRate of motor
maximum V/f ratio
minimum speed
maximum speed
Hall Sensor Parameters
//
// hall speed sensor
//
uint32_t
MotorCtrl_u32EdgesPerCycle
float32_t
MotorCtrl_f32BaseTimerClkMHz
= 16;// hall edges per motor cycle
= 10.0;// Base timer clock
In this firmware, motor speed is measured from a hall sensor, and captured by base timer. The base timer captures
both the falling edge and rising edge of hall signal. For example:
Your hall sensor returns 8 pulses per mechanical cycle, then you have 8 falling edges and 8 rising edges, therefore
16 edges per cycle is set.
www.cypress.com
Document No. 002-04394Rev.*A
9
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5.2.4
Startup Parameters
//
// motor start-up settings
//
int32_t
MotorCtrl_i32StartRpm1
int32_t
MotorCtrl_i32StartRpm2
float32_t
MotorCtrl_f32StartWsHz
int32_t
MotorCtrl_i32StartAccRpmPerSec
=
=
=
=
100;
400;
8.0;
1500;
The startup process applies slip speed curve for large startup torque. This section defines the transition point at
startup as well as speed acceleration rate.
5.2.5
Normal Running Parameters
//
// motor normal running settings
//
float32_t
MotorCtrl_f32MinWsHz
float32_t
MotorCtrl_f32MaxWsHz
= 2.8; // (Hz) nominal slip speed
= 18.0; // (Hz) maximum slip speed
The normal running operation requires two slip speeds. One is for low speed and medium speed region that applies
MTPA control, named as minimum slip speed. Another is for field weakening control, which defines the maximum slip
speed allowed in field weakening region.
5.2.6
Braking Parameters
//
// motor brake settings
//
float32_t
MotorCtrl_f32FreeBrakeVsRamp
float32_t
MotorCtrl_f32ForceBrakeVs
float32_t
MotorCtrl_f32ForceBrakeVsRamp
= 25.0;
= 19.0;
= 200.0;
// Volt/second
// Volt
// Volt/second
The braking process has two steps. First when motor is under AC excitation, stator voltage will decrease to zero with
voltage ramp defined by MotorCtrl_f32FreeBrakeVsRamp. If force brake is enabled in braking process, a DC
voltage with amplitude MotorCtrl_f32ForceBrakeVs will be imposed on stator, and the rising ramp of this voltage
is defined by MotorCtrl_f32ForceBrakeVsRamp.
5.2.7
Field Weakening Parameters
//
// field weakening control
//
float32_tMotorCtrl_f32FwUpperVsK
float32_t
MotorCtrl_f32FwLowerVsK
= 0.97;
= 0.91;
Two voltage ratio of maximum output voltage is defined for field weakening control, 0.90~0.99 are recommended for
these two values.
www.cypress.com
Document No. 002-04394Rev.*A
10
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5.2.8
PI Parameters
//
// PI parameters
//
float32_t
MotorCtrl_f32SpdRegTimeMs
// voltage PI regulator
int32_t
MotorCtrl_i32LowSpdRpm
int32_t
MotorCtrl_i32HighSpdRpm
float32_t
MotorCtrl_f32LowSpdVsKp
float32_t
MotorCtrl_f32LowSpdVsKi
float32_t
float32_t
MotorCtrl_f32HighSpdVsKp
MotorCtrl_f32HighSpdVsKi
// slip speed PI regulator
float32_t
MotorCtrl_f32WsKp
float32_t
MotorCtrl_f32WsKi
5.2.9
= 0.6;
=
=
=
=
// speed regulation cycle (ms)
1600;// low speed transition speed
3000;// high speed transition speed
2.5;// low speed Kp of voltage PI
6;// low speed Ki of voltage PI
= 0.5;// high speed Kp of voltage PI
= 1.0;// high speed Kpof voltage PI
= 0;// Kp of slip speed PI for field weaken
= 1;// Ki of slip speed PI for field weaken
Protection Parameters
//
// protections
//
int32_t
int32_t
MotorCtrl_i32OverVoltage
MotorCtrl_i32UnderVoltage
= 360;
= 200;
// over voltage threshold
// under voltage threshold
int32_t
int32_t
MotorCtrl_i32IrreHighVoltage = 390;// irregular high voltage limit
MotorCtrl_i32IrreLowVoltage = 100;
// irregular low voltage limit
In this firmware, over current protection is done by hardware, thus you only need to configure voltage protection in
customer interface. There are two limits for both over voltage and under voltage protection. The irregular high voltage
and irregular low voltage take a shorter time to trigger a protection than normal over voltage and under voltage.
5.3
Debug Slip Speed Control System
5.3.1
Check Your Hardware
Figure 7. Live Watch of IAR System
4
5
3
2
1
www.cypress.com
Document No. 002-04394Rev.*A
11
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
After first time burning the firmware into hardware, check below items to make sure both your hardware and firmware
are correctly configured:
5.3.2
1.
Check item 1 in Figure 7. If fault code is 0x0000, no error code is detected. Otherwise refer to Figure 8 to fix the
problem.
2.
Check item 2 in Figure 7. This item is DC bus voltage. If this value is in your expectation, then DC bus sample is
OK. Otherwise check your ADC configuration and sample parameters.
3.
Check item 3 in Figure 7.This item is rotor speed measured by Base Timer. In standstill case, this value should
be zero. Rotate your motor, and keep watching this value, it becomes a non-zero integer when motor is rotating.
If this value keeps being zero, check your Hall sensor and Base Timer configuration.
Startup Your Motor
Once the hardware and firmware are properly configured, you are ready to rotate your motor.
Input a speed into item 4 in Figure 7, this is command speed. At first time, run the motor in low speed region, and
check whether the parameters are proper for your motor.
You might confront below problems:
1.
Fault Code: 0x0008
This means hardware over current protection is triggered. This is probably due to that a large V/f ratio caused over
current protection; you can smaller the maximum V/f ratio as 5.2.2 described. Otherwise, check your hardware that
whether you have set a too low value to hardware over current protection.
2.
Fault Code: 0x0400
This is lock rotor protection or hall lost protection. Double confirm motor can be freely rotates, and hall sensor are
correctly configured. Otherwise, refer to next problem.
3.
Motor does not rotate with non-zero command speed
If current appears but motor never rotates. This is probably that the maximum V/f ratio is too small to startup the
motor; you can enlarge the maximum V/f ratio as 5.2.2 described.
5.3.3
Tuning PI Parameters
Find the PI parameter for voltage regulation as Figure 8 shows. Tune the PI parameters such that both the dynamics
and stability satisfies your requirement. Figure 9 shows the auto tuning process of Kp according to target speed, and
Ki shares the same adjustment pattern.
Figure 8. Voltage PI Regulation Parameters
www.cypress.com
Document No. 002-04394Rev.*A
12
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Figure 9. Auto-Tuning of Kp According to Target Speed
i32Q15_Kp
i32Q15_LowSpdKp
i32Q15_HighSpdKp
TgtRPM
i32LowSpdRpm
5.3.4
i32HighSpdRpm
Tuning Slip Speed
The slip speed is the key factor to optimized power consumption operation. The theoretical optimal slip speed is
calculated as
πœ”π‘  =
π‘…π‘Ÿ
πΏπ‘Ÿ
This means that the optimal slip speed equals to the inverse of rotor time constant. Now drive the motor in a proper
speed stably (no disturbance is preferred). Be aware that speed should not be too slow (or efficiency is quite low) or
too high (otherwise field weakening is introduced). Find the minimum slip speed in live watch window
Tune the parameter and observe phase current or input power. The optimized slips speed is found when minimum
current or power is achieved. Record this slip speed and use this slip speed for your further application.
Figure 10 shows the current waveform of motor at 580 RPM with different slip speed. Apparently, the target motor
runs under slip speed equals to 2.8Hz approached a better efficiency.
Figure 10. 580 RPM with Different Slip Speed
a.
www.cypress.com
πœ”π‘  = 5.0 Hz
Document No. 002-04394Rev.*A
13
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
b.
5.3.5
πœ”π‘  = 2.8 Hz
Tuning High Speed Region
The high speed region involves field weakening control. Due to the lack of current close-loop control, you are going to
tuning below parameters to achieve a proper performance. Table 5 shows each parameter that relates to field
weakening control.
Table 5. High Speed Region Tuning Parameters
Parameter
Customer Interface Variable
Description
Slip_stcWsPid.i32Q15_Kp
MotorCtrl_f32WsKp
Kp of slip speed PI regulator
Slip_stcWsPid.i32Q15_Ki
MotorCtrl_f32WsKi
Ki of slip speed PI regulator
Slip_stcSlipCtrl.i32Q8_LowerVsK
MotorCtrl_f32FwLowerVsK
Lower voltage threshold for field weakening control.
Tuning target:
1. Field weakening is fluent and stably exited.
Upper voltage threshold for field weakening control.
Tuning target:
Slip_stcSlipCtrl.i32Q8_UpperVsK
MotorCtrl_f32FwUpperVsK
1. Field weakening enters fluently
2. Field weakening is effectively extending speed
range.
Maximum allowed slip speed for field weakening
control. Tuning target::
Slip_stcSlipCtrl.i32Q8_MaxWsHz
MotorCtrl_f32MaxWsHz
1. Speed range is extended
2. Current range is within rated value with slip speed
equals to this value.
www.cypress.com
Document No. 002-04394Rev.*A
14
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5.3.6
Tuning the Braking Function
Figure 11 shows the command voltage in braking process. Three parameters are to be tuned for this function.
1.
MotorCtrl_f32FreeBrakeVsRamp
This is a voltage ramp in unit V/s that decreases the amplitude of AC voltage. Tune this ramp such that the DC bus
voltage does not boost too much and the decreasing process as short as possible.
2.
MotorCtrl_f32ForceBrakeVsRamp
This is a voltage ramp in unit V/s that increases a DC voltage imposed to stator. Choose a proper one that current
reaches to its stable point quickly with small overshoot.
3.
MotorCtrl_f32ForceBrakeVs
This is the braking DC voltage imposed on stator. Choose a proper voltage that rotor brakes fast and current
amplitude is within the rated range is OK.
Figure 12 shows a typical braking process with force braking. Channel 2 is stator current, channel 3 is DC bus
voltage, and channel 4 is hall signal.
Figure 11. Command Voltage in Braking Process
𝑉𝑠
MotorCtrl_f32FreeBrakeVsRamp
MotorCtrl_f32ForceBrakeVsRamp
MotorCtrl_f32ForceBrakeVs
t
start brake
πœ”π‘Ÿ = π‘‡π‘Žπ‘Ÿπ‘”π‘’π‘‘ πœ”π‘Ÿ
Figure 12. A Typical Braking Process
www.cypress.com
Document No. 002-04394Rev.*A
15
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
5.4
Troubleshooting
For other unstated fault case, please refer to fault code in Figure 13 to fix problems.
Figure 13. Fault Code of Slip Speed Control System
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
#define
6
7
NORMAL_RUNNING
AD_MIDDLE_ERROR
SW_OVER_CURRENT
SINK_ERR
MOTOR_OVER_CURRENT
OVER_VOLTAGE
UNDER_VOLTAGE
POWER_OVER
IPM_TEMPOVER
MOTOR_TEMPOVER
MOTOR_LOSE_PHASE
MOTOR_LOCK
DCBUS_ERR
COMM_ERROR
SF_WTD_RESET
HW_WTD_RESET
UNDEFINED_INT
0x0000
0x0001
0x0002
0x0004
0x0008
0x0010
0x0020
0x0040
0x0080
0x0100
0x0200
0x0400
0x0800
0x1000
0x2000
0x4000
0x8000
//no error
//current sample 2.5V offset error
//over-current of FW
//IPM circuit fault
//over-current of HW
//DC bus over-voltage
//DC bus under-voltage
//motor over-power
//IPM temperature error
// motor over temperature
//motor lose phase
//motor lock
// dc bus voltage error
//communicate error code
//FW watch dog reset
//HW watch dog reset
//undefined interrupt
Reference Documents
1.
FM0+ S6E1A1 Series Data Sheet, Revision 0.1, 2013
2.
FM0+ Family Peripheral Manual, Revision 1.0, 2014
3.
FM0+ Family Timer Part Peripheral Manual, Revision 1.0, 2014
4.
FM0+ Family Analog Macro Part Peripheral Manual, Revision 1.0, 2014
5.
P. C. Krause, O. Wasynczuk, and S. D. Sudhoff, Electric Machinery and Drive Systems. IEEE Press, 2002
Additional Information
For more Information on Cypress semiconductor products, visit the following websites:
http://www.cypress.com/cypress-microcontrollers
www.cypress.com
Document No. 002-04394Rev.*A
16
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
8
Document History
Document Title: AN204394 - FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Document Number: 002-04394
Revision
ECN
Orig. of
Change
Submission
Date
Description of Change
**
-
CBZH
06/15/2015
Initial release
*A
5100364
CBZH
06/16/2016
Migrated Spansion Application Note AN710-00009-1v0-E to Cypress
format.
There is no web link for the reader to get the PCB (evaluation board),
So this AN is for obsolete.
www.cypress.com
Document No. 002-04394Rev.*A
17
FM0+ Family, 3-Phase ACIM Scalar Control with Slip Speed Control Solution
Worldwide Sales and Design Support
Cypress maintains a worldwide network of offices, solution centers, manufacturer’s representatives, and distributors. To find
the office closest to you, visit us at Cypress Locations.
PSoC® Solutions
Products
®
®
ARM Cortex Microcontrollers
cypress.com/arm
PSoC 1 | PSoC 3 | PSoC 4 | PSoC 5LP
Automotive
cypress.com/automotive
Cypress Developer Community
Clocks & Buffers
cypress.com/clocks
Interface
cypress.com/interface
Lighting & Power Control
cypress.com/powerpsoc
Memory
cypress.com/memory
PSoC
cypress.com/psoc
Touch Sensing
cypress.com/touch
USB Controllers
cypress.com/usb
Wireless/RF
cypress.com/wireless
Forums | Projects | Videos | Blogs | Training | Components
Technical Support
cypress.com/support
PSoC is a registered trademark and PSoC Creator is a trademark of Cypress Semiconductor Corporation. All other trademarks or registered trademarks
referenced herein are the property of their respective owners
Cypress Semiconductor
198 Champion Court
San Jose, CA 95134-1709
Phone
Fax
Website
: 408-943-2600
: 408-943-4730
: www.cypress.com
© Cypress Semiconductor Corporation, 2015-2016. This document is the property of Cypress Semiconductor Corporation and its subsidiaries, including
Spansion LLC (β€œCypress”). This document, including any software or firmware included or referenced in this document (β€œSoftware”), is owned by
Cypress under the intellectual property laws and treaties of the United States and other countries worldwide. Cypress reserves all rights under such
laws and treaties and does not, except as specifically stated in this paragraph, grant any license under its patents, copyrights, trademarks, or other
intellectual property rights. If the Software is not accompanied by a license agreement and you do not otherwise have a written agreement with
Cypress governing the use of the Software, then Cypress hereby grants you a personal, non-exclusive, nontransferable license (without the right to
sublicense) (1) under its copyright rights in the Software (a) for Software provided in source code form, to modify and reproduce the Software solely for
use with Cypress hardware products, only internally within your organization, and (b) to distribute the Software in binary code form externally to end
users (either directly or indirectly through resellers and distributors), solely for use on Cypress hardware product units, and (2) under those claims of
Cypress’s patents that are infringed by the Software (as provided by Cypress, unmodified) to make, use, distribute, and import the Software solely for
use with Cypress hardware products. Any other use, reproduction, modification, translation, or compilation of the Software is prohibited.
TO THE EXTENT PERMITTED BY APPLICABLE LAW, CYPRESS MAKES NO WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, WITH REGARD
TO THIS DOCUMENT OR ANY SOFTWARE OR ACCOMPANYING HARDWARE, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. To the extent permitted by applicable law, Cypress reserves the right to
make changes to this document without further notice. Cypress does not assume any liability arising out of the application or use of any product or
circuit described in this document. Any information provided in this document, including any sample design information or programming code, is
provided only for reference purposes. It is the responsibility of the user of this document to properly design, program, and test the functionality and
safety of any application made of this information and any resulting product. Cypress products are not designed, intended, or authorized for use as
critical components in systems designed or intended for the operation of weapons, weapons systems, nuclear installations, life-support devices or
systems, other medical devices or systems (including resuscitation equipment and surgical implants), pollution control or hazardous substances
management, or other uses where the failure of the device or system could cause personal injury, death, or property damage (β€œUnintended Uses”). A
critical component is any component of a device or system whose failure to perform can be reasonably expected to cause the failure of the device or
system, or to affect its safety or effectiveness. Cypress is not liable, in whole or in part, and you shall and hereby do release Cypress from any claim,
damage, or other liability arising from or related to all Unintended Uses of Cypress products. You shall indemnify and hold Cypress harmless from and
against all claims, costs, damages, and other liabilities, including claims for personal injury or death, arising from or related to any Unintended Uses of
Cypress products.
Cypress, the Cypress logo, Spansion, the Spansion logo, and combinations thereof, PSoC, CapSense, EZ-USB, F-RAM, and Traveo are trademarks or
registered trademarks of Cypress in the United States and other countries. For a more complete list of Cypress trademarks, visit cypress.com. Other
names and brands may be claimed as property of their respective owners.
www.cypress.com
Document No. 002-04394Rev.*A
18