You are on page 1of 30

Digital PID Speed Controller for Motor

Drive Applications
V1.3 - Dec 22, 2006
English Version

19, Innovation First Road • Science Park • Hsin-Chu • Taiwan 300 • R.O.C.

Tel: 886-3-578-6005 Fax: 886-3-578-4418 E-mail: mcu@sunplus.com

http://www.sunplusmcu.com http://mcu.sunplus.com
Digital PID Speed Controller for Motor Drive Applications

Important Notice

SUNPLUS TECHNOLOGY CO. reserves the right to change this documentation without prior notice. Information
provided by SUNPLUS TECHNOLOGY CO. is believed to be accurate and reliable. However, SUNPLUS
TECHNOLOGY CO. makes no warranty for any errors which may appear in this document. Contact SUNPLUS
TECHNOLOGY CO. to obtain the latest version of device specifications before placing your order. No
responsibility is assumed by SUNPLUS TECHNOLOGY CO. for any infringement of patent or other rights of third
parties which may result from its use. In addition, SUNPLUS products are not authorized for use as critical
components in life support systems or aviation systems, where a malfunction or failure of the product may
reasonably be expected to result in significant injury to the user, without the express written approval of Sunplus.

© Sunplus Technology Co., Ltd. PAGE 1 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Revision History

Page
Revision Date By Remark
Number(s)

V1.3 2006/12/22 Li Jing Proofreading


Translate ‘Digital PID Speed Controller for Motor
V1.2 2006/04/18 Li Jing
Drive Applications V1.2, Chinese version’

© Sunplus Technology Co., Ltd. PAGE 2 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Table of Content
PAGE

1 Analog PID Control............................................................................................................................. 4

1.1 Analog PID Control Theory............................................................................................................ 4

2 Digital PID Control.............................................................................................................................. 7

2.1 Positional PID Algorithm ................................................................................................................ 7


2.2 Increment PID Algorithm................................................................................................................ 8
2.3 PID Controller Tuning .................................................................................................................... 9
2.3.1 Trial & Error Method ......................................................................................................................... 10
2.3.2 Critical Proportion Method (Ziegler-Nichols Method)........................................................................ 10
2.3.3 Experiential Method ..........................................................................................................................11
2.3.4 Sampling Period Selection ............................................................................................................... 12
2.4 Explore for Parameter Tuning Rule ............................................................................................. 12
2.5 Self-Tuning PID Controller........................................................................................................... 13

3 Software Design................................................................................................................................ 14

3.1 Software Description ................................................................................................................... 14


3.2 Source File .................................................................................................................................. 14
3.3 DMC Interface ............................................................................................................................. 14
3.4 Subroutines ................................................................................................................................. 15

4 Demo Listing..................................................................................................................................... 20

4.1 Demo ........................................................................................................................................... 20


4.2 Main Process Description............................................................................................................ 22
4.3 ISR Description............................................................................................................................ 23

5 MCU Resource .................................................................................................................................. 24

6 Test..................................................................................................................................................... 25

6.1 Response Curves ........................................................................................................................ 25

7 Reference .......................................................................................................................................... 29

© Sunplus Technology Co., Ltd. PAGE 3 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

1 Analog PID Control

The PID controller receives signals from sensors and computes corrective action to the
actuators from a computation based on the error (proportion), the sum of all previous
errors (integral) and the rate of change of the error (derivative).

1.1 Analog PID Control Theory

A PID controller is a common feedback loop component in industrial control applications.


First, let's take a look at how the PID controller works in a closed-loop system using the
schematic shown below. The variable e(t) represents the difference between the desired
rotate speed n0(t) and the actual rotate speed n(t), which can be obtained by the
calculation e(t)= n0(t)-n(t). This error signal e(t) will be sent to the PID controller. After
computing, the controller will output the voltage control signal u(t), which will drive the DC
motor to change the rotate speed via power amplifying.

n0 (t ) + e(t ) u(t )
PID Controller DC Motor


n (t )

Figure 1-1 Speed Regulating System for a Light Power DC Motor

Figure 1-1 is the schematic of a basic PID control system consisting of a PID controller
and Plant (a controlled system). In the schematic, r(t) is the desired input value and y(t)
is the actual output value. The error signal e(t) between them is:

