Real Time DC Water Tank Level Control Using Arduino Mega 2560

Download as pdf or txt
Download as pdf or txt
You are on page 1of 6

Real Time DC Water Tank Level Control using

Arduino Mega 2560


Jie Sheng
School of Engineering and Technology
University of Washington, Tacoma
Tacoma, USA
[email protected]

Abstract — Control engineering is an interdisciplinary field discussion regarding the controller design, as presented in [5].
requiring knowledges on math and physics, circuits, sensors, In our teaching efforts, we want to emphasize the importance of
actuator, and microcontrollers (for digital control math and physics in formulating engineering problems and show
implementation). It also provides users experiences in testing, students how these knowledges can be integrated with
simulation and real-time implementation. This paper presents a programming to implement real time control solutions. The
real-time level control of a laboratory water tank plant expectation for them is to study dynamics of the open-loop water
demonstrating the essence of control engineering. The objective is flow system, and apply PID design methods to close the loop.
to design and apply a PID controller to maintain the water level in Our focus in more on the engineering design flow and cycle
a cylinder tank by using Arduino microcontrollers. After plant
instead of advanced control solutions.
modelling and device testing, controllers are designed, and the
closed-loop system is simulated. Refined controllers are then The importance of using microcontrollers in control
implemented through Arduino Mega 2560. By comparing the education has been recognized for a long time [6]. With the
simulation and experimental closed-loop system performances, development of technologies, microcontrollers have been
the difference caused by plant-model mismatch is discussed. The widely adopted in real-time control implementation. One
importance of integrating math, physics, and circuits with example is using ARM7TDMI to control a coupled tank system
Arduino programming in embedded control systems is as reported in [7]. During our teaching of Devices and Control,
highlighted.
we chose Arduino microcontroller, due to the fact that it
Keywords—Real time control, Arduino Mega 2560, water tank
provides an open-source electronics platform based on low-cost
level control, control engineering hardware and easy-to-use software [8]. Arduino has been quite
popular in making interactive projects to meet both individual
I. INTRODUCTION interests and academic educational requirements; and thus has
become a mainstay of control systems laboratories. Enhancing
Control engineering is an interdisciplinary field requiring
the teaching and learning of control systems by using Arduino-
knowledges on math, physics, circuits, sensors, actuators,
based projects is not new in engineering discipline, for example,
programming and microcontrollers (for digital control
[9] summarizes how this effort was taken in the college of
implementation). It also provides users experiences in device
engineering at Qassim University Saudi Arabia, just to name a
testing, design simulation, and real-time implementation.
few.
The purpose of this paper is to show one of the efforts we
In the remaining of this paper, we will first present in Section
have ever tried at UW Tacoma in teaching Devices and Controls
II the laboratory water tank system and the problem formulation.
to undergraduate students who have never taken any control
Section III describes the tests and experiments we designed to
courses before. Since water tank systems as well as PI/PID
derive the mathematical representation of each physical
controllers play important roles for introductory courses in
component in the system. PID controller design, simulation
control as mentioned in [1], we built a simple DC water tank
results as well as detailed implementation and experimental
level control plant and use it to illustrate the essence of control
results will be discussed in Section IV, and Section V concludes
engineering. The objective is to help students understand the
the paper.
modeling of control system, testing of devices, measuring and
reading of signals, as well as design and implementation of PID II. SYSTEM DESCRIPTION
controllers. Students are expected to gain hands-on experience
with actuators and sensors including a DC water pump [2] and a A. Laboratory Plant Description
fluid level sensor [3]; meanwhile, they are required to maintain The water tank level control plant was built for teaching
the water level at the set height by programming Arduino Mega undergraduate students Devices and Control at the School of
2560 [4]. Engineering and Technology in UW Tacoma [10]. A picture of
We noted that in general water tank systems contain multiple the system is shown in Fig.1, where the user can set the desired
tanks. They can have different types including cascaded tank water level by altering a potentiometer on the circuit board; the
systems and coupled tank systems [1] and thus propose very level of the water inside the cylinder tank is measured through a
challenging control problems. A single tank system, although pressure sensitive tape which changes resistance as the water
simpler in the setup, can still present issues worth a significant level changes [3].

