http://bbs.21ic.com/upfiles/img/20091/2009117232923483.pdf

Sensing - Universal PID-Thermoregulator
AN2208
Author: Andrew Smetana
Associated Project: Yes
Associated Part Family: CY8C27xxx
GET FREE SAMPLES HERE
Software Version: PSoC Designer™ 4.2
Associated Application Notes: AN2120, AN2148
Application Note Abstract
This Application Note describes implementation of a digital temperature PID controller. Various temperature control system
configurations and aspects of their practical implementation are analyzed. Two types of temperature sensors are applied:
thermocouple and platinum RTD sensor. The PSoC® device supports two heat power control methods: phase and numeral
impulse. The wide variety of system configurations allows use of thermoregulators in different industrial, commercial, and
residential systems, where temperature control is needed.
After the parameters are determined, implementation of
controller algorithms is a simple task.
Introduction
Regulators can be developed using analog and digital
techniques. Different mathematical methods are needed to
analyze and design analog and digital regulators. Though
digital technology can replicate analog system operation,
its abilities go much further. For example, nonlinear and
self-adjusting systems, which are difficult to create using
only an analog system, can be designed. The main issue
in digital control is regulator structure and parameter
definition.
Regulator systems are widespread in industry
applications. In many cases, the process is passed with a
preset temperature profile. These applications need a
corresponding regulator to satisfy process requirements.
The structure of the simplest regulator is presented in
Figure 1.
Figure 1. Structure of the Simplest Regulator
z(t)
w(t)
Σ
e(t)
Regulator
Gr
u(t)
Control object
y(t)
-1
This structure presents an automatic control system with
feedback. See the following definitions:
w(t): System function algorithm
u(t): Control effect
Examples of output variables are: temperature in the
stove, the engine shaft rotation speed, liquid level in the
cistern, etc. The key to temperature control is to constantly
adjust the output variable, y(t), so that it is near the value
of w(t). Doing this, will minimize the control error, e(t).
z(t): External disturbance impact, which must be
minimized
y(t): Output variable
e(t) = w(t) – y(t): Output variable y(t) deviation from
required value w(t)
March 3, 2005
Document No. 001-32905 Rev. **
1
[+] Feedback
AN2208
Temperature adjustments can be made with an automatic
Regulator, Gr (Figure 1), which is described by control
law:
u(t) = Gr[e(t)].
To select the correct control law, the automatic regulator
must know the mathematical model of the control object:
y(t) = Go[u(t)].
The mathematical model is usually a nonlinear, ordinary
system of differential equations or differential equations in
partial derivatives. Identifying the form and coefficients of
these equations is done via the control object identification
task. For conventional systems, mathematical models are
commonly used and then the principal task is identification
of equation coefficients. In many cases, these coefficients
can be selected empirically during the system tuning
process or by performing some special tests.
Some features of control systems with feedback indicators
are:
Independent corrective action initialization when
control variables deviate from reference values.
Dynamic regulation of temperature variation with
minimal detail.
The control law in Equation 1 is the main factor for
designing automatic control systems. Ideally, an optimal
regulator synthesis could fulfill these requirements.
However, it is a challenge to find one of good quality at an
economical price. Inexpensive alternatives used in many
industry applications are the simplest and most common
types of linear regulators: P-, PI- and PID-regulators.
The ideal equation of a PID-regulator is:
⎡
1
u (t ) = K ⎢e(t ) +
T
I
⎣
t
∫0 e(τ )dτ + TD
de(t ) ⎤
⎥
dt ⎦
Equation 1
Where К is the controller gain, ТI is the integral time
constant and ТD is the derivative time constant.
These three parameters can be selected during the
regulator tuning process to calculate the system
functioning algorithm.
The described automatic control system is continuous.
That is, it uses continuous time.
Using microprocessor techniques during construction of
the regulator, the input and output variables must be
measured in time and converted to digital using the ADC.
At the same time, the PID-regulator equation should be
transformed by changing the derivatives by finite
differences and integrals by finite sums. Using the
following method for substitution of integrals by finite
sums, yields:
⎡
⎤
T k
T
u ( k ) = K ⎢e( k ) + 0 ∑ e(i − 1) + D [e( k ) − e(k − 1)]⎥
TI i = 0
T0
⎢⎣
⎥⎦
k = 0,1,...
Equation 2
The advantage of digital regulators is their ability to
operate remotely to easily exchange data through multiple
communication channels. Despite this advantage, the
analog method is still the most reliable, most common,
and its data is easily converted to digital.
Regulator Characteristics
The developed regulator is implemented using principles
of a digital PID-controller. Its main task is maintaining the
object’s preset temperature level in low- or high-wattage
heaters. For example, a low-wattage heater could be a
soldering iron, where a preset soldering temperature is
required. An example of a high-wattage heater is an
industrial electric stove. For temperature sensors in this
project, both resistive temperature detectors RTD (HEL700) and thermocouple (T-type) sensors are used. Both
are widely used in the industry. There are two methods for
power transfer: phase and numeral-impulse. The numeralimpulse method is used to control the inertial load, which
works on the principle of sending in load some half-cycled
of AC mains with an immediate delay. In this project, this
method was modified to take into account constant
temperature fluctuation.
To simplify the tuning process for the thermoregulator, the
EIA-232 (RS-232) interface is used and a command
language developed. Therefore, it is possible to use
standard terminal programs to set system parameters and
obtain current status information. The user-friendly
interface to control the device and monitor the regulator
process was developed using the Win32 Application and
C++Builder.
Using this setup, the universal thermoregulator with
different kinds of sensors, loads and power control
methods is determined. The desired combination of
system functions is dependent on industry regulator
requirements.
Regulator Flowchart
The regulator flowchart is presented in Figure 2. Note that
the gray blocks identify the external units for the PSoC
device.
The regulator structure consists of two main parts: a
synchronization system with a power control block and a
measurement module with a PID-controller. These two
subsystems work independently and concurrently. The
central unit of the synchronization system is the interrupt
service (Network_Sync_ISR), which is called each time a
signal in the AC network crosses zero level. Then this
subroutine reads the last value of the control signal (PID
control value), which is formed by the PID-controller block
(PID controller). Depending on the power control method,
the phase method or numeral-impulse method is initiated
to generate the control signals. The power control method
settings are determined during PSoC device initialization
after reset, by questioning the jumpers (JUMPERS). The
phase method uses a pulse width modulator (PWM) to
form the control signal.
t
counts out the discrete time.
T0
March 3, 2005
Document No. 001-32905 Rev. **
2
[+] Feedback
AN2208
This signal is used to control the electronic switch Power
Switch (FET for the low power heater or optotriac for the
high power heater).
Consider the working principles. The active block of this
subsystem is the translation module (Translation Module).
It selects the sensor to read its signals, depending on the
jumpers’ states. Sensor selection is completed by means
of an internal multiplexer (MUX). The multiplexed signal is
gained by the instrumentation amplifier module (INSTR
AMP). The gain factor is different for the thermocouple
and RTD. The analog signal is then converted into a digital
representation using ADC1.
The analog piece of the synchronization system is
implemented by an external node (Network Sync Circuit)
and internal PSoC blocks. The zero crossing detection
module (Zero Crossing Detection) uses the Schmitt trigger
scheme, which features internal hysteresis. This approach
preserves generation of multiple false synchronization
signals, especially in moments of load commutation. Upon
output from these blocks, a digital signal is formed, which
generates an interrupt signal.
Figure 2. Regulator Flowchart
Sensor Error LED
FLASH
Memory
Set PID’s Parameters
Sensor
Connection
Control
Rref
Sensor
MUX
INSTR
AMP
RTD
Sensor
TC
Sensor
Tcurr
Translation
Module
TMP37
Sensor
PC
(Optional)
PID
Controller
ADC code into
Temperature
RF LPF
EIA-232
(RS-232)
PID
Constituents
Digital
Filter
ADC1
Terminal
Command
Interpreter
Get PID’s Parameters
ADC2
PID Control Value
TC Connection Control
Circuit
Software
Network_Sync_ISR
AC
Mains
Network
Sync
Circuit
Zero
Crossing
Detection
Interrupt Signal
HEATER
Duty Cycle
Phase Power
Control
PWM
MUX
Power
Switch
AC
Mains
Pulses Count
Control
Regulator LED
External
Sensor Kind
Power Control Method
JUMPERS
Internal
To prevent external noise from influencing the regulation
process, the digital signal is passed through a nonlinear
digital filter (Digital Filter), on which the output code ready
for processing is set. The translation module (Translation
Module) translates the ADC code into temperature values
using the sensors’ characteristic tables. The translation
methods and specific measurement methods between the
thermocouple and the RTD are different. Thus, it is
necessary to read the voltage using RTD measurement on
two resistors, Rref Sensor and RTD Sensor, at the same
time. The RTD resistance is then calculated and the
corresponding temperature value found using a table. The
thermocouple measurement method uses an additional
low cost temperature sensor TMP37, which measures the
thermocouple’s cold junction temperature. To accomplish
this, it utilizes ADC2. Note, ADC1 and ADC2 work
simultaneously. To get the absolute temperature of a
March 3, 2005
control object, the thermocouple and TMP37 temperatures
are calculated. The object’s temperature is then passed to
a PID-controller unit, which compares this value with a
reference temperature and generates corresponding
control signals.
To reduce unwanted influence of stray radio noise on
thermocouple wires, the signal is passed through an
external RC low-pass filter (RF LPF). The sensor break
control is provided by two units: TC Connection Control
and Sensor Connection Control. If a sensor break is
detected, the red LED turns on (Sensor Error LED), the
regulator output is set to zero (i.e., it disconnects load),
and the device waits for sensor connection.
A UART User Module is used for debugging and to tune
the thermoregulator block. The regulator’s parameters are
loaded through the PSoC’s Flash memory. The UART also
Document No. 001-32905 Rev. **
3
[+] Feedback
AN2208
Figure 3. Numeral-Impulse Method
provides a means for receiving regulator status. The
software implemented Terminal Command Interpreter
block interprets the command language of the device
terminal module.
Power Control
1
2
3
4
5
Two methods can be used to transfer power in the load:
6
7
8
9
10
6
7
8
9
10
6
7
8
9
10
A
Phase method, in which the value of power delivered
is determined in changing of phase angle.
Numeral-impulse control is performed by whole halfcycles. Impulses are directly carried after voltage in
the AC mains crosses zero level and during the time
the load is connected to the AC mains. Some halfcycles are passed through the load during this time.
The numeral-impulse method is utilized for power control
in loads with long reaction times (inertial load). The
advantage of this method is that load commutation
moments concur with moments of zero crossing, so the
level of radiated radio noise is sharply reduced. The
minimal amount of energy entered in the load equals the
energy that is supplied during one AC mains half-cycle.
For example, to get a 10% increase, there is a need to
have a period of 10 half-cycles. In Figure 3А is a sequence
of impulses on control electrode for 30% power in load.
The electronic switch is on during the first three halfcycles, and off during the last seven. This sequence is
repeated.
1
2
3
4
5
B
1
2
3
4
5
C
It is more logical to distribute half-cycles uniformly during
the whole sequence period when the switch is on. The
problem of uniform distribution of N impulses in sequence
with length M (N ≤ M) is solved by Bresenham’s algorithm,
which is used in raster graphics for drawing slanting lines.
This algorithm is implemented using integer arithmetic,
simplifying the programming. Figure 3В depicts impulse
distribution for the same 30% power, but using
Bresenham’s algorithm. The raster line drawing using the
same algorithm is shown in Figure 3С. In this project,
Bresenham’s algorithm provides gradual temperature
adjustments without large fluctuations during the
regulation period.
Figure 4. Power Control Method Comparison
Phase Control
Numeral-Impulse Control
AC mains
LOAD
1
March 3, 2005
2
3
4
5
6
7
8
9 10
1
2
3
Document No. 001-32905 Rev. **
4
5
6
7
8
9 10
4
[+] Feedback
AN2208
Power control method comparisons are shown in Figure 4.
Note, a 30% half-cycle time of the switch on in phase
method, does not correspond to 30% power transfer in
load. For sinusoidal signals, the output power has
nonlinear dependence on electronic switch phase angle
opening. This feature does not prevent correct
temperature regulation since the system includes
feedback contours.
The regulator uses three kinds of sensors: resistors (R11,
RTD1), thermocouple, and temperature sensor TMP37.
For temperature measurement on the basis of platinum
RTD, a 4-wire measurement circuit is used. The
advantage of this method is precise measurement
regardless of the length of connecting wires (from sensor
to board). The RTD sensor resistance is calculated
according to the following equation:
RRTD =
Hardware Implementation
The hardware solution of this project is presented in two
parts: the PSoC internals and the regulator’s external
schematics.
Regulator Schematics
The regulator schematic circuit is presented in Figure 5.
The connecting link of all components is the PSoC device,
which reads and processes sensor signals. It then
generates control signals and provides communication
through the UART.
To provide network synchronization, the following
elements are used: a transformer, a diode rectifier, and
also a circuit formed from resistor R14 and Zener Diode
D5 with a stabilizing voltage, 3.3V. The output Net_Sync of
this circuit is connected to the PSoC comparator. The
resistor R15 is used for discharging stray capacitance,
which is not able to reset the sinusoidal signal to reach
zero level.
The resistors R16, R17 and FET Q1 are used to control
the low power load. This load on the schematic is depicted
as resistor R12. The optotriac U5 is used to control high
power heaters. The control signal, Gate Control, is
generated by the PSoC. The regulation process is
provided by LED D6.
VRRTD
VR11
R11
Equation 3
The circuit for measuring voltage on the thermocouple is
presented by functional blocks. Components R5, R6, R8,
R9 and C3, C6, C7 form a low-pass filter to filter out RF
noise. Resistors R1, R2, R3 and R4 are used to bring the
thermocouple signal into the working range of the
instrumentation
amplifier.
For
the
thermocouple
connection, two digital pins are utilized (P2[5] and P2[7]).
These pins are set to logic 1 and 0. If the thermocouple
breaks, the ADC output is set at the maximum code and
the LED D1 turns on. The RTD connection control is
achieved without use of digital pins; only the ADC code is
controlled digitally. In temperature measurement mode,
P2[5] and P2[7] are in High-Z state. The sensor, TMP37, is
used to measure temperature of thermocouple cold
junction. According to its output, the set voltage is directly
proportional to the temperature of its package. This sensor
provides 500 mV output at 25ºC and its scale factor equals
20 mV/ºC. The absolute temperature is measured as:
T = TTMP 37 + ΔTTC
Equation 4
The type of sensor (thermocouple or RTD) and power
control method (phase or numeral-impulse) can be
selected using jumper J2.
The power supply of digital electronics is recognized by
the voltage regulator L78M05 and corresponding
capacitors/filters С9, С10, С11, С12. The supply unit diode
D2 prevents smooth signal flow into the synchronization
circuit.
March 3, 2005
Document No. 001-32905 Rev. **
5
[+] Feedback
AN2208
Figure 5. Regulator Schematic Circuit
VCC
VCC
R1
1K
TC+
U1
R2
1K
RTD R4
10 K
R5
Thermocouple
connector
Rref -
TCR3
10 K
R6
D1
Test +
J1
1
2
Net_Sy nc
100
100 K
C3
0.1 mkF
R8
Sensor_Error_LED
R9
100
P0[7]
P0[5]
P0[3]
P0[1]
P2[7]
P2[5]
P2[3]
P2[1]
SMP
P1[7]
P1[5]
P1[3]
P1[1]
Vss
Vcc
P0[6]
P0[4]
P0[2]
P0[0]
P2[6]
P2[4]
P2[2]
P2[0]
Xres
P1[6]
P1[4]
P1[2]
P1[0]
28
27
26
25
24
23
22
21
20
19
18
17
16
15
RTD +
Rref +
U2
12
9
C1
1 mkF
14
7
Gate Control
16
CY 8C27443
R7
300
Test -
CON2
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
R1OUT
R2OUT
R1IN
R2IN
T1OUT
T2OUT
T1IN
T2IN
C1+
C1C2+
C2V+
V-
VCC
GND
13
8
11
10
RxD
C4
0.1 mkF
C8
MAX232
D2
VCC
U3 L78M05/TO220
1
JUMPER4
R10
10 K
1
RTD +
AC
network
1
Vout
2
J3
2
1
CON2
1
T1
2
~12 V
4
VOUT
3
VCC
C11
0.1 mkF
C12
1000 mkF
D3
-
+
4
8
R12
BRIDGE
TRANSFORMER
R15
680
R13
820
LOW Power Heater
Gate Control
3
HEL-700
Net_Sy nc
NTP10N60
D4
R14
10 K
R16
Q1
TMP37
RTD1
VIN
C10
1000 mkF
5
3
C13
0.1 mkF
Vss
Rref -
GND
U4
t
C9
0.1 mkF
DIODE
VCC
DB9 (Female)
2
4
6
8
GND
1
3
5
7
2
REG_MODE
SENSOR KIND
0.1 mkF
0.1 mkF
J2
R11
1K
TxD
C5
C7
0.1 mkF
Rref +
1
6
2
7
3
8
4
9
5
0.1 mkF
100 K
C6
0.1 mkF
P1
C2
1
3
4
5
2
6
R17
10 K
Network_LED
1K
D5
3.3 N
RTD -
R18
10 K
R19
HIGH Power Heater
U5
1
3
2
4
D6
R20
S202T02
OPTOTRIAC
Title
Regulator_LED
100
Thermoregulator
Size
B
Document Number
<Doc>
Date:
March 3, 2005
Document No. 001-32905 Rev. **
Thursday , June 24, 2004
Rev
<Rev Code>
Sheet
1
of
1
6
[+] Feedback
AN2208
To provide communication with the PC through the COM
port, a standard level shifter, such as MAX232, can be used.
PSoC Internals
The internal chip configuration is presented in Figure 6.
Implementation of the internal structure consists of the
following components: an instrumentation amplifier
(INSAMP), two ADCs (ADC) united in a single module, a
comparator (CMP), a digital communication module (UART),
and the pulse width modulator (PWM).
March 3, 2005
To gain signals from the sensors, the instrumentation
amplifier is used and is placed in analog blocks ACB02,
ACB03, and ASD13. For multiplexing the input signal from
the sensor, the multiplexers in 2-d and 3-d analog columns
are used. The bit assignments for the amplifier inputs are
defined in register AMX_IN.
The amplifier zero shift measurement is performed by short
circuiting its inputs. For this, the input’s multiplexer in 2-d
analog column is used (controlled by register ABF_CR0).
The gain factor is dependent on the sensor type. The gain
signal is given on the input of the ADC2.
Document No. 001-32905 Rev. **
7
[+] Feedback
AN2208
Figure 6. PSoC Internal Configuration
March 3, 2005
Document No. 001-32905 Rev. **
8
[+] Feedback
AN2208
This ADC2 property ClockPhase2 is set to SWAP to
provide synchronization with the output of the
instrumentation amplifier. The ADC is a dual ADC and
occupies the following analog and digital blocks: ASC10,
ASC12, DBB00, DBB01, DBB10, and DBB11. Another
ADC (ADC1) is used to measure the signal from the
TMP37 sensor. Its input is connected directly to Р2[1].
The comparator (CMP), in ACB01, provides AC
synchronization. This module is software configured to
create a Schmitt trigger. The analog signal enters the
comparator’s input from P0[7] and is digitally output. The
Schmitt trigger output is connected to Comparator Bus 1,
which generates an interrupt signal upon zero crossing
detection.
When using the phase power control method, a PWM is
needed. With its help, the AC mains’ frequency is
calculated during device initialization and load
commutation is determined.
The UART occupies the DCB02 and DCB03 blocks. It
operates at a baud rate of 115200. The UART utilizes the
16-byte command buffer to implement the communication
interface. The receiver’s input is on P1[2], and the
transmitter output is on P0[1]. The module is clocked from
frequency source VC3 equal to SysClk/26.
For the phase method, the AC main half-cycle is
determined using the Calculate_Circuit_Frequency()
subroutine and the phase graduation step is calculated.
The
half-cycle
is
saved
in
variable
Current_Network_Period, and the phase graduation step
in variable phase_step. To calculate the AC main halfcycle, the interrupt service routine is used and its working
principles are implemented. After zero crossing detection,
the PWM is started and it works towards the next zero
crossing condition. After that, it is stopped, and its current
counter value is read and considered as a half-cycle.
When using the numeral-impulse power control method, it
is necessary to disconnect the PWM from the GPIO. This
is done by modifying the PRT1GS register.
After the initialization procedure is complete, the regulation
cycle begins. This cycle (besides the main tasks of reading
and processing sensor signals and sending their results to
the regulator) executes the sensor connection control
function, is_sensor_connected(). This control is done once
every 32 cycles. If a sensor break is detected, the heater
is disconnected and a red LED turns on. Also, during each
cycle, the presence of a UART command is verified. If a
command is detected, then its processing subroutine
terminal() is called. A visual description of this cycle is
shown in Figure 9.
Firmware Implementation
tc_get_t.c
The regulator firmware consists of modules based in
separate source files. Each module executes its own
functions. See the following:
After the sensor signals are read, the corresponding
object’s temperature must be determined. The sensor
(RTD and thermocouple) characteristic tables are stored in
the PSoC Flash memory. In this project, tables are built
with 1ºC-steps in the temperature range [-100 to 400]ºC.
The tables for the thermocouple and the RTD are based in
the tc_data.h and rtd_data.h files. The last table’s element
index is assigned in macro definition MEASURE_RANGE
in the includes.h file.
Initialization procedure and main regulation cycle.
(main.c).
PID-controller subroutine (regulator.c).
Synchronization module presented in the interrupt
service routine (ISR) (sync_int.c).
Interpolation and searching subroutines in sensor
tables (tc_get_t.c).
Terminal interface, which provides communication
using EIA-232 (RS-232) interface (terminal.c).
Each module is discussed in more detail below.
To obtain more precise regulation, temperature
interpolation is done to a quarter degree. The user can
modify the interpolation step by changing the macro
definition N in the includes.h file. Note that N is a power of
two. For example, if N=2, then the interpolation step
N
equals 1/2 = 1/4ºC. It enables the PID-controller to react
from a small temperature deviation and restore the
reference temperature.
main.c
Interpolation assumes that the characteristic interval of the
sensor is linear.
This file is the main connection/link of the firmware. Its
flowchart is shown in Figure 9. It executes two main
functions: device initialization and regulation. During the
initialization process, when all of the PSoC modules start,
jumpers determine which current sensor type and power
control method is used. Current settings are saved in
variables SENSOR_TYPE and REG_METHOD, which are
passed
in
subroutines
Set_Sensor()
and
Set_Regulation_Mode().
When the temperature is measured using a thermocouple
and after the signals are digitized, the ADC code clearly
corresponds to the defined temperature. To minimize
presser time, the table is built from ADC code, but does
not use corresponding voltages. All of the table’s
calculations can be implemented using any programming
language. The table’s file for this project tc_data.h is
generated automatically. The value of table’s element
index was calculated according to the following equation:
When the sensor type is assigned, the pointer to the
corresponding sensor’s table is initialized, and the
instrumentation amplifier gain is set.
March 3, 2005
13
ADC _ code = U TC • 93.024 • 2
Document No. 001-32905 Rev. **
2.6
Equation 5
9
[+] Feedback
AN2208
Figure 7. Search Algorithm
In this equation, voltage is expressed in volts. 93.024 is
the gain of the instrumentation amplifier. (Gain can be an
additional source of calculation error, as it can float
slightly.) 13 is the digit capacity of the ADC and 2.6 volts is
the measurement range of the ADC.
START
The ADC code is calculated and its corresponding
temperature value in the table is found. The accordance
between temperature and the table’s element index is
calculated using the following equation:
T = Element _ No − T _ Zero _ Index
prev = get _prev ()
next = get _next ()
dp = abs(ADC-prev )
dc = abs(ADC-curr)
dn = abs (ADC-next)
Equation 6
Element_No is the table’s element
T_Zero_Index is the table’s element
corresponds to 0ºС.
index
index
and
that
dp < dc
This parameter is assigned in the includes.h file.
YES
The elements in the RTD table are resistance values
corresponding to temperatures. To increase the quality of
interpolation, each element is multiplied by 10. The
following equation is used:
RT = R0 (1 + A • T + B • T − 100 • C • T + C • T ) • 10
2
3
4
NO
p=p- 1
curr = next
Equation 7
R0 is the sensor resistance at 0ºС. A, B, and C are the
sensor characteristic coefficients and 10 is the
interpolation enhancing coefficient.
dn < dc
NO
YES
Searching the Algorithm
p=p+1
Beginning with the physical properties of the
heating/cooling process, an object’s temperature cannot
change in spurts. In other words, temperature change is a
continuous function through time. Searching is carried out
relative to last fixed temperature.
The previous and next temperatures are found using
interpolation. The direction along the table is determined to
reach the current temperature. A flowchart for this
algorithm is shown in Figure 7. This flowchart uses the
following symbols:
curr = next
return p
regulator.c
ADC – current ADC code, for which the temperature
is looking.
After interpolating and searching the tables, the subroutine
of the PID-controller is called in the manner by which the
current temperature was determined. The subroutine’s
parameter is the object’s temperature.
curr – determines the result of previous search at the
start of search procedure.
Upon the output of the regulator, the digital code is set
based on the control signals.
prev – stores previous values to curr.
The regulation algorithm is implemented according to the
following equation:
next – stores value following curr.
k
The algorithm executes cyclically. The absolute difference
between the desired quantity ADC and the current value
from table curr is not minimal.
March 3, 2005
u (k ) = K p • e(k ) + K I • ∑ e(i ) + K D [e(k ) − e(k − 1)] Equation 8
Document No. 001-32905 Rev. **
i =0
10
[+] Feedback
AN2208
Differentiation amplifies noise. To reduce the influence of
differentiation, derivatives are calculated using two data
points. To calculate the derivative in this project, the
numerical method of left fifth differences was utilized:
dy
1
≈
(25 y0 − 48 y−1 + 36 y− 2 − 16 y−3 + 3 y− 4 )
dtt =t 0 12h
Equation 9
The output controller value is determined by the value of
PWMcount
and
is
limited
in
range
by
[0..PWM_Resolution].
sync_int.c
The network synchronization subroutine is implemented as
an ISR from the comparator bus. Figure 8 shows its flow.
This method reduces the influence of noise on the final
result.
The flowchart of the PID-controller algorithm is presented
in Figure 10. The software control implementation must
limit each element to a fixed range.
Following is a description of each regulator parameter and
corresponding variable in the program:
Tref – reference temperature, which is kept up by the
regulator.
Figure 8. Synchronization ISR
START
YES
Mode = 1
NO
YES
Mode = 2
NO
YES
Mode = 3
PWM_Stop
Mode=0
PWM_Stop
PWM_WritePeriod (Current_Network_Period)
PWM_WritePulseWidth (duty_cycle)
PWM_Start
NO
Prop_Gain – proportional gain parameter (KP).
YES
Intl_Gain – integral gain parameter (KI).
PWM_Start
Mode=2
Mode = 4
Deri_Gain – derivative gain parameter (KD).
Execute Bresenheim algorithm to determine
contol signal
NO
Send control signal to port
PROP_REG_LIMIT – working range of proportional
element.
FINISH
INTL_REG_LIMIT – working range of integral
element.
DERI_REG_LIMIT – working range of derivative
element.
REG_RANGE – working range of regulator (set in
degrees).
PWM_RESOLUTION – determines the number of
regulation steps. For the phase method, this is the
amount of segments on which a half-cycle is divided.
For the numeral-impulse method, this is the regulation
period in half-cycles.
th
All of these parameters are based in the 255 block of
Flash memory starting at address 0x3FC0. Parameters
can be changed in-system using the terminal program.
SCALE_FACTOR – this is a divider by which the
calculated control value is limited in the range
[0..PWM_Resolution]. This parameter is used in the
following equation:
PWMcount =
PropTerm + IntlTerm + DenTerm
Equation 10
SCALE _ FACTOR
This ISR is implemented in the form of a finite state
machine. That is, it remembers its previous state. This
feature is used by Bresenham’s algorithm to generate
control signals during periodic AC main half-cycles.
As can be seen in Figure 8, the subroutine works in four
modes, each determined by the global variable mode.
Modes 1 and 2 are used to determine the AC main halfcycle. In Mode 1 (after zero crossing detection), the PWM
starts and Mode 2 switches on automatically. In Mode 2,
the PSoC device waits for the next zero crossing
condition.
When this condition becomes true, the PWM is stopped
and the variable mode is set to 0 (this is the signal for the
subroutine Calculate_Circuit_Frequency() to finish halfcycle measuring). Then, in the main program, the current
PWM counter is read and treated as half-cycle.
Mode 3 is used by the phase method to form control
signals. This subroutine branch starts the PWM with a
given duty cycle. In Mode 4, the Bresenham’s algorithm,
which is utilized by the numeral-impulse power control
method, is implemented.
The SCALE_FACTOR parameter is set in firmware and
cannot be modified via the UART. This should be noted
when tuning the PID-controller.
March 3, 2005
Document No. 001-32905 Rev. **
11
[+] Feedback
AN2208
terminal.c
Interface Elements
To make in-system regulator tuning and configuration
easier, a UART is included in its structure. The command
language that enables communication with the PSoC
device by means of standard terminal programs (e.g.,
HyperTerminal) is based on the UART. The СOM-port is
configured as follows:
Once the program is started, communication with the
thermoregulator must be established. Select the COM-port
to which the PSoC device is connected. Communication is
then set by pressing the CONNECT with PSoC button.
After connection is established, the user can tune the
regulator.
Baud Rate (bit/sec):
Data Bits:
8
Parity:
None
Stop Bits:
1
115200
Using the implemented commands, regulator parameters
can be edited and saved to Flash. Also, there are
commands for receiving current status information. The full
list of supported commands is presented in Table 1.
The carriage return symbol is used (ASCII code 0x0D) as
a command terminator. Therefore, after typing a
command, it is necessary to press the [Enter] key. The
UART uses [Space Bar] (ASCII code 0x20) as a
parameter delimiter in the command. All commands are to
be typed using capital letters.
Note that after the setting command is entered, and in the
case of its successful completion, the UART sends the
answer “OK!” If an inadmissible command is entered, the
answer is “Unknown!”
Terminal Program
To send commands automatically to the PSoC and to
create a user-friendly interface, a program was developed
using Win32 Application and C++Builder. The program
allows the user to visually parameterize, and also enables
real-time graph building. Graphs are constructed
simultaneously. The first graph shows the dependence of
temperature on time. In the second graph, the values of
proportional integral and derivative constituents are traced.
These tools make it easier for the user to tune the
regulator. Figure 11 shows the appearance of the main
application.
March 3, 2005
Controller parameters are entered in the text fields. To
save the typed parameters to Flash, press the SAVE
REGULATOR PARAMETERS IN PSoC’S FLASH button.
The terminal program does not correct entered data. It
merely sends the data to the PSoC, which translates data
strings into a digital representation. If invalid symbols are
detected, this parameter is assigned a zero. The data is
returned to the terminal program and shown in the
corresponding text fields. Note that writing to Flash works
correctly if the device is not in debug mode. Using the
PSoC ICE, it takes about 150 ms to write one Flash block,
but on an actual chip, this time is about 10 ms.
Use the following buttons to construct the graph:
START construction of graph – start graph
constriction.
CLEAR graphs – clear graph forms.
STOP construction of graph – stop graph
construction.
To show the graphs on the screen, check Show
Temperature Graph and Show PID Constituents Graph.
As graphs are constructed in real-time, note that the
regulator status is received with the frequency of 5 Hz.
Figure 12 shows examples of graph forms.
Document No. 001-32905 Rev. **
12
[+] Feedback
AN2208
Table 1. List of Terminal Commands
Command Format
GET T
Description
To get object’s temperature (integer and fraction).
For example:
GET T
70 3
Current temperature equals 70 + ¾ = 70.75ºC (if interpolation step is ¼).
GET P
Get current proportional element (PropTerm).
GET I
Get current integral element (IntlTerm).
GET D
Get current derivative element (IntlTerm).
GET
Get current temperature, proportional, integral and derivative elements.
For example:
GET
70 3 1000 -500 300
70 3 – temperature
1000 – proportional element
-500 – integral element
300 – derivative element
PG <NUMBER>
Set proportional gain (PropGain).
For example:
PG 4000
OK!
IG <NUMBER>
Set integral gain (IntlGain).
DG <NUMBER>
Set derivative gain (DeriGain).
PL <NUMBER>
Set limitation of proportional element (PROP_REG_LIMIT).
IL <NUMBER>
Set limitation of integral element (INTL_REG_LIMIT).
DL <NUMBER>
Set limitation of derivative element (DERI_REG_LIMIT).
RR <NUMBER>
Set regulation range in degrees (REG_RANGE).
PWM_RES <NUMBER>
Set regulation step quantity (PWM_RESOLUTION).
CONNECT
Set connection with PSoC. For example:
CONNECT
OK!
SET_T <NUMBER>
Set reference temperature (Tref).
GET_ALL_PARAMS
Get all parameters. For example:
GET_ALL_PARAMS
70 250 3 0 7000 20000 8000 15 10 2
70
– reference temperature (Tref)
250 – proportional gain (PropGain)
3
– integral gain (IntlGain)
0
– derivative gain (DeriGain)
7000 – limitation of proportional element (PROP_REG_LIMIT)
20000 – limitation of integral element (INTL_REG_LIMIT)
8000 – limitation of derivative element (DERI_REG_LIMIT)
March 3, 2005
15
– regulation range (REG_RANGE)
10
– regulation step quantity (PWM_RESOLUTION)
2
– interpolation coefficient (N). Interpolation step = 1/2 ºC
N
Document No. 001-32905 Rev. **
13
[+] Feedback
AN2208
Figure 9. Main Loop
START
Questioning jumpers, then sets sensor
kind and power control method
Initialize hardware
NO
Is sensor connected?
Light on Sensor Error LED
YES
Shutdown Heater
Shutdown Error LED
Zero_Data = get_zero_offset()
NO
Sensor_Kind = RTD_Sensor?
YES
Sensor_Data=get_sensor_data(RTD_Sensor)
Sensor_Data=get_sensor_data(TC_Sensor)
Vrtd=Sensor_Data – Zero_Data
Vtc = Sensor_Data – Zero_Data
Sensor_Data=get_sensor_data(Rref_Sensor)
Get TMP37 data in tmpData
Vref=Sensor_Data – Zero_Data
Tcj = tmpData*2600/(20*8192)
Rrtd = (Vrtd * Rref / Vref) * 10
T = get_temp(Vtc)
Sensor_Temperature = get_temp(Rrtd)
Sensor_Temperature = Tcj + T
regulator(Sensor_Temperature)
YES
Has UART got command?
Process command
NO
March 3, 2005
Document No. 001-32905 Rev. **
14
[+] Feedback
AN2208
Figure 10. PID-Controller Flowchart
START
CurrError = Tref – Tcurr
PropTerm = CurrError * PropGain
Limit PropTerm in range
[-Prop_Reg_Limit..+Prop_Reg_Limit]
Calculate derivative constituent DeriTerm
using formula of left fifth differences and
multiply it by DeriGain
Limit DeriTerm in range
[-Deri_Reg_Limit..+Deri_Reg_Limit]
LastError = CurrError
AccuError = AccuError + CurrError
Limit AccuError in range
[-Intl_Reg_Limit..+Intl_Reg_Limit]
IntlTerm = AccuError * IntlGain
Limit IntlTerm in range
[-Intl_Reg_Limit..+Intl_Reg_Limit]
NO
CurrError > reg_range
YES
PWMcount = PWM_Resolution
AccuError = 0
NO
CurrError > reg_range
YES
PWMcount = 0
AccuError = 0
PWMcount = (PropTerm + IntlTerm + DeriTerm) /
SCALE_FACTOR
Limit PWMcount in range
[0..PWM_Resolution]
set_control_value (PWMcount)
FINISH
March 3, 2005
Document No. 001-32905 Rev. **
15
[+] Feedback
AN2208
Figure 11. Terminal Program’s Main Window
March 3, 2005
Document No. 001-32905 Rev. **
16
[+] Feedback
AN2208
Summary
The PID-thermoregulator described in this Application
Note involves different variations of temperature control
systems. The following options are available: load type,
temperature sensor type (thermocouple or RTD), and
power control method (phase or numeral-impulse). These
options simplify thermoregulator design for specific
applications. Among the advantages of the presented
thermoregulator is the UART’s precise tuning capability.
The associated terminal program allows users to visually
observe the regulation process and easily adjust as
needed.
To adapt this thermoregulator to specific technology
conditions, only minimal changes to software are
necessary. Most of the changes are due to the type of
sensor used (thermocouple or RTD). In this case, the
sensor’s characteristic table must be generated and
inserted in the regulator project along with minute
modifications to the macro definitions in the includes.h file.
Then the PID-parameter’s tuning can be performed by
means of the terminal program.
March 3, 2005
Document No. 001-32905 Rev. **
17
[+] Feedback
AN2208
Figure 12. Graph Construction using Terminal Program
March 3, 2005
Document No. 001-32905 Rev. **
18
[+] Feedback
AN2208
About the Author
Name:
Title:
Education:
Contact:
Andrew Smetana
Undergraduate Student
Ukraine National University “Lvov
Poltechnic.”
Computer Engineering Chair.
[email protected]
In March of 2007, Cypress recataloged all of its Application Notes using a new documentation number and revision code. This new documentation
number and revision code (001-xxxxx, beginning with rev. **), located in the footer of the document, will be used in all subsequent revisions.
PSoC is a registered trademark of Cypress Semiconductor Corp. "Programmable System-on-Chip," PSoC Designer, and PSoC Express are trademarks
of Cypress Semiconductor Corp. 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: 408-943-2600
Fax: 408-943-4730
http://www.cypress.com/
© Cypress Semiconductor Corporation, 2005-2007. The information contained herein is subject to change without notice. Cypress Semiconductor
Corporation assumes no responsibility for the use of any circuitry other than circuitry embodied in a Cypress product. Nor does it convey or imply any
license under patent or other rights. Cypress products are not warranted nor intended to be used for medical, life support, life saving, critical control or
safety applications, unless pursuant to an express written agreement with Cypress. Furthermore, Cypress does not authorize its products for use as
critical components in life-support systems where a malfunction or failure may reasonably be expected to result in significant injury to the user. The
inclusion of Cypress products in life-support systems application implies that the manufacturer assumes all risk of such use and in doing so indemnifies
Cypress against all charges.
This Source Code (software and/or firmware) is owned by Cypress Semiconductor Corporation (Cypress) and is protected by and subject to worldwide
patent protection (United States and foreign), United States copyright laws and international treaty provisions. Cypress hereby grants to licensee a
personal, non-exclusive, non-transferable license to copy, use, modify, create derivative works of, and compile the Cypress Source Code and derivative
works for the sole purpose of creating custom software and or firmware in support of licensee product to be used only in conjunction with a Cypress
integrated circuit as specified in the applicable agreement. Any reproduction, modification, translation, compilation, or representation of this Source
Code except as specified above is prohibited without the express written permission of Cypress.
Disclaimer: CYPRESS MAKES NO WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, WITH REGARD TO THIS MATERIAL, INCLUDING, BUT
NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. Cypress reserves the
right to make changes without further notice to the materials described herein. Cypress does not assume any liability arising out of the application or
use of any product or circuit described herein. Cypress does not authorize its products for use as critical components in life-support systems where a
malfunction or failure may reasonably be expected to result in significant injury to the user. The inclusion of Cypress’ product in a life-support systems
application implies that the manufacturer assumes all risk of such use and in doing so indemnifies Cypress against all charges.
Use may be limited by and subject to the applicable Cypress software license agreement.
March 3, 2005
Document No. 001-32905 Rev. **
19
[+] Feedback