e(t)= r(t)-y(t) (Formula 1-1)

e(t) is the input value of PID controller, u(t) is the output of PID controller and input of Plant.
Therefore, the control rule of the analog PID controller is:

1 t de( t )
u (t ) = Kp[e( t ) +
Ti ∫0
e(t )dt + Td
dt
] (Formula 1-2)

Where

Kp= Proportional gain

© Sunplus Technology Co., Ltd. PAGE 4 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Ti= Integral time, or called integral gain

Td= Derivative time, or called derivative gain

Proportion


r (t ) + e(t ) + u(t ) y(t )
Integral Plant



Differential

Figure 1-2 Schematic of a Basic PID Control System

1. Proportional Response

The proportional component can be expressed as Kp*e(t).

In an analog PID controller, the proportional component makes the transient response for
the error. It means that once the error occurs, the controller will immediately control the
Plant to reduce error. The effect of controlling error depends on the proportional gain
(Kp). In general, increasing the proportional gain will increase the speed of the control
system response and reduce the steady-state error. However, if the proportional gain is
too large, the system will begin to oscillate and become unstable. Thus, Kp must be
selected suitable to make the system stable and have the effect of reducing the rise time
and steady-state error.

2. Integral Response

Kp t
The integral component can be expressed as Ti
∫0e(t )dt .
From the expression shown above, we can see that the integral component sums the error
term over time. The result is that even a small error term will cause the integral
component to increase slowly. The integral response will continually increase over time
unless the error is zero, so the effect is to drive the Steady-State error to zero.

But the integral control will reduce the speed of the overall control system response and
increase the overshoot. Increasing the integral gain (Ti) will cause the integral
component to accumulate weakly and reduce the overshoot, thus it makes the system not
to oscillate during the rising time, which improves the stability; however, it will slow the
© Sunplus Technology Co., Ltd. PAGE 5 V1.3 - Dec 22, 2006
Digital PID Speed Controller for Motor Drive Applications

process of eliminating Steady-State error. Reducing Ti will strengthen the accumulation of


integral component and shorten the time of eliminating error, but it will make the system
oscillate. Therefore, Ti should be selected according to the desired needs.

3. Derivative Response

de(t )
Kp * Td
The derivative component can be expressed as dt .

Practically, the control system also demands to speed up the rate of change in error signal.
That means when the error occurs or the error makes the transient change, the system is
expected not only to response immediately (proportional action), but also to anticipate the
future behavior of the error signal by using corrective action based on the rate of change in
error signal. Therefore, the derivative component is added to the system to consist of
PID controller.

Derivative control is used to stop the change in error signal. The derivative response is
proportional to the rate of change of the process variable. When the error signal is
increasing greatly, the controller output is larger, and the error can be corrected before
increasing. Adding the derivative component to the system will help reduce overshoot
and eliminate oscillate thus make the system go stable. Especially in the higher-order
system, it accelerates the speed of controller's response. Since the derivative response
is highly sensitive to noise in processing variable signal, most practical control systems of
larger noise use very small derivative time or filter the input signal before derivative
processing.

The effect of derivative component depends on the derivative time constant (Td). In
general, the larger Td, the better the effect to restrain the change of e(t) and vice versa.
Thus, to select Td properly can make the derivative component better meet the system
requirement.

The appearance of computer makes it easy to perform PID control by software to realize
the control of formula 1-2, called digital PID control.

© Sunplus Technology Co., Ltd. PAGE 6 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

2 Digital PID Control

Digital PID control algorithms contain positional PID and increment PID control algorithms.

2.1 Positional PID Algorithm

Since software control method uses sampling control, which calculates the control signals
based on the error at the sampling point, the signal cannot be output serially as analog
control method does. Therefore, the integral and derivative components in Formula 1-2
must be discrete. The discrete process is: Take T as the sampling period and k as the
sampling number, then the discrete sampling time kT corresponds to the continuous time t,
and the equivalent discrete algorithm can be approximately transformed by replacing
integral with rectangle numerical integration, derivative with first order backward difference,
shown as follows.

(Formula 2-1)

To express conveniently, e(kT) is simplified to ek.

The discrete PID algorithm is shown as follows using Formula 2-1 and Formula 1-2:

T k e − ek −1
u k = Kp[ek + ∑
Ti j =0
e j + Td k
T
] (Formula 2-2)

or

k
u k = Kp * ek + Ki ∑ e j + Kd(ek − ek −1) (Formula 2-3)
j =0

Where, k ---- Sampling number, k=0, 1, 2 …

Uk ----The output value sampling at the K times

© Sunplus Technology Co., Ltd. PAGE 7 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

ek ---- The error sampling at the K times

ek-1 ---The error sampling at the (K-1) times

Ki ---- Integral coefficient, Ki=Kp*T/Ti

Kd --- Derivative coefficient, Kd=Kp* Td/T

If the sampling period is short enough, the approximate calculation by Formula 2-2 or
Formula 2-3 can get an accurate result and the discrete control process is close to the
continuous control process.

The control algorithm expressed by Formula 2-2 or Formula 2-3 are based on the PID
control rule defined in Formula 1-2, thus it calculates all control values and is known as the
‘Full value’ or 'Positional' PID control algorithm.

The disadvantages of this algorithm are: The current full value output is related to the
previous control value, thus ek is needed to accumulate. Beisides, since Uk corresponds
to the actual position of actuator, if malfunction occurs, the great change of Uk will affect
the actuator output largely, which may result in severe accident-this is not allowed in
practical production.

Using the increment PID control algorithm can avoid above problems.

2.2 Increment PID Algorithm

The Increment PID Algorithm means the output of digital controller is only the increment

∆uk of controlling value. When the control value needed by actuator is the increment,

but not the absolute value of position, an increment PID control algorithm is a good choice
to control the system.

The increment PID algorithm can be deduced from formula 2-2. The output value
sampling at the (k-1) times is derived as:

T k-1 e −e
uk-1 = Kp[ek-1 + ∑
Ti j = 0
e j + Td k-1 k − 2 ]
T
(Formula 2-4)

Subtracting Formula 2-4 from formula 2-2 to get the increment PID algorithm formula
shown as follows:

© Sunplus Technology Co., Ltd. PAGE 8 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

T e − 2ek-1 + ek − 2
∆uk=uk-uk-1 = Kp( ek-ek-1 + ek + Td k )
Ti T
T Td 2Td Td (Formula 2-5)
= Kp(1 + + )ek-Kp(1 + )ek-1 + Kp ek − 2 )
Ti T T T
= Aek + Bek-1 + Cek − 2

Where A = Kp (1 + T + Td ) ;
Ti T

B = Kp(1 + 2Td ) ;
T

C = Kp Td .
T

From Formula 2-5, we can see that once the sample period (T) of the control system is a
constant and A, B, C are fixed, the control value can be calculated using the errors
measured in recent three times.

The calculation of increment PID algorithm is much smaller than that of positional PID
algorithm; hence it is used widely in practice.

The recursion formula of positional PID algorithm can be also deduced from the increment
PID algorithm as follows:

uk=uk-1+∆uk (Formula 2-6)

Currently Formula 2-6 is used in a large range of computer control system.

2.3 PID Controller Tuning

Tuning a PID controller means to determine the values of proportional gain (Kp), integral
time (Ti), derivative time (Td) and sampling period (Ts). Essentially, tuning the
parameters of controller is to match its characteristic to the process characteristic, thus
improving the dynamic and state data to make the system achieve the best control effect.

There are several methods for tuning a PID controller. Summarily, they can be divided
into two categories: Theoretical Calculation tuning (including Logarithmic frequency
characteristic method and Root-locus method) and Project tuning (including Trial & Error
method, Critical Proportion method, Experiential method, Decay Curve method and
Response Curve method). Users don’t need to know the mathematical model of control
© Sunplus Technology Co., Ltd. PAGE 9 V1.3 - Dec 22, 2006
Digital PID Speed Controller for Motor Drive Applications

process when adopting Project tuning method. We can directly tune parameters just in
the process control system which features simple calculation and easy control.

2.3.1 Trial & Error Method

This method performs parameter tuning according to the sequence of proportion (P),
integral (I), and derivative (D).

First, set the integral time Ti =∞, derivative time Td =0. Then, put the system into
operation and adjust Kp from small to large to obtain the best transition process curve with
1/4 attenuation.