l-))) 
During normal operation, the valve at the bottom of the tank ‫ܣ‬
ௗ௛ሺ௧ሻ
ൌ ݂ଵ ሺ‫ݐ‬ሻ െ ݂଴ ሺ‫ݐ‬ሻ (1)
is open. The Arduino computes the error between the desired ௗ௧
and actual water level. It also implements the controller and ଵ
Replacing ݂଴ ሺ‫ݐ‬ሻ ൌ  ݄ሺ‫ݐ‬ሻ , (1) can be further rewritten as
generates the PWM signal, which is in turn sent to a motor driver ோ
carrier Pololu [11] to control the speed of the pump; and further, Equation (2)
to control the rate of flow into the tank. In this course project, ‫ܣ‬
ௗ௛ሺ௧ሻ ଵ
൅ ݄ሺ‫ݐ‬ሻ ൌ ݂ଵ ሺ‫ݐ‬ሻ (2)
students are required to design and use at least two elements of ௗ௧ ோ
a PID controller (PD, PI, or PID) to regulate the water level. Applying Laplace transform to (2), and assume zero initial
conditions, the transfer function is a first order system as
Equation (3) shows.
ுሺ௦ሻ ଵΤ஺
ܶሺ‫ݏ‬ሻ ൌ  ൌ (3)
ிభ ሺ௦ሻ ௦ାଵΤሺோ஺ሻ

Fig. 3. An ideal water tank model


Fig. 1. A water level control system developed for teaching
demonstration at UWT We remark that a pressure sensitive tape is used to measure
the water level. The user cannot read the height directly, instead
the sensor outputs a resistance in the unit of Kilo Ohms as shown
B. Block Diagram Representation in Fig. 4 from its datasheet. Although not included in Fig.2, it is
an important device and needs careful calibration as we will
By connecting each component in the way they work, the discuss in the next section.
plant in Fig. 1 can be depicted using a block diagram given in
Fig. 2. In the following problem formulation, R(s) and H(s)
represent the desired and actual water level, ܸ௣ the DC voltage
applied to the pump, and ‫ܨ‬ଵ the flow rate into the tank. Pump as
the actuating device and tank the object being controlled, they
are represented as a pump constant ܲ௞ and a transfer function
T(s), respectively.

Fig. 4. Typical eTape sensor output [3]


Fig.2. Block diagram of the closed-loop level control system

Since the project aims at illustrating basics of control


engineering, the derivation of transfer function T(s) starts with III. TESTS AND MEASUREMENT RESULTS
an ideal water tank as shown in Fig. 3, where ݂ଵ ሺ‫ݐ‬ሻ and ݂଴ ሺ‫ݐ‬ሻ are In this section, we will design tests and show the
inflow and outflow rate, respectively. ݄ሺ‫ݐ‬ሻ represents the water measurement as well as modeling results of the three
height, A represents the area of tank cross-section and R the fluid components mentioned in Section II, i.e., the fluid level sensor,
resistance of the tank. A governing first-order differential the pump, and the water tank. More specifically, through these
equation describing this ideal water tank is given in Equation (1) experiments, we will decide values of following physical


variables so that each block (except the controller) in Fig.2 can B. Determine the Tank Transfer Function T(s)
be represented mathematically: Transfer function (3) can be decided once the area of tank
x A: the area of tank cross-section cross-section A and the fluid resistance of tank R are obtained.
x R: the fluid resistance of the tank Using digital calipers we found the tank is 3.5cm in diameter,
i.e., ‫ ܣ‬ൌ ߨ‫ ݎ‬ଶ ൌ ͻǤ͸ܿ݉ଶ .
x ܲ௞ : the pump constant
The method we used to determine the fluid resistance of tank
A. Reading of the Fluid Level Sensor ଵ
R, is based on the physics ݂଴ ሺ‫ݐ‬ሻ ൌ  ݄ሺ‫ݐ‬ሻ contained in Fig. 3.
The Milone eTape [3] is the fluid level sensor; it has resistive ோ
output that is inversely proportional to the liquid height inside a Once we figureed out the outflow rate function ݂଴ ሺ‫ݐ‬ሻ and the
container. Correct reading makes big sense in obtaining the fluid height change function ݄ሺ‫ݐ‬ሻ, the fluid resistance R is then
௛ሺ௧ሻ
actual water height and setting the desired height through tuning simply the ratio given by ܴ ൌ  ሺ௧ሻ. So our 3- step test to find
௙బ
the potentiometer. To read the output of eTape and convert the the fluid resistance R was designed as follows:
reading into relevant liquid height, we created a voltage divider
circuit as shown in Fig. 5, where a 9V source and a 1.9K Ohms Step 1, we continue previous tests on eTape ADC reading.
resistor are used. By Fig. 4, eTape has a range of 2.2K Ohms to By adding a time stamp to ADC outputs from the serial port, we
0.4K Ohms when the liquid level varies from 1 inch to 12 inches. filled the water tank, and let it drain while recording values. This
These are then taken into consideration when we design tests in data was an exponential decay. Using (4) to convert ADC values
order to utilize the largest range on the ADC. to water height in inches, we obtained the curve in Fig. 7, i.e.,
the water height change function ݄ሺ‫ݐ‬ሻ as represented by
Equation (2):
݄ሺ‫ݐ‬ሻ ൌ ͳͲǤͺͳ͹ ‫ି ݁ כ‬଴Ǥ଴ହ଼௧ (5)

