AN3998 Sensorless BLDC MC AVR MCU Fam DS00003998
AN3998 Sensorless BLDC MC AVR MCU Fam DS00003998
AN3998 Sensorless BLDC MC AVR MCU Fam DS00003998
Introduction
Authors: Alexandru Zîrnea, Leona Pop, Microchip Technology Inc.
This application note describes a sensorless Brushless Direct Current (BLDC) motor control method using a Plug-In
Module (PIM) based on the AVR128DA48 or AVR128DB48 microcontrollers from the AVR® DA and AVR DB families.
The first part of the document focuses on the motor control theory from which the software implementation is
derived. It describes the sensored and sensorless control methods, details about trapezoidal commutation, and other
important information about how to drive the motor.
The second part is dedicated to the software and hardware implementation of the system.
The example application uses the AVR128DA48 or the AVR128DB48-based PIM connected to a dsPICDEM™
MCLV-2 Development Board (Motor Control Low-Voltage) (MCLV-2). The MCLV-2 board offers a potentiometer for
adjusting the speed of rotation, while the input protection and Back Electromotive Force (BEMF) circuitry are found
on the PIM.
The system is capable of regenerative braking, which is inherent to the driving method used.
The driving waveforms for the motor are generated independently from the core, using the hardware capabilities of
the microcontroller’s peripherals.
Additionally, the application employs several protection mechanisms such as stall detection, false input detection, and
overcurrent protection in both directions.
The system can drive a wide range of BLDC motors with an adequate tuning of the firmware. Guidelines for tuning
the parameters needed for different types of motors are outlined at the end of the document.
BLDC motors are used in a wide range of applications such as cordless power tools, computers, hard drives,
multimedia equipment, cooling fans in small electronic equipment, electric vehicles and are a growing market for the
electric future. The presented solution creates a cost-effective motor driver by using an 8-bit microcontroller when
traditionally, only 16-bit microcontrollers or more were used in creating this device.
Table of Contents
Introduction.....................................................................................................................................................1
1. Overview................................................................................................................................................. 3
2. Relevant Devices.................................................................................................................................... 4
4. Firmware Implementation......................................................................................................................14
6. Tuning................................................................................................................................................... 34
7. Conclusion............................................................................................................................................ 37
8. References............................................................................................................................................38
9. Revision History.................................................................................................................................... 39
Customer Support........................................................................................................................................ 40
Legal Notice................................................................................................................................................. 41
Trademarks.................................................................................................................................................. 41
1. Overview
This application note presents the motor control theory needed to drive a BLDC motor and contains a comparison
between the sensored and sensorless motor control, a typical implementation of a power stage, modulation
techniques as well as a detailed description of the custom PIM.
Moreover, the document covers a detailed presentation of bipolar switching, which is the focus of this example.
To obtain the position of the rotor, the zero-cross point detection method is covered, using a comparator with a
variable voltage reference consisting of a virtual neutral of the motor.
The motor starts at an initial position after an alignment routine. This is done so that at start-up the motor follows the
generated open-loop waveform.
At compile-time, the user can select the mode the motor must run in, open- or closed-loop.
A potentiometer on the MCLV-2 board provides a value read by the ADC that is used to compute a duty reference
for the waveform timer, and this reading, along with the current, is done asynchronously from the motor logic drive of
the software. This part runs in the main loop, while the motor control runs on interrupts to get the best response time
possible.
At the end of this document, the user can find a brief introduction to tuning the parameters of the firmware to obtain
the desired results.
This application example uses the following peripherals:
• Analog Comparator (AC)
• Analog-to-Digital Converter (ADC)
• I/O Pin Controller (PORT)
• Timer/Counter Type A (TCA)
• Timer/Counter Type B (TCB)
• Timer/Counter Type D (TCD)
• Custom Configurable Logic (CCL)
• Voltage Reference (VREF)
• Universal Synchronous Asynchronous Receiver Transmitter (USART)
Prerequisites:
1. Software:
– Microchip Studio 7 Integrated Development Environment (IDE) with AVR DX Device Family Pack (DFP
1.7.85 or newer)
2. Hardware:
– AVR128DA48 Motor Control PIM or AVR128DB48 Motor Control PIM with internal op amp configuration
board
– dsPICDEM™ MCLV-2 Development Board (Motor Control Low-Voltage)
– AC300020 - 24V 3-Phase Brushless DC Motor
– AC002013 - 24V Power Supply
– MPLAB® PICkit™ 4 In-Circuit Debugger
The MCLV-2 Development Board is targeted to control either a brushless motor or a permanent magnet synchronous
motor in sensored or sensorless operation. In this demo, it will be used in conjunction with the AVR128DA48 or
AVR128DB48 Motor Control PIMs to drive a brushless motor in sensorless operation. The board offers a driver for
the three phases, a way to measure feedback signals, and an on-board op amp. An additional configuration board is
used with the AVR128DB48 PIM because the internal operational amplifier signals are routed differently.
This demo will use some other features of the MCLV-2 board like the programming interface and the serial interface
to receive information about the working parameters of the motor. Additionally, there are LEDs, buttons and a
potentiometer on the board that provide a user interface to show which PWM outputs are active, to set the direction
of the motor and to start and stop it, and to change the speed of the motor.
2. Relevant Devices
This section lists the relevant devices for this document. The following figures show the different family devices,
laying out pin count variants and memory sizes:
• Vertical migration upwards is possible without code modification, as these devices are pin-compatible and
provide the same or more features
• Horizontal migration to the left reduces the pin count and, therefore, the available features
• Devices with different Flash memory sizes typically also have different SRAM and EEPROM
Figure 2-1. AVR® DA Family Overview
Flash
Pins
28 32 48 64
Flash
Pins
28 32 48 64
Step 1: Step 4
• Red winding is driven positive • Green winding is driven positive
• Green winding is driven negative • Red winding is driven negative
• Blue winding is not driven • Blue winding is not driven
Step 2: Step 5:
• Red winding is driven positive • Blue winding is driven positive
• Blue winding is driven negative • Red winding is driven negative
• Green winding is not driven • Green winding is not driven
Step 3: Step 6:
• Green winding is driven positive • Blue winding is driven positive
• Blue winding is driven negative • Green winding is driven negative
• Red winding is not driven • Red winding is not driven
At constant speed, or for small speed variations, the period between two commutations is equal. This is the
estimation for controlling the motor in Closed Loop.
This implementation uses trapezoidal commutation due to its simplicity and ability to be very easily implemented in
8-bit microcontrollers, as it needs little memory resources and processing power.
AH BH CH
A
B C
AL BL CL
GND
The AH, BH and CH represent the high-side command signals from the microcontroller, while AL, BL and CL
represent the low-side signals.
In addition to the power transistors, MOSFET/IGBT drivers are used to ensure good rise and fall times and provide
the gate voltage needed for the high-side and low-side transistors.
A combinational logic circuit is used to avoid shoot-through by adding dead time between the high-side and low-side
command signals.
This dead time ensures the MOSFETs or IGBTs on the same branch are completely turned off and do not conduct
current at the same time.
VBUS /2
Electrical degrees
VBUS
AH BH CH
A
B C
AL BL CL
GND
The complementary state of AH-BL will be AL-BH and the current will flow in this way. See Figure 3-5 below.
Figure 3-5. Current Flow During AL-BH State
VBUS
AH BH CH
A
B C
AL BL CL
GND
Considering zero speed at 0% duty cycle for unipolar drive, in this case, the zero speed is at 50% duty cycle, where
the complementary state time is equal to the characteristic state.
This method has the advantage of a very clean BEMF because all the voltage induced in the floating phase is
canceled by the complementary state, thus, obtaining a waveform that will contain only high-frequency spikes, which
can be filtered using an RC filter with a very small time constant.
The main disadvantage of this method is that the motor emits more electromagnetic and acoustic noise and
increases the overall system loss due to another transistor pair needed to switch.
The voltage on one phase can be seen in Figure 3-6.
Figure 3-6. Bipolar Switching Phase Voltage (75% Duty Cycle)
VBUS /2
The high-frequency spikes appear at the transition between the characteristic state and the complementary
state. These can be observed in low-inductance motors where the amplitude of the spikes gets higher near the
commutation zones.
Figure 3-7. BEMF Noise on Low-Inductance Motor
In Figure 3-7, the first three waveforms represent the PWM signals for the three phases of the motor while the fourth
waveform represents the sensed current through the transistors.
To avoid shoot-through, dead time will be added between the command signals of the drivers.
Dead time
HIGH
Characteristic
LOW
HIGH
Complementary
LOW
Period
A dead time of approximately 42 ns was added (one clock cycle of the PWM timer), and the result can be seen in
Figure 3-9. However, it is recommended to have a higher dead time if the power MOSFETs/IGBTs have high gate
capacitance.
Figure 3-9. Motor Waveform Close-Up
In Figure 3-9, the first three waveforms represent the PWM signal for the three phases while the fourth waveform is
the sensed current through the transistors. The small spikes in the current waveform correspond to the transistors
switching and represent a small amount of shoot-through. If no dead time was added, then the current would rise
considerably and the transistors will warm up and burn up.
Switching Noise
Similar to unipolar switching, bipolar switching suffers from a specific problem: During commutation, when the motor
has a certain amount of load applied to it, there will be a demagnetization sequence that will influence the detection
of the zero-cross and potentially give a false input, which, in turn, will get the motor out of sync.
This can be particularly challenging as the demagnetization sequence can almost get to 30 electrical degrees, which
will, in turn, limit the area in which the zero cross point can be detected, and potentially suppress it.
The solution to this behavior is to add a blanking time, during which the zero cross is ignored completely. This
parameter will be dynamically set in the control algorithm and self-adapt during the entire range of RPM.
Regenerative Braking
A brushless motor can run in four different regions. These regions are called ‘quadrants’ and are described in Figure
3-10.
Figure 3-10. Four Quadrant Operation
Speed
II I
0 Torque
VBUS > BEMF VBUS < BEMF
III IV
For this application note, only quadrant numbers one and two are of interest and the motor can run in either one,
without the specific intervention of the control algorithm.
In quadrant one, the motor draws current from the bus and is free-running or has a load applied to it. The measured
speed of the rotor is equal to or less than the set speed.
On the other side, in quadrant number two, the set speed of the motor is lower than the measured speed due to
system inertia or other external forces.
The two-quadrant operation is directly related to the duty cycle, which will impose a specific RPM, given in the
equation below.
RPM = Kv × U, where Kv is a parameter of the motor and U is the voltage applied to the coils.
The following concepts: RPMSET and RPMMEASURED provide information about the current RPM of the motor and the
set RPM at any given time.
It is, thus, necessary to express the difference in the RPM with the formula:
ΔRPM = RPMSET − RPMMEASURED
If ΔRPM is greater than zero, then the motor is in quadrant one and draws current from the power supply.
Otherwise, if ΔRPM is less than zero, the motor is in quadrant two and pushes current to the power supply.
This is a rough approximation of how the motor behaves and does not account for variables such as friction losses or
load.
In quadrant two, the system behaves like a boost converter and the maximum current that can be generated depends
on the parameters of the motor, as well as the ΔRPM mentioned earlier and the ESR of the battery.
An equivalent circuit can be obtained for the motor:
The coil resistance and inductance are static throughout the RPM range but the BEMF is directly proportional to the
RPM: BEMF = RPM/Kv. The BEMF amplitude is equal to the supply voltage multiplied by the PWM duty factor (for
bipolar operation, 50% duty means 0V). If the motor does not have any load, the BEMF amplitude will approach the
supply voltage at the full duty cycle.
To protect the system and the power supply from an Overvoltage condition, additional circuitry is needed to monitor
the voltage on the bus.
Figure 3-12. Phase Voltages and Command Signals of Bipolar Switching
VBUS
PHASE A VBUS/2
0
V
Deg
VBUS
PHASE B VBUS/2
0
V
Deg
VBUS
PHASE C VBUS/2
0 Deg
HIGH
AH
LOW Deg
HIGH
AL
LOW Deg
HIGH
BH
LOW Deg
HIGH
BL
LOW Deg
HIGH
CH
LOW Deg
HIGH
CL
LOW Deg
The neutral voltage can be expressed as Vn = BEMF A + BEMF B + BEMF C , where Vn is the virtual neutral voltage,
3
BEMF A is the BEMF voltage in phase A, BEMF B is the BEMF in phase B, and BEMF C is the voltage in phase C.
Due to the asymmetry in the coil impedance, the virtual neutral signal will not be constant, but one that will vary
based on the driving cycle. To avoid any phase shifts in the commutation point, the virtual neutral point must not be
heavily filtered. Only high-frequency noise must be suppressed with a low RC time constant low-pass filters.
The irregularity of the virtual ground can be seen in Figure 3-14, where the first three waveforms represent the PWM
signal for each of the three phases and the fourth waveform is the virtual ground.
Figure 3-14. Virtual Ground Waveform
4. Firmware Implementation
This section presents the use of the internal AVR peripherals to achieve a specific task and describes how the
firmware works as a motor control system.
Watchdog Reset
Potentiometer value
< Minimum Value
Potentiometer value
< Minimum Value
Stop Fault Mode
Potentiometer value
> Minimum Value
Potentiometer value
< Minimum Value
Potentiometer value
< Minimum Value Overcurrent
Overvoltage
Undervoltage
Control Mode
= Open Loop
Ramp-Up Open Loop
Ramp-Up finished
Overcurrent
Overvoltage
Undervoltage
Zero-cross delta over limit
Zero-cross time-out
Control Mode
= Closed Loop
On system power-up, the System Control state is set to Driver Init, App Init state. This is the default state that
the system has after any Reset. To identify the Reset cause, a message is printed to notify the user about the
specific event. The potentiometer value is checked beforehand to make sure that the system does not start right
up (for example, if the system had an external Reset while the motor was at full speed, it would not have started
right up protecting the motor and power stage). If the condition is not met, the watchdog will trigger and reset the
microcontroller.
After this, the motor enters the Stop state. If the potentiometer value increases above a set threshold, then the rotor
will be aligned, and the system state will be set to Ramp-Up. Here, the motor is accelerated to the defined speed in
software, without knowing the position of the rotor.
Upon finishing the ramp-up sequence, the system goes in the Defined Control state, which can be either Open Loop
or Closed Loop.
When in Open Loop, the motor runs and the microcontroller does not have any information about its rotor position.
The speed of the motor can be adjusted through the potentiometer. If its value is smaller than a set threshold, the
motor stops and the system goes into the Stop state. If an overcurrent is detected, the system goes into the Error
Handling state.
When in Closed Loop, the running of the motor is based on the feedback received by the microcontroller about the
rotor position. The speed of the motor is constant and only the duty cycle can be adjusted through the potentiometer.
If its value is smaller than a set threshold, the motor stops and the system goes into the Stop state.
Besides overcurrent, zero-cross delta over limit, zero-cross time-out, undervoltage and overvoltage cause the system
to enter the Error Handling state.
If the system gets into Error state, then the only way to reset it is to get the potentiometer under a set threshold. Then
the system gets back to the initial Stop state.
CCL Control
Custom
Configurable LUT0 OUT AH
Logic
Phase A (CCL)
AC1 Interrupt Phase A
Half Bridge
Phase A Voltage Half Bridge
CCL Control Driver
dividers Phase B Analog Custom
Low-pass Comparator Configurable LUT1 OUT AL
Phase B filters (AC) Logic
Voltage Phase C AC1 Control (CCL)
summer
Phase C
Virtual
Ground
CCL Control
Custom
AC0 Interrupt Configurable LUT4 OUT
Analog BH
Logic
I/O Pin Comparator
(CCL)
Controller (AC) Control Algorithm Half Bridge Phase B Motor
(PORT) AC0 Control Half Bridge
Current AC2 OUT CCL Control Driver
sensing circuit Custom BL
Analog Configurable LUT3 OUT
Comparator Logic
(AC) (CCL) I/O Pin
Controller
(PORT)
Analog-to- ADC Result TCD0 WOB
Digital TCD0 WOA
Converter
Potentiometer (ADC) ADC Control
TCD0 WOC CH
TCD0 Control 12-Bit
Timer/Counter Half Bridge Phase C
Half Bridge
Voltage Type D Driver
Reference (TCD) CL
(Vref) TCD0 WOD
TCB0 Control
TCA1 Control
16-bit 16-bit TCA1 CMP0 Interrupt USART TX
USART Control
Timer/Counter Timer/Counter USART
TCA1 CMP1 Interrupt
Type B Type A
(TCB) (TCA) TCA1 CMP2 Interrupt
TCB0 CMP Interrupt
This implementation makes use of the bipolar switching presented above, and the zero-cross is detected by using an
internal comparator.
TCD cycle
Dead time A On time A Dead time B On time B
Counter
Compare
value
values
CMPBCLR
CMPBSET
CMPACLR
CMPASET
WOA
WOB
CMPBCLR + 1
In One Ramp mode, the TCD cycle period is: TTCD_cycle =
fCLK_TCD_CNT
For example, using an input clock of 24 MHz, a prescaler of 1:1, and a CMPBCLR value of 512, will give a period of
21.375 µs, or a frequency of approximately 46.783 kHz.
The dead time is set in software during external changes on the timer’s duty cycle.
For this application, the operation region is above 50% duty cycle to operate in quadrant one and two.
The equivalent logic for one phase, based on the behavior of the system, is configured through the TRUTH registers:
Figure 4-4. Equivalent Logic Routing Schematic
WOA
MUX
AND PHASE HIGH
MUX
The CCL logic implements smart routing of PWM signals to the half-bridge drivers, allowing control of two motor
phases using only one complimentary PWM pair (WOA and WOB), as described in the use cases below.
If the characteristic state of the phase is LOW, WOA is routed to the low-side transistor, while the WOB will be routed
to the high-side transistor.
If the characteristic state of the phase is HIGH, the WOA is routed to the high-side transistor and the WOB to the
low-side transistor.
PHASE A Voltage 0
divider+LPF
Voltage 1 MUX
PHASE B
divider+LPF
+
OUT
-
Voltage
PHASE C 2
divider+LPF
1:0
SUM
Ideally, for faster computation, the filter coefficient (MOTOR_DIVISION_FACTOR) must be a power of two, as it can be
implemented using bit shifting with specific core instructions.
The input and output values are unsigned 16-bit values, thus, to prevent an overflow during the multiplication of
y(n-1), as well as the total sum, the operations are done using casting to 32-bit unsigned values.
For the scope of this application, a value of 4 for the filter coefficient was considered the best fit.
tmr_ramp_up_compare_value -= MOTOR_TIMER_RAMP_UP_DECREMENT;
TCA0_setCMP0Value(tmr_ramp_up_compare_value);
The second instance of the TCA peripheral (TCA1) is used for driving/handling time-related motor events during each
step.
During one trapezoidal step, the counter serves four purposes:
• It handles the blanking time
• It counts the time from the commutation point to the zero-cross point
• It counts the new calculated time from the zero-cross point to the new commutation point
• It handles the stall detection (zero-cross time-out)
The counter has three compare channels, each of them configured to trigger a specific interrupt.
The method of operation is described below:
After a new commutation, the CNT register value is cleared, and the CMP0 interrupt is enabled.
Upon reaching the CMP0 interrupt, the AC1 interrupt is enabled, and the CMP0 interrupt is disabled.
If the zero cross is found within the CMP2 time interval, then the timer is stopped, the CNT register value is
processed with the zero-cross filter and set to the CMP1 register. The counter register is cleared once again and the
CMP1 interrupt is enabled.
When the timer reaches the CMP1 value, it triggers an interrupt, commutates to the next step, disables the CMP1
interrupt, and the cycle is repeated. A detailed, time-domain representation of the functionality of this block can be
seen in Figure 4-6.
Figure 4-6. TCA1 Time-Domain Representation
Active Interrupts
AC1
TCA1 CMP0
TCA1 CMP1
TCA1 CMP2
Commutation
Zero Cross
Phase
Voltage
Commutation
Interrupts
The TCB0 timer/counter acts like a very basic scheduler to run tasks that are non-time critical. It uses a fixed value
for a compare register which triggers an interrupt and sets the SCHEDULER_mainLoopFlag checked in the main
loop.
is a result of the magnetic coupling between the driven and the undriven coils, and not the voltage induced in the
coils by the moving magnet.
4.11 Debugging
The MPLAB® Data Visualizer is used to view live data and for debugging purposes.
Figure 4-7. MPLAB® Data Visualizer Example
or the Data Visualizer. Debug messages are disabled by default. To enable them, comment lines 31 and 33 and
uncomment line 30. Any changes to the code require recompiling and reuploading the project.
Figure 4-8. Debug Options
Configuration
1. Connect the MCLV-2 board to the PC using a Mini-USB cable.
2. Make sure the MPLAB Data Visualizer plug-in is installed.
2.1. Go to Tools → Plug-ins → Available plug-ins and search for MPLAB Data Visualizer.
3. Launch the MPLAB Data Visualizer and click on Load Workspace from the top bar. Select the .json file in
the root of the repository.
Figure 4-9. Loading the Workspace
4. On the left Connections tab, select the COM port and set the Baud Rate to 115200. Leave the rest of the
configuration like in Figure 4-10:
5. Press the Start streaming button for the selected COM port. To view the traces on the Time Plot, the Show
Live Data mode needs to be activated.
– If debug messages are enabled (see the app.c source file macros), they can be viewed in the Terminal
tab, with the Display As mode set to 8-bit ASCII
Figure 4-11. Debug Messages for Various States and Faults
The usage of the internal op amps relies mainly on microcontrollers that contain the op amp module such as
the AVR DB family, eliminating the need for an external op amp. The amplified current is then fed through a
comparator window with software-adjustable limits leaving the user the possibility to select between internal or
external references by changing a single selection jumper on the PIM.
A special configuration board is needed to gain access to both signals from the current shunts and the back-EMF of
the motor. It comes in the same package as the PIM. This is only needed when using the internal op amp current
reference. However, if the PIM is configured to run with an external op amp, it can also work with the provided
MCLV-2 EXTERNAL OP_AMP configuration board.
...........continued
PIM Pin # Signal Name Pinout Description AVR® DX PIN
13 MCLR Device Master Clear PF6
15 VSS Digital supply GND
16 VDD Digital supply VDD
18 FAULT DC BUS current fault (active-low logic) PC2
19 TX UART Transmit N/A
20 PIM_V_M3 Voltage feedback signal PD4
21 PIM_V_M2 Voltage feedback signal PD6
22 PIM_V_M1 Voltage feedback signal PD3
23 PIM_IMOTOR_SUM DC bus current signal PD2
24 PIM_IMOTOR2 Phase current signal PE0
25 PIM_IMOTOR1 Phase current signal PF2
26 PGC Device programming clock line N/A
27 PGD Device programming data line UPDI
28 VREF Reference voltage (half of AVDD voltage) PD7
29 PIM_REC_NEUTR Reconstructed motor neutral line voltage PD5
30 AVDD Analog supply AVDD
31 AVSS Analog supply GND
32 PIM_POT Potentiometer signal PD0
34 PIM_GEN2 General I/O PA4
35 PIM_VBUS DC bus voltage (downscaled) PD1
36 VSS Digital supply GND
37 VDD Digital supply VDD
41 PIM_MONITOR_1 Hall sensor/Current sense/Voltage feedback signal N/A
42 PIM_MONITOR_2 Hall sensor/Current sense/Voltage feedback signal N/A
43 PIM_MONITOR_3 Hall sensor/Current sense/Voltage feedback signal N/A
45 VSS Digital supply GND
46 VDD Digital supply VDD
47 HALLB Hall sensor/QEI input PB5
48 HALLC Hall sensor/QEI input PB4
49 RX UART Receive PA0
50 TX UART Transmit PA1
51 USB_TX UART Transmit (connected directly to U7) PB1
52 USB_RX UART Receive (connected directly to U7) PB0
58 PIM_FLT_OUT2 General I/O PC6
59 PIM_FLT_OUT1 General I/O PC5
...........continued
PIM Pin # Signal Name Pinout Description AVR® DX PIN
60 DBG_LED1 Debug LED 1 PC0
61 HOME Home signal for QEI PC7
62 VDD Digital supply VDD
63 OSC1/CLKO Crystal oscillator in N/A
64 OSC2/CLKI Crystal oscillator out N/A
65 VSS Digital supply GND
66 PIM_IBUS+ BUS current shunt signal N/A
67 PIM_IBUS- BUS current shunt signal N/A
68 LIN_CS LIN Chip Select signal PA2
69 LIN_FAULT LIN Fault signal PC1
70 RX UART Receive N/A
72 USB_RX UART Receive (connected directly to U7) N/A
73 PIM_IB+ IMOTOR1 shunt signal N/A
74 PIM_IA+ IMOTOR2 shunt signal N/A
75 VSS Digital supply GND
76 USB_TX UART Transmit (connected directly to U7) N/A
77 CAN_TX CAN Transmit N/A
78 CAN_RX CAN Receive N/A
80 HALLA Hall sensor/QEI input PB2
82 PIM_GEN1 General I/O N/A
83 BTN_1 Push-button S2 input PF5
84 BTN_2 Push-button S3 input PF4
86 VDD Digital supply VDD
87 CAN_RX CAN Receive N/A
88 CAN_TX CAN Transmit N/A
93 PWM1L1 PWM output - 1L PC3
94 PWM1H1 PWM output - 1H PA3
98 PWM1L2 PWM output - 2L PF3
99 PWM1H2 PWM output - 2H PB3
100 PWM1L3 PWM output - 3L PA7
Notes:
1. Digital Power (VDD) pins are connected to the PIM.
2. Digital Ground (VSS) and Analog Ground (AVSS) pins are connected to the PIM.
Table 5-2 provides the mapping between the 48-pin device and the 100-pin PIM.
...........continued
PIM Pin # Pin Name Pinout Description AVR® DX PIN
51 USB_TX UART Transmit (connected directly to U7) PB1
80 HALLA Hall sensor/QEI input PB2
99 PWM1H2 PWM output - 2H PB3
48 HALLC Hall sensor/QEI input PB4
47 HALLB Hall sensor/QEI input PB5
60 DBG_LED1 Debug LED 1 PC0
69 LIN_FAULT LIN Fault signal PC1
18 FAULT DC BUS current fault (active-low logic) PC2
93 PWM1L1 PWM output - 1L PC3
59 PIM_FLT_OUT1 General I/O PC5
58 PIM_FLT_OUT2 General I/O PC6
61 HOME Home signal for QEI PC7
32 PIM_POT Potentiometer signal PD0
35 PIM_VBUS DC bus voltage (downscaled) PD1
23 PIM_IMOTOR_SUM DC bus current signal PD2
22 PIM_V_M1 Voltage feedback signal PD3
20 PIM_V_M3 Voltage feedback signal PD4
29 PIM_REC_NEUTR Reconstructed motor neutral line voltage PD5
21 PIM_V_M2 Voltage feedback signal PD6
28 VREF Reference voltage (half of AVDD voltage) PD7
24 PIM_IMOTOR2 Phase current signal PE0
25 PIM_IMOTOR1 Phase current signal PF2
98 PWM1L2 PWM output - 2L PF3
84 BTN_2 Push-button S3 input PF4
83 BTN_1 Push-button S2 input PF5
13 MCLR Device Master Clear PF6
27 PGD Device programming data line UPDI
2 VDD N/A VDD
16 VDD N/A VDD
37 VDD N/A VDD
46 VDD N/A VDD
62 VDD N/A VDD
86 VDD N/A VDD
Notes:
1. Digital Power (VDD) pins are connected to the PIM.
2. Digital Ground (VSS) and Analog Ground (AVSS) pins are connected to the PIM.
PIN 42 PIN 14
GND DVDD PIM1
PIM:49 PIM:27 1 100
PIM:01 1 100 PIM:100
DVDD
DVDD
PIM:50 MCLR_SAFE 2 99
DVDD 2 99 PIM:99
PIM:68 PIM:83 3 98
PIM:03 3 98 PIM:98
PIM:94 PIM:84 4 97
PIM:04 4 97 PIM:97
PIM:34 PIM:98 5 96
PIM:05 5 96 PIM:96
6 95
PIM:06 6 95 PIM:95
7 94
PIM:07 7 94 PIM:94
48
47
46
45
44
43
42
41
40
39
38
37
8 93
U1 PIM:08 8 93 PIM:93
C1 C3 C2 C6 9 92
AVR128DB48-I/PT PIM:09 9 92 PIM:92
PF3
PF5
GND
VDD
PF6
PF4
UPDI
PA3
PA4
PA2
XTALHF2/PA1
XTALHF1/PA0
GND
GND
PIM:52 PB0 PE3 OP2:INN 15 86
5 32 GND 15 86 DVDD
PIM:51 PB1 PE2 OP2:OUT 16 85
6 31 DVDD 16 85 PIM:85
PIM:80 PB2 PE1 OP2:INP 17 84
7 30 PIM:17 17 84 PIM:84
PIM:99 PB3 PE0 PIM:24 18 83
8 29 PIM:18 18 83 PIM:83
PIM:48 PB4 GND GND PIN 28 19 82
9 28 PIM:19 19 82 PIM:82
PIM:47 PB5 AVDD AVDD 20 81
B 10 27 PIM:20 20 81 PIM:81 B
PIM:60 PC0 PD7 PIM:28 21 80
AVDD
11 26 PIM:21 21 80 PIM:80
PIM:69 PC1 PD6 PIM:21 22 79
12 25 PIM:22 22 79 PIM:79
VDDIO2
PIM:24 24 77 PIM:77
PD0
PD1
PD2
PD3
PD4
PC3
PC4
PC5
PC6
PC7
25 76
GND
PIM:25 25 76 PIM:76
26 75
21
13
23
15
18
14
16
17
19
20
22
24
PIM:26 26 75 GND
27 74
C4 C11 TP1 TP2 PIM:27 27 74 PIM:74
28 73
0.1uF 1uF PIM:28 28 73 PIM:73
PIM:93 PIM:20 29 72
PIM:29 29 72 PIM:72
DVDD PIM:22 30 71
AVDD 30 71 PIM:71
GND ISUM 31 70
GND 31 70 PIM:70
PIM:35 GND 32 69
PIM:32 32 69 PIM:69
PIM:59 PIM:32 33 68
GND PIM:33 33 68 PIM:68
PIM:58 PIM:61 34 67
PIM:34 34 67 PIM:67
35 66
PIM:35 35 66 PIM:66
36 65
GND 36 65 GND
37 64
DVDD 37 64 PIM:64
R1 38 63
GND PIM:38 38 63 PIM:63
C12 39 62
C13 PIM:39 39 62 DVDD
GND 30k 40 61
56pF PIM:20 PIM:40 40 61 PIM:61
41 60
R2 R3 OP2_O PIM:41 41 60 PIM:60
XTAL1
XTAL2
10nF 42 59
PIM:67 PIM:42 42 59 PIM:59
C 43 58 C
1k 1k GND PIM:43 43 58 PIM:58
44 57
OP2:INN - R4 OP2 PIM:44 44 57 PIM:57
C14 45 56
OP2 OP2:OUT GND 45 56 PIM:56
56pF 46 55
OP2:INP + 1k C15 DVDD
47
46 55
54
PIM:55
R5 R6 Y1 PIM:47 47 54 PIM:54
PIM:21 48 53
PIM:66 PIM:48 48 53 PIM:53
10nF 49 52
1k 1k VREF PIM:49 49 52 PIM:52
C16 32.7680kHz 50 51
PIM:50 50 51 PIM:51
R7 1000pF GND
C17
PIM:28 C8 C9 PIM 4x25 Female
56pF
30k 12pF 12pF
C18 C19
10nF
PIM:22
GND GND 10nF
GND GND
GND GND
J2
OP2:OUT J4
0R MCLR_SAFE MCLR
ISUM 0R
J3
PIM:23
0R
DNP UPDI
D PIM:27 D
VDD
DVDD
LABEL1
RST/MCLR
MCLR
1 2 3 4 5 6
Notes:
1. Jumpers J2 and J3 are used to switch between external and internal op amp.
2. Jumper J4 can be replaced with a resistor to protect the microcontroller against an accidental HV
programming mode.
A A
J1
B SHUNT_HIGH_SUM PIM_IBUS+ SHUNT_HIGH_SUM PIM_IBUS+ B
49 47 45 43 41 39 37 35 33 31 29 27 25 23 21 19 17 15 13 11 9 7 5 3 1
50 48 46 44 42 40 38 36 34 32 30 28 26 24 22 20 18 16 14 12 10 8 6 4 2
SHUNT_LOW_SUM PIM_IBUS- SHUNT_LOW_SUM PIM_IBUS-
SHUNT_HIGH_1 PIM_IA+ SHUNT_HIGH_1 PIM_IA+
SHUNT_HIGH_2 PIM_IB- SHUNT_HIGH_2 PIM_IB-
D D
1 2 3 4 5 6
AVR128DB48
B E 31
IBUS+ +
Filter, Feedback 32
Op Amp 2
A and Bias Circuit F 33 _
IBUS-
C D
30k 30k
56 pF
B E
1k 1k
56 pF
A F
1k 1k
56 pF
1
Common − mode f−3 dB ≅ ≅ 2.8 MHz
2π 1kΩ 56 pF
Figure 5-6. Voltage Divider and Low-Pass Filter for Phase Back-EMF
MCLV-2 PIM
M1 PIM_V_M1 PIM:22
30k 300
2k 10 nF
M2 PIM_V_M2 PIM:21
30k 300
2k 10 nF
M3 PIM_V_M3 PIM:20
30k 300
2k 10 nF
1
Cutoff frequency−3 dB = ≅ 7321 Hz
2π 30k ∥ 2k + 300 10 nF
tan 30
30 degree phase shift frequency = = 4226 Hz
2π 30k ∥ 2k + 300 10 nF
Thus, the theoretical maximum speed of the motor will be:
4226 Hz * 60 ≅ 253560 eRPM
Mecℎanical RPM = eRPM/Pole pairs
6. Tuning
The following paragraphs will focus on the tuning parameters and their impact on the system behavior:
1. Start-up PWM Duty [%] – It represents the start-up duty cycle in percentage. A value that is too low may
be insufficient for the ramp-up sequence as the current through the windings is too low and the generated
magnetic field is not strong enough for the rotor to follow.
A value that is too high will result in a trigger of the overcurrent protection or excessive heating of the windings.
The start-up duty cycle is also strongly dependent on the motor load at start-up. Higher loads demand higher
duty cycles.
This parameter applies to the ramp-up sequence only.
2. Rotor align time [ms] – The rotor align time in milliseconds. The duty cycle is gradually increased using a
linear ramp from 0% to the Start-up PWM Duty value so there is no mechanical shock. This alignment is done
for the motor to start from a known position.
This parameter applies to the ramp-up sequence only.
3. Target RPM [RPM] – This will be the final RPM after the ramp-up sequence. If it is set too high, then there will
be a need for a higher duty cycle so that the motor can follow the magnetic field at high RPMs.
This parameter applies to the ramp-up sequence only, but the closed-loop control also depends on it.
4. Initial start-up period [ms] – Start-up point of the ramp. There is generally no need to tune this parameter.
This parameter applies to the ramp-up sequence only.
5. Ramp duration [ms] – Sets how much the ramp will last. For faster start-up times, lower this value. Beware
that strong accelerations also demand higher duty cycles.
This parameter applies to the ramp-up sequence only.
6. Ramp sustain duration [ms] – After the ramp-up sequence, where the motor is accelerated, there is a
sustained period where the motor is spun with the Target RPM speed. Unless there is a PI controller used,
where it can benefit in the training of the controller, it is recommended for this parameter to be kept to a
minimum.
This parameter applies to the ramp-up sequence only.
7. Hold-off steps – Immediately after the ramp-up sequence, the PWM is disabled and the comparator is
enabled. This is done to detect the exact position of the rotor in absence of any phase noise. This parameter
needs to be kept to a minimum of one unless there is a very slow variation of the phase voltage of the motor.
This parameter applies to the ramp-up sequence only.
8. Motor pole pairs – The number of pole pairs of the motor.
9. Minimum PWM duty [%] – The minimum PWM duty cycle. Use this parameter to limit the minimum speed of
the motor.
This parameter applies to the closed and open-loop control.
10. Maximum PWM duty [%] – The maximum PWM duty cycle. Use this parameter to limit the maximum speed
of the motor.
This parameter applies to the closed and open-loop control.
11. Braking PWM duty [%] – The duty cycle for the motor in Stop mode. The system is protected from
overcurrents caused by braking at high speeds. In this case, the firmware will get to the Fault state and
protect the transistors.
This parameter applies to the Stop state only.
12. Motoring current limit [mA] – The maximum current value that can be drawn from the bus over which the
Fault condition is triggered. The maximum value is limited by MCLV-2 to 4420 mA.
This parameter applies to all system states except for the Error Handling state.
13. Braking current limit [mA] – The maximum current value that can be pushed to the bus over which the Fault
condition is triggered. The maximum value is limited by MCLV-2 to -4420 mA.
This parameter applies to all system states except for the Error Handling state.
14. Undervoltage protection [mV] – The minimum voltage on the bus for the MCLV-2. Do not set under 11V.
This parameter applies to all system states except for the Error Handling state.
15. Overvoltage protection [mV] – The maximum voltage for the system. Do not set over 24V if using a single
supply, or over 48V if using dual supplies (see the MCLV-2 user guide).
This parameter applies to all system states except for the Error Handling state.
16. Moving average filter division factor – The division factor for the moving average filter of the zero-cross time
needs to be set as a power of two because it can be optimized by the compiler with right shifts. Higher values
are recommended because the system has higher immunity to any glitches but limits the maximum variation
between 2 zero-cross events, thus limiting the maximum acceleration of the motor. This parameter applies to
the closed-loop control only.
17. Advance angle [Deg] – The advance angle of the motor. Increasing this value will advance the generation of
the waveforms with that specific degrees, concerning the motor back-EMF zero-cross point. Also, it will have
an impact on the torque generated by the motor.
This parameter applies to the closed-loop control only.
18. Pass-through delay compensation [us] – Fixed advance time for the next sector timing. This value is
directly subtracted from the next sector timing to compensate for any software or hardware delays.
This parameter applies to the closed-loop control only.
19. Delta division factor – This parameter controls an additional stall and glitch detection mechanism. In the case
of very early or very late detection of the zero-cross point, if the absolute difference between the previous
zero-cross time and the currently measured time is more than the previous zero-cross time/Delta division
factor, then a Fault condition is triggered. The Delta division factor is ideal to be chosen as a power of two for
code efficiency. A value too high will make the system very unstable and will limit the maximum acceleration
by triggering the Fault condition. A value too low may not detect a glitch very well but will not encounter any
troubles at start-up.
This parameter applies to closed-loop control only.
20. Minimum RPM tolerance [%] – This parameter controls the time-out and the minimum RPM for the timer.
After the start-up, it may be that the system will detect the zero-cross point a bit later than it needs to, and if
the tolerance is very low, it will be considered as a time-out event. To avoid that, a given tolerance is needed
under the shape of a percentage of the minimum RPM. The minimum RPM thus becomes Target RPM -
Target RPM * Minimum RPM tolerance.
This parameter applies to the closed-loop control only.
After modifying the parameters, press the Patch File button, then recompile and program the AVR DX with the
firmware.
7. Conclusion
This application note describes a method of driving a BLDC motor using bipolar switching, starting from generating
the waveforms and routing them to the required pins.
There is no need for external comparators or other logic circuits, the only exception being a few passive components
to condition the input signal going to the microcontroller.
The AVR core running at 24 MHz, providing up to 24 MIPS, is a very powerful choice in designing a system that
integrates multiple requirements alongside the Core Independent Peripherals (AC, ADC, TCA, TCB, CCL, USART)
used to drive the motor as a complete control system.
Bipolar drive ensures clean BEMF which helps an accurate detection of the zero-cross point, without the need for
synchronization with the PWM output signal.
For better performance, the built-in moving average filter adds an extra measure of protection in case of an external
disturbance and ensures a smooth run throughout the RPM range of the motor.
8. References
1. AN857, Brushless DC Motor Control Made Easy (DS00857)
2. AN1160, Sensorless BLDC Control with Back-EMF Filtering Using a Majority Function (DS01160)
3. AVR444: Sensorless control of 3-phase brushless DC motors
4. AN2522, Core Independent Brushless DC Fan Control Using CCL AVR® microcontrollers (DS00002522)
9. Revision History
Doc. Rev. Date Comments
B 6/2021 Updated Introduction section with GitHub link.
A 5/2021 Initial document release.
Microchip provides online support via our website at www.microchip.com/. This website is used to make files and
information easily available to customers. Some of the content available includes:
• Product Support – Data sheets and errata, application notes and sample programs, design resources, user’s
guides and hardware support documents, latest software releases and archived software
• General Technical Support – Frequently Asked Questions (FAQs), technical support requests, online
discussion groups, Microchip design partner program member listing
• Business of Microchip – Product selector and ordering guides, latest Microchip press releases, listing of
seminars and events, listings of Microchip sales offices, distributors and factory representatives
Microchip’s product change notification service helps keep customers current on Microchip products. Subscribers will
receive email notification whenever there are changes, updates, revisions or errata related to a specified product
family or development tool of interest.
To register, go to www.microchip.com/pcn and follow the registration instructions.
Customer Support
Note the following details of the code protection feature on Microchip devices:
• Microchip products meet the specifications contained in their particular Microchip Data Sheet.
• Microchip believes that its family of products is secure when used in the intended manner and under normal
conditions.
• There are dishonest and possibly illegal methods being used in attempts to breach the code protection features
of the Microchip devices. We believe that these methods require using the Microchip products in a manner
outside the operating specifications contained in Microchip’s Data Sheets. Attempts to breach these code
protection features, most likely, cannot be accomplished without violating Microchip’s intellectual property rights.
• Microchip is willing to work with any customer who is concerned about the integrity of its code.
• Neither Microchip nor any other semiconductor manufacturer can guarantee the security of its code. Code
protection does not mean that we are guaranteeing the product is “unbreakable.” Code protection is constantly
evolving. We at Microchip are committed to continuously improving the code protection features of our products.
Attempts to break Microchip’s code protection feature may be a violation of the Digital Millennium Copyright Act.
If such acts allow unauthorized access to your software or other copyrighted work, you may have a right to sue
for relief under that Act.
Legal Notice
Information contained in this publication is provided for the sole purpose of designing with and using Microchip
products. Information regarding device applications and the like is provided only for your convenience and may be
superseded by updates. It is your responsibility to ensure that your application meets with your specifications.
THIS INFORMATION IS PROVIDED BY MICROCHIP “AS IS”. MICROCHIP MAKES NO REPRESENTATIONS
OR WARRANTIES OF ANY KIND WHETHER EXPRESS OR IMPLIED, WRITTEN OR ORAL, STATUTORY
OR OTHERWISE, RELATED TO THE INFORMATION INCLUDING BUT NOT LIMITED TO ANY IMPLIED
WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE
OR WARRANTIES RELATED TO ITS CONDITION, QUALITY, OR PERFORMANCE.
IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR
CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE
INFORMATION OR ITS USE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE
POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT ALLOWED BY LAW,
MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY RELATED TO THE INFORMATION OR ITS USE
WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR
THE INFORMATION. Use of Microchip devices in life support and/or safety applications is entirely at the buyer’s risk,
and the buyer agrees to defend, indemnify and hold harmless Microchip from any and all damages, claims, suits, or
expenses resulting from such use. No licenses are conveyed, implicitly or otherwise, under any Microchip intellectual
property rights unless otherwise stated.
Trademarks
The Microchip name and logo, the Microchip logo, Adaptec, AnyRate, AVR, AVR logo, AVR Freaks, BesTime,
BitCloud, chipKIT, chipKIT logo, CryptoMemory, CryptoRF, dsPIC, FlashFlex, flexPWR, HELDO, IGLOO, JukeBlox,
KeeLoq, Kleer, LANCheck, LinkMD, maXStylus, maXTouch, MediaLB, megaAVR, Microsemi, Microsemi logo,
MOST, MOST logo, MPLAB, OptoLyzer, PackeTime, PIC, picoPower, PICSTART, PIC32 logo, PolarFire, Prochip
Designer, QTouch, SAM-BA, SenGenuity, SpyNIC, SST, SST Logo, SuperFlash, Symmetricom, SyncServer,
Tachyon, TimeSource, tinyAVR, UNI/O, Vectron, and XMEGA are registered trademarks of Microchip Technology
Incorporated in the U.S.A. and other countries.
AgileSwitch, APT, ClockWorks, The Embedded Control Solutions Company, EtherSynch, FlashTec, Hyper Speed
Control, HyperLight Load, IntelliMOS, Libero, motorBench, mTouch, Powermite 3, Precision Edge, ProASIC,
ProASIC Plus, ProASIC Plus logo, Quiet-Wire, SmartFusion, SyncWorld, Temux, TimeCesium, TimeHub, TimePictra,
TimeProvider, WinPath, and ZL are registered trademarks of Microchip Technology Incorporated in the U.S.A.
Adjacent Key Suppression, AKS, Analog-for-the-Digital Age, Any Capacitor, AnyIn, AnyOut, Augmented Switching,
BlueSky, BodyCom, CodeGuard, CryptoAuthentication, CryptoAutomotive, CryptoCompanion, CryptoController,
dsPICDEM, dsPICDEM.net, Dynamic Average Matching, DAM, ECAN, Espresso T1S, EtherGREEN, IdealBridge,
In-Circuit Serial Programming, ICSP, INICnet, Intelligent Paralleling, Inter-Chip Connectivity, JitterBlocker, maxCrypto,
maxView, memBrain, Mindi, MiWi, MPASM, MPF, MPLAB Certified logo, MPLIB, MPLINK, MultiTRAK, NetDetach,
Omniscient Code Generation, PICDEM, PICDEM.net, PICkit, PICtail, PowerSmart, PureSilicon, QMatrix, REAL ICE,
Ripple Blocker, RTAX, RTG4, SAM-ICE, Serial Quad I/O, simpleMAP, SimpliPHY, SmartBuffer, SMART-I.S., storClad,
SQI, SuperSwitcher, SuperSwitcher II, Switchtec, SynchroPHY, Total Endurance, TSHARC, USBCheck, VariSense,
VectorBlox, VeriPHY, ViewSpan, WiperLock, XpressConnect, 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.
The Adaptec logo, Frequency on Demand, Silicon Storage Technology, and Symmcom are registered trademarks of
Microchip Technology Inc. in other countries.
GestIC is a registered trademark of Microchip Technology Germany II GmbH & Co. KG, a subsidiary of Microchip
Technology Inc., in other countries.
All other trademarks mentioned herein are property of their respective companies.
© 2021, Microchip Technology Incorporated, Printed in the U.S.A., All Rights Reserved.
ISBN: 978-1-5224-8307-6