Increase I and adjust Ti from large to small. At this time, the above Kp should be
adjusted to 5/6 Kp.

If D is needed to increase, Td can be set as your experience or adjust to (1/3~1/4) Ti from


small to large.

2.3.2 Critical Proportion Method (Ziegler-Nichols Method)

This is a method of determination of optimum controller settings when tuning a process


control loop. It is based on finding the proportional gain which causes instability in a
closed loop. In a closed loop control system, put the regulator under pure proportion
function, then change the proportional gain from small to large to make the system
oscillate continuously. The current proportional gain is called the critical gain Ku and the
time interval between two neighboring peaks is called critical oscillation period Tu.

The steps are shown below:

(1) Set Ti=∞, Td=0, and adjust Kp to a suitable value. After the system is stable, put the
system into running automatically.

(2) Increase Kp gradually to make the system oscillating continuously. Record the critical
gain (Ku) and critical oscillation period (Tu).

(3) Calculate the values of Kp, Ti, and Td using the experience formula.

© Sunplus Technology Co., Ltd. PAGE 10 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

 Notes:

„ In some process control systems, the critical gain is so large that the system is close to the on/off control.
At that time, the regulator is either closed or opened completely which is a disadvantage for the
industry production.

„ In some process control systems, when Kp is adjusted to the maximum, system cannot yet oscillate
continuously. Therefore, this maximum is considered as Ku.

2.3.3 Experiential Method

Tuning PID controller using trial & error method needs to be tried out many times. In
order to reduce the trial times and improve efficiency, we can refer to others’ experience
and make some experiments in advance according to the specific demands to get some
parameters. Applying these reference parameters to the experience formula can deduce
the PID control parameters. This method is called experiential method.

Critical ratio method is a kind of experiential methods. First, select a pure proportional
controller and make the system form a closed loop system. Then, change the
proportional gain to make the system arrive the critical state for the step input response.
At this time, record the proportion gain Ku and the critical oscillating period Tu. Based on
the experience formula, the parameters of different controllers can be obtained as shown
in Table 2-1.

Table 2-1 The Parameter of The Analog Controller Using Critical Proportional Method

Controller type Kp Ti Td

P 0.5 Ku

PI 0.45 Ku 0.85 Tu

PID 0.6 Ku 0.5 Tu 0.12 Tu

For digital PID controller, the theory is the same as long as the sampling period is small
enough. In a motor control system, critical proportional method can be used first to adjust
the parameters of PID controller, and then trial & error method is used to fix them.

Parameters displayed in the Table 2-1 are acquired with 1/4 degree of decay which is

© Sunplus Technology Co., Ltd. PAGE 11 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

thought suitable for the system stability and system fast response. If larger attenuation is
needed, trial & error method must be adopted to further adjust the parameters.

2.3.4 Sampling Period Selection

Shannon sampling theorem states when sampling a signal at discrete intervals: The
sampling frequency must be at least twice the highest frequency of the input signal in
order to be able to reconstruct the original perfectly from the sampled version. Based on
the Shannon sampling theorem, the upper limit of the sampling period can be confirmed.
In the real life, the choice of sampling period is affected by many factors, thus the different
systems may have different choices.

The sampling period is usually chosen according to the process characteristics and the
interference. That means if the process is vulnerable, responding fast (such as flow rate
and pressure) and fluctuating greatly, the shorter sampling period is recommended; on the
contrary, if the process responds slowly (such as temperature), and has large-time delay,
the longer sampling period is recommended.

In addition, tuning parameters for PID controller should be considered when choosing the
sampling period. The sampling period should be greatly shorter than the period of the
noise signal, but if the actuator responses slowly, the too small sampling period will not
meet the command, thus we may choose a little longer period. Within your computer
speed limit, the shorter the sampling period, the better the control effect. Generally, when
the pure time delay is much longer, the sampling period will be chosen as 1/4~1/8 times
longer than the pure time.

2.4 Explore for Parameter Tuning Rule

Based on PID control theory and decades of manual work experience, there are some
steps for parameter tuning.