Fig.7. Height (inches) vs. time (seconds)

Fig.5. Circuit Diagram created to read the sensor Step 2: converting the height unit in function (2) to be cm,
together with the tank cross-section area ‫ ܣ‬ൌ ͻǤ͸ܿ݉ଶ , we then
ADC on Arduino Mega 2560 generates a 10-bit discrete drew the volume change over time. The curve is shown in Fig.
value in the range of 0-1023. The more of these values we can 8, and the expression is in Equation (6):
map into water levels the more precise control we can derive. A
small Arduino sketch (see Appendix) was developed to output ‫ ݁݉ݑ݈݋ݒ‬ൌ ʹ͵ͶǤͲͳ ‫ି ݁ כ‬଴Ǥ଴ହ଼௧ (6)
the ADC values to the serial port; meanwhile we filled the water
tank to each of the inch marks on the eTape. With these data we
created a best-fit line, see Fig. 6.

Fig.8. Outflow volume (cm^3) vs. time (seconds)


ௗ௏௢௟௨௠௘
Step 3: Outflow function is simply ݂଴ ሺ‫ݐ‬ሻ ൌ  .
ௗ௧
Together with the height function in (5), we were able to solve
Fig. 6. Water height (in inches) vs. ADC reading on Arduino the fluid resistance of the tank,
௛ሺ௧ሻ
By linear approximation, water level in the unit of inches can ܴ ൌ ൎ ʹ ‫ ݏ݀݊݋ܿ݁ݏ‬Τܿ݉ଶ  (7)
௙బ ሺ௧ሻ
be decided by Equation (4) below:
By now, with ‫ ܣ‬ൌ ͻǤ͸ܿ݉ଶ , and ܴ ൎ ʹ ‫ ݏ݀݊݋ܿ݁ݏ‬Τܿ݉ଶ , the
݄݄݁݅݃‫ ݐ‬ൌ െͲǤͲʹͳ͸ ‫ ݁ݑ݈ܽݒܥܦܣ כ‬൅ ʹʹǤ͸Ͳͳ (4) tank transdfer function is obtained as


ܶሺ‫ݏ‬ሻ ൌ 
ଵȀ஺
ൌ
଴Ǥଵ
(8) programming Arduino Mega 2560. We note here that the
௦ାଵȀሺோൈ஺ሻ ௦ା଴Ǥ଴ହ purpose of this control system design is to illustrate students how
C. Determine the Pump Constant to use different methods and tools to complete a control
engineering project. As the tradeoff between response speed and
Next we moved to solve the pump constant ܲ௞ . Again we stability, we chose maximum 5% overshoot as the main design
wrote an Arduino sketch (given in Appendix) in order to find the requirement, as most design problems would pick, e.g, [12], just
amount of fluid the pump moved at a set voltage for exactly 10 to name a few.
seconds. We had the pump connected to a precision power
supply so we could run the pump at different voltages, in
particular, within its working range from 3 Volts to 12 Volts.
We measured the amount of fluid pumped by weighing the fluid
on a gram scale and using the fact that one gram on water
equates to 1 milliliter of water. For each voltage, the experiment
was run 3 times; the three volume measurements were then
averaged and graphed versus that relevant voltage in Volts, as
shown in Fig.9. Taking into consideration that each experiment
runs for 10 seconds, the constant is then calculated as shown in
Equation (9).
ସǤଵସସ
ܲ௞ ൌ  ൌ ͲǤͶͳͶͶܿ݉ଷ Ȁሺܸ‫ݏ݀݊݋ܿ݁ܵ כ ݏݐ݈݋‬ሻ (9)
ଵ଴

Fig. 11. Simulation results (system output) with Kp = 1.1, KI = 0.1

Fig. 9. Pump constant testing results; each test runs for 10 seconds

IV. SIMULATION AND REAL-TIME IMPLEMENTATION RESULTS