„ If the error is larger, in order to quickly eliminate error, improve response speed and
avoid overshoot in the system response, ; while if the error is smaller, decrease Kp and
simultaneously avoid increasing overshoot, and making system oscillate and unstable,
decrease Kp and set Ki value or increase it a little to eliminate steady-state error and
overshoot, and make system stable quickly.

„ If the error and the error change rate are in the same direction, the controlled item will
vary to the opposition direction of desired value. Therefore, if the controlled item is

© Sunplus Technology Co., Ltd. PAGE 12 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

close to the desired value, the proportional component with opposite sign will restrain
the integral action, thus avoid overshoot and the following oscillation; if the controlled
item is far from the desired value and is varying to its direction, the proportional
component with opposite sign will slower the control process. Overall, when the error
is larger, and the error and the error change rate have the opposite signs, we should
set Kp as zero or negative value to speed up the dynamic process.

„ The error change rate indicates the speed of error change. The more ( ek-ek −1 ), the
smaller Kp and the larger Ki and vice versa. Furthermore, the error size should be
taken into account.

„ Derivative control can improve system dynamic characteristics, stop the change in
error signal, help to reduce the overshoot, eliminate system oscillation and shorten the
adjust time t s . The derivative item allows increasing Kp to reduce the steady state
error and improve the control precision. Therefore, when ek is larger, Kd is set to
zero, actually a PI controller is designed for the system; when ek is smaller, set Kd as
a positive value to control system using a PID controller.

2.5 Self-Tuning PID Controller

For a specific system to be controlled, the critical oscillating period (Tu) and the critical
proportional gain (Ku) can be figured out by changing the proportional gain under the pure
proportional control.

Based on Ziegler-Nichols method:

T = 0.1Tu Ti = 0.5Tu Td = 0.125Tu

Thus:

∆u k=Kp ( 2.45ek − 3.5ek −1 + 1.25ek − 2 ) (Formula2-7)

Obviously, the constant Kp is easy to be corrected using above formula.

© Sunplus Technology Co., Ltd. PAGE 13 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

3 Software Design

3.1 Software Description

This document is intended to guide you how to adjust the speed of BLDC using digital PID.
The key is tuning the parameters of PID controller to make the system characteristics meet
the optimal effect. Here we use SPMC75F2413A as an example for demonstration
purpose.

3.2 Source File

File Name Function Type

Initialize parameters for driving BLDC, DMC


Main C
communication

Chap2 Functions for driving BLDC C

Initial System initialization programs C

ISR Interrupt service in driving program C

PID setting, parameters initialization and PID


Digital PID_V100.lib lib
calculation functions

Spmc75_dmc_lib_V100.lib DMC communication program lib

3.3 DMC Interface

Speed1_Cmd: Set the rotate speed of motor

Speed1_Now: Feedback the current rotate speed of motor

Speed1_Kp: Mentioned in Section 2.5

User_R0: Current value in P_TMR3_TGRA

User_R1: Error between the desired speed and the actual speed

© Sunplus Technology Co., Ltd. PAGE 14 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Motor 1: Start and Motor 1 Stop control the motor starting/stopping

3.4 Subroutines

PIDInit ( )

Prototype void PIDInit (void)

Description Clear RAM for PID

Input Arguments None

Output Arguments none

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Calling this subroutine before setting parameters

Example PIDInit ();

PIDSetPoint ( )

Prototype void PIDSetPoint(int)

Description Set the target value of PID tuning

Input Arguments Desired value

Output Arguments None

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note

Example PIDSetPoint (2000); // The desired rotate speed is 2000pm

PIDGetSetpoint ( )

Prototype int PIDGetSetpoint(void)

Description Get the target value for PID tuning

Input Arguments None

Output Arguments The desired value set for PID tuning

Head File Spmc75_PID.h

© Sunplus Technology Co., Ltd. PAGE 15 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Library File DigitalPID_V100

Note The output value should be the same as the target value.

Example uiSpeed = PIDSetPoint (); // Get the desired rotate speed of motor

PIDSetKp ( )

Prototype void PIDSetKp(double)

Description Set Kp for PID controlling

Input Arguments Kp

Output Arguments None

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Kp represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

Kp in Fomula 2-4 is the proportion gain

Kp in Fomula 2-5 is the coefficient of ek: Kp(1 + T + Td )


Ti T

Example PIDSetKp (0.257); // Set Kp=0.257

PIDGetKp ( )

Prototype double PIDGetKp(void)

Description Get Kp set for PID tuning

Input Arguments None

Output Arguments Kp

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Kp represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

Kp in Fomula 2-4 is the proportion gain

Kp in Fomula 2-5 is the coefficient of ek: Kp(1 + T + Td )


Ti T

Example dKp = PIDSetKp ();

© Sunplus Technology Co., Ltd. PAGE 16 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

PIDSetKi( )

Prototype void PIDSetKi(double dKii)

Description Set Ki for PID tuning

Input Arguments Ki

Output Arguments None

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Ki represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

Ki in Fomula 2-4 is the integral gain Kp T


Ti

Ki in Fomula 2-5 is the coefficient of ek-1: Kp(1 +


2Td
)
T

Example PIDSetKi (0.367); // Set Ki=0.367

PIDGetKi( )

Prototype double PIDGetKi(void)

Description Get Ki set for PID tuning

Input Arguments None

Output Arguments Ki

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Ki represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

T
Ki in Fomula 2-4 is the integral gain Kp
Ti

Ki in Fomula 2-5 is the coefficient of ek-1: Kp(1 +


2Td
)
T

Example dKi = PIDSetKi ();

PIDSetKd ( )

Prototype void PIDSetKd(double dKdd)

© Sunplus Technology Co., Ltd. PAGE 17 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Description Set Kd for PID tuning

Input Arguments Kd

Output Arguments None

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Kd represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

Td
Kd in Fomula 2-4 is the derivative gain Kp
T

Td
Kd in Fomula 2-5 is the coefficient of ek-2: Kp
T

Example PIDSetKd (0.157); // Set Kd=0.157

PIDGetKd ( )

Prototype void PIDGetKd(double dKdd)

Description Get Kd set for PID tuning

Input Arguments None

Output Arguments Kd

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Kd represents different meanings when calculating by positional PID


algorithm and increment PID algorithm.

Td
Kd in Fomula 2-4 is the derivative gain Kp
T

Td
Kd in Fomula 2-5 is the coefficient of ek-2: Kp
T

Example dKd = PIDSetKd ();

IncPIDCalc ( )

Prototype int IncPIDCalc(int)

Description Calculation by increment PID algorithm

Input Arguments The current sampling value for PID tuning

© Sunplus Technology Co., Ltd. PAGE 18 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Output Arguments Calculate the increment

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Refer to (Formula 2-5) for quadrature PID algorithrm

Example uiGoalvalue += IncPIDCalc (1998); // Positional PID algorithm is duduced


from increment PID algorithm, the current sampling rotate speed is

1998rpm.

LocPIDCalc ( )

Prototype unsigned int LocPIDCalc(int)

Description Calculation by positional PID algorithm

Input Arguments The current sampling value for PID tuning

Output Arguments The absolute positional value calculated by positional PID algorithm

Head File Spmc75_PID.h

Library File DigitalPID_V100

Note Fomula 2-4 is positional PID algorithm

Example uiGoalvalue = LocPIDCalc (1998); // Positional PID algorithm, the current


sampling rotate speed is 1998rpm.

Other application functions for BLDC driving are not introduced here, please refer to
【AN_SPMC75_0003】for detailed information.

© Sunplus Technology Co., Ltd. PAGE 19 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

4 Demo Listing

4.1 Demo
/*=============================================*/
// Application Note
/*=============================================*/
#include "Spmc75_regs.h"
#include "Spmc_typedef.h"
#include "unspmacro.h"
#include "Spmc75_BLDC.h"