Once the blocks of pump and tank in Fig.2 have found their
math representations, we started simulation using MATLAB
and Simulink. We then applied the PID controller, which was Fig. 12. Simulation results (controller output) with Kp = 1.1, KI = 0.1
tested via simulation, to the real plant using Arduino Mega 2560.
A. Simulation Results B. Implementation Details
Since the open-loop system shows a simple first order As shown in Fig. 5, the user sets a desired water level by
dynamics, we just tried the very basic structure of PID using a potentiometer with 1 Kilo Ohm resistance. With it we
controllers as shown in Fig. 10, to show students the effects of are able to select 1024 different set points for the level of the
each term. By using the trial and error method, it is not hard to tank. The Arduino measures the potentiometer, and compares its
find suitable three term parameters, i.e., ‫ܭ‬௣ , ‫ܭ‬ூ and ‫ܭ‬஽ . value to the eTape reading on ADC. Notice that the value of
eTape reading is subtracted from 1023 (the maximum value of
10-bit ADC) as the eTape gives the value from the top of the
tape to the water level instead of the amount of tape under the
water. The error between the desired and actual height is then
fed into the PI controller where the error is converted into a value
between 0-255. Notice here 255 is the maximum PWM value
that Arduino can supply. The PWM value maps to output
voltage between 0 and 5 Volts; and this voltage is fed into a
Pololu motor controller which will scale the PWM voltage to the
range of 0-12 Volts. The higher the voltage, the more water the
Fig. 10. Closed-loop simulation using Simulink pump can fill the tank.
We stopped at ‫ܭ‬௣ ൌ ͳǤͳ, ‫ܭ‬ூ ൌ ͲǤͳ and ‫ܭ‬஽ ൌ Ͳ. With this PI C. Experimental Results
controller, the output can track the input signal at a relative fast As the tank gets filled, the resistance on the eTape decreases,
pace with a 5% overshoot as shown in Fig. 11; the control signal this affects the error term calculated by Arduino. By using
generated by PI controller also looks reasonable, see Fig. 12. We correct values from the PI controller we can ensure the water
then plugged in this PI controller into implementation by


level follow the desired level with little overshoot and little to V. CONCLUSION
no oscillations. A water tank plant is a typical system designed for control
We started our implementation by the PI controller obtained education. When the inflow rate of the water is well controlled,
from simulation. After a little bit tuning, we found a set of new the water level changes showing a typical first-order system
parameters which are quite satisfying our needs (relatively dynamics. It is thus a good illustration example to teach students
quick response with no excessive overshoot), i.e., ‫ܭ‬௣ ൌ ͳǤʹ and concepts about modelling (using their math and physics
‫ܭ‬ூ ൌ ͲǤʹ. The following graphs in Fig. 12 and 13 show the knowledges), testing, and simulation. Arduino is a good
hardware platform to collect data, process data, compute the
water tank level response, and PWM output response of the
controller algorithm and output PWM signal driving external
system, respectively. The resistance of the water level sensor devices. The real-time implementation of a control algorithm via
was recorded and converted every 30 ms; the potentiometer sets microcontroller teaches students existence of the plant-model
the desired height as 16.8 cm for the tank water. mismatch, and thus motivates them to consider more advanced
By comparing the simulation results in Fig. 11-12 with the methods to improve control performance.
real-time implementation results in Fig. 13-14, students can
observe the difference of two sets of graphs showing model- This paper summarizes a water level control project in
plant mismatch and real-time implementation issues. They also teaching Devices and Control to undergraduate students at UW
noticed the similarities between them; this enhanced their Tacoma. We remark that the design and development of control
understanding on the importance of system modeling and theories for tank systems is not the focus of this paper; instead
simulation. we want to emphasize that control engineering is an
interdisciplinary field. With the rapid progress of information
and computer technologies, it is our goal to keep building
interesting projects which not only integrate modern
technologies and hardware/software tools into traditional
teaching, but also highlight math/physics fundamentals.
As a conclusion, this paper studied a water level control
system from an educator’s perspective. Through this project, we
expect to teach students modeling of a real system, dynamics of
the open-loop water flow system, and apply PID design methods
to close the loop. Our focus in more on the engineering design
flow and cycle instead of advanced control solutions.
APPENDIX
Fig. 13. Real-time response (height) of the water level control system
with Kp = 1.2, KI = 0.2 Water Depth Code
const int analogInPin = A0; // Analog input pin that the
potentiometer is attached to
int sensorValue = 0; // value read from the pot

void setup() {
// initialize serial communications at 9600 bps:
Serial.begin(9600);
}

void loop() {
// read the analog in value:
sensorValue = analogRead(analogInPin);
Serial.print(sensorValue);
Fig. 14. Real-time response (PWM) of the water level control system delay(200);
with Kp = 1.2, KI = 0.1 }

Pump Constant Code


Note that PWM will output the duty cycle to control the const int analogInPin = A0; // Analog input pin that the
speed of the motor, and further the rate of flow into the tank. potentiometer is attached to
From Fig. 14, the duty cycle was 100% (associated with the int outputTime = 0; // value output to the PWM (analog out)
maximum value 255)) for about 11 seconds after the system had int sensorValue;
started. Then the motor speed decreased until the system reached void setup() {
the set-point value. This control efforts matches the rising-up // initialize serial communications at 9600 bps:
curve in Fig. 12 at the first 20 seconds. Serial.begin(9600);
}


void loop() { void loop()
while(outputTime < 10000) {Input = 1023 - (analogRead(sensorInPin));
{sensorValue = analogRead(analogInPin); Setpoint = (analogRead(setPointInPin));
Serial.print(sensorValue); myPID.Compute();
Serial.print(","); analogWrite(pwm1, Output);
Serial.println(outputTime); Serial.print(Input);
delay(1000); Serial.print(",");
outputTime = outputTime + 1; Serial.print(Output);
} Serial.print(",");
} Serial.print(Setpoint);
Serial.print(",");
PID Project Code Serial.println(timeElapsed);
#include <elapsedMillis.h> }

const int inA = 2; REFERENCES


const int enA = 3; [1] R. Bieda, M. Blachuta and R. Grygiel, "New Look at Water Tanks
Systems as Control Teaching Tools," IFAC-PapersOnLine, vol. 50, no. 1,
const int inB = 4; pp. 13480-13485, 2017.
const int enB = 5; [2] http://www.amazon.com/gp/product/B001D679Y0/ref=s9_simh_co_p20
const int pwm1 = 6; 1_d0_i1?pf_rd_m=ATVPDKIKX0DER&pf_rd_s=left-
const int sensorInPin = A0; 1&pf_rd_r=0QRPTDQR6A9TQ4TTP3PW&pf_rd_t=3201&pf_rd_p=12
const int setPointInPin = A1; 80661682&pf_rd_i=typ01
//Define Variables we'll be connecting to [3] https://cdn-
shop.adafruit.com/datasheets/eTape+Datasheet+12110215TC-
double Setpoint, Input, Output; 12_040213.pdf
[4] https://store.arduino.cc/usa/arduino-mega-2560-rev3
//Specify the links and initial tuning parameters [5] M. Blachuta, R. Bieda, and R. Grygiel, "High Performance Tank Level
double Kp=1.2, Ki=0.2, Kd=0; Control as an Example for Control Teaching", Proc. of the 25th
PID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, Mediterranean Conference on Control and Automation, pp. 1053-1058,
DIRECT); July 2017, Valletta, Malta.
elapsedMillis timeElapsed; [6] R. Shoureshi, P.H. Meckl, “Microprocessors in Control Education”, Proc.
of the American Control Conference, pp. 374-377, June 1994.
[7] R. Jaisue, J. Chaoraingern, V. Tipsuwanporn, A. Numsomran, P.
void setup() Pholkeaw, “A design of fuzzy PID controller based on ARM7TDMI for
{Serial.begin(9600); coupled-tanks process”, Proc. of the 12th International Conference on
pinMode(inA, OUTPUT); Control, Automation and Systems, pp. 610 – 613, 2012.
pinMode(inB, OUTPUT); [8] https://www.arduino.cc/
pinMode(enA, INPUT); [9] H. M. Omar, “Enhancing automatic control learning through Arduino-
based projects,” European Journal of Engineering Education, vol. 0, Iss.
pinMode(enB, INPUT); 0, pp. 1-12, 2017.
digitalWrite(inA, HIGH); [10] J. Sheng, “Teaching Devices and Controls for Computer Engineering and
digitalWrite(inB, LOW); Systems Students using Arduino and MATLAB/Simulink”, Proc. of the
//initialize the variables we're linked to 14th IEEE International Conference on Control and Automation,
Input = analogRead(sensorInPin); Anchorage, Alaska, 2018, USA.
Setpoint = analogRead(setPointInPin) [11] https://www.pololu.com/product/1451
//turn the PID on [12] https://nl.mathworks.com/help/slcontrol/ug/design-compensator-in-
simulink-using-automated-pid-tuning.html
myPID.SetMode(AUTOMATIC);
}



You might also like