main()
{
P_IOA_SPE->W = 0x0000;
P_IOB_SPE->W = 0x0000;
P_IOC_SPE->W = 0x0000;

Spmc75_System_Init(); // Spmc75 system initialization

while(1)
{
BLDC_Run_Service(); // Status Monitor
NOP();
}
}
//=================================================================
// Description: IRQ0 interrupt source is XXX,used to XXX
// Notes: Error Protection
//=================================================================
void IRQ0(void) __attribute__ ((ISR));
void IRQ0(void)
{
IPM_Fault_Protect();
}
//=================================================================
// Description: IRQ1 interrupt source is XXX,used to XXX
// Notes: BLDC start up and running service
//=================================================================
void IRQ1(void) __attribute__ ((ISR));
void IRQ1(void)
{
/*=============================================================*/
/*Position detection change interrupt
/*=============================================================*/
if(P_TMR0_Status->B.PDCIF && P_TMR0_INT->B.PDCIE)
{
BLDC_Motor_Normalrun();
}

/*=============================================================*/

© Sunplus Technology Co., Ltd. PAGE 20 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

/*Timer Counter Overflow


/*=============================================================*/
if(P_TMR0_Status->B.TCVIF && P_TMR0_INT->B.TCVIE)
{
BLDC_Motor_Startup();
}
P_TMR0_Status->W = P_TMR0_Status->W;
}
//=================================================================
// Description: IRQ6 interrupt source is XXX,used to XXX
// Notes: DMC receives ISR
//=================================================================
void IRQ6(void) __attribute__ ((ISR));
void IRQ6(void)
{
if(P_INT_Status->B.UARTIF)
{
if(P_UART_Status->B.RXIF) MC75_DMC_RcvStream();
if(P_UART_Status->B.TXIF && P_UART_Ctrl->B.TXIE);
}
}
//=================================================================
// Description: IRQ7 interrupt source is XXX,used to XXX
// Notes: 512Hz timing interrupt for adjusting speed by PID controller
//=================================================================
void IRQ7(void) __attribute__ ((ISR));
void IRQ7(void)
{
if(P_INT_Status->B.CMTIF)
{
if(P_CMT_Ctrl->B.CM0IF && P_CMT_Ctrl->B.CM0IE)
{
BLDC_Motor_Actiyator();
}
P_CMT_Ctrl->W = P_CMT_Ctrl->W;
}
}

„ PID Calculation Subroutine

// Data structure
typedef struct PID
{
int SetPoint; // Desired Value
long SumError; // Accumulated errors

double Proportion; // Proportional Const


double Integral; // Integral Const
double Derivative; // Derivative Const

int LastError; //Error[-1]


int PrevError; //Error[-2]
} PID;
static PID sPID;
static PID *sptr = &sPID;

© Sunplus Technology Co., Ltd. PAGE 21 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

// PID parameters initialization


void IncPIDInit(void)
{
sptr->SumError = 0;
sptr->LastError = 0; // Error[-1]
sptr->PrevError = 0; // Error[-2]

sptr->Proportion = 0; // Proportional Const


sptr->Integral = 0; // Integral Const
sptr->Derivative = 0; // Derivative Const
sptr->SetPoint = 0;
}
// Increment PID algorithm
int IncPIDCalc(int NextPoint)
{
register int iError, iIncpid;
// Current error
iError = sptr->SetPoint - NextPoint;
// Calculate increment
iIncpid = sptr->Proportion * iError // E[k]
- sptr->Integral * sptr->LastError // E[k-1]
+ sptr->Derivative * sptr->PrevError; // E[k-2]
// Store error for the next calculation
sptr->PrevError = sptr->LastError;
sptr->LastError = iError;
// Return increment
return(iIncpid);
}
// Positonal PID algorithm
unsigned int LocPIDCalc(int NextPoint)
{
register int iError,dError;

iError = sptr->SetPoint - NextPoint; // Error


sptr->SumError += iError; // Integral
dError = iError - sptr->LastError; // Derivative
sptr->LastError = iError;

return(sptr->Proportion * iError // Proportion item


+ sptr->Integral * sptr->SumError // Integral item
+ sptr->Derivative * dError); // Derivative item
}

4.2 Main Process Description

The main program mainly performs the system initialization. The operations for motor are
processed within the interrupt service routines. The interruptions includes: IRQ0
input/output error interrupt, IRQ1 PDC and TCV interrupt, IRQ6 UART RXD interrupt and
CMT0 timing interrupt. Figure 4-1 is the main program flowchart.

© Sunplus Technology Co., Ltd. PAGE 22 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Figure 4-1 BLDC Main Program

4.3 ISR Description

Error input, output short circuit, PDC, TCV, RXD and CMT0 interrupt routines helps to
control BLDC starting, working, speed adjusting and error protection. The default
parameters are all set in the system initialization routines. Figure 4-2 shows the interrupt
operation process of PDC and TCV for your reference.

Figure 4-2 PDC and TCV Interrupt Operation

© Sunplus Technology Co., Ltd. PAGE 23 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

5 MCU Resource

CPU Type SPMC75F2413A Package QFP80-0.8

crystal Frequency 6MHz


Oscillator
external Input frequency

WATCHDOG Enable Disable

IOB[0..6]: Motor drive interface

IOB[8..10]: Position detect interface


IO port Use
IOB14: Enable motor drive

IOC[0..1]: UART

PDC0 Position detect and speed measurement

Timer MCP3 Generate motor driving signal

CMT0 Timing for PID tuning

PDC0 (IRQ1): Speed measurement and timing

MCP3 (IRQ3): Generate motor driving signal


Interrupt
UART (IRQ6): Serial communication for MCU

CMT0 (IRQ7PID): Timing for PID tuning

ROM 6.34K Words

© Sunplus Technology Co., Ltd. PAGE 24 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

6 Test

This test adopts PID design method for BLDC motor speed control with Hall position
sensor by upper phase PWM control with 120 degrees. The hardware schematic and
how to drive BLDC can take 【 AN_SPMC75_0003】 for reference. Kp should be
predefined in resource program After that, Kp can be adjusted using DMC toolkit in
which it will be enlarged 1000 times. For instance, if Kp = 0.105, then the corresponding
parameter in DMC toolkit is 105, within the range of (400, 10). For the best effect, you
need to adopt other tuning methods.

 Notice

„ The choise of PID parameters is ralated with carrier frequency of PWM. The higher the carrier
frequency, the shorter the range set by【P_TMRx_TGRA】and the faster the adjustment. Therefore, to

obtain the best PID parameters, this factor is recommanded to be considered.

„ If DMC tool is used to adjust Kp of PID controller, the rotate speed (Speed1_Cmd) and Kp (Speed1_Kp)
should be set first, then start up Motor1; if fixed Kp of PID controller (fixed in program) is used, the rotate

speed (Speed1_Cmd) should be set first, then start up Motor1.

„ When PID parameters are set using DMC tool, the relation between Speed1_Kp and Kp is
Speed1_Kp=1000Kp, which means if Kp is 0.125, Speed1_Kp should be 125.

6.1 Response Curves

All tests are performed under the circumstance of no-load and 6KHz PWM carrier
frequency.

„ Speed1_Kp=10, thus Kp= 0.01. Figure 6-1 shows the response curve when the rotate
speed ranges from 0rpm to 2000rpm.

© Sunplus Technology Co., Ltd. PAGE 25 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Figure 6-1 Response Curve (Kp=0.01)

„ Speed1_Kp=105, thus Kp=0.105. Figure 6-2 shows the response curve when the
rotate speed ranges from 0rpm to 2000rpm.

Figure 6-2 Response Curve (Kp=0.105)

© Sunplus Technology Co., Ltd. PAGE 26 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

„ Speed1_Kp=180, thus Kp= 0.180. Figure 6-3 shows the response curve when the
rotate speed ranges from 0rpm to 2000rpm.

Figure 6-3 Response Curve ( Kp=0.180)

„ Speed1_Kp=250, thus Kp=0.250. Figure 6-4 shows the response curve when the
rotate speed ranges from 0rpm to 2000rpm.

© Sunplus Technology Co., Ltd. PAGE 27 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

Figure 6-4 Response Curve (Kp=0.250)

© Sunplus Technology Co., Ltd. PAGE 28 V1.3 - Dec 22, 2006


Digital PID Speed Controller for Motor Drive Applications

7 Reference

【1】SUNPLUS. SPMC75F2413A Programming GuideV1.0. Oct 12, 2004.

【2】Zhang Chen. BLDC Fundamentals and Applications Version 2. China Machine


Press.

【3】Wang Xiaoming. Motor Control Based on MCU. Beijing University of Aeronautics


and Astronautics Press.

【4】Yu Yongquan, Zeng Bi. Fuzzy Logic Control Based on MCU. Beijing University of
Aeronautics and Astronautics Press.

© Sunplus Technology Co., Ltd. PAGE 29 V1.3 - Dec 22, 2006

You might also like