Você está na página 1de 22

International Journal of Network and Mobile Technologies

ISSN 2229-9114 Electronic Version


VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Wireless Controlled Two Wheel Balancing Robot


Charles Yong1 and Chiew Foong Kwong2
1

INTI International University, Malaysia, Faculty of Engineering and Technology, kodcyky@yahoo.com


INTI International University, Malaysia, Faculty of Engineering and Technology, chiewfoong.kwong@newinti.edu.my
Abstract
The idea of two wheel self balancing robot had gain popularity among control system researchers worldwide
over the last decade. This thesis aimed to design and build a two wheel self balancing robot that can be
controlled remotely. The electronic circuit design for the robot was split into parts and connected together
through ribbon cable. The robot chassis was constructed using acrylic and mounted on two motors with
440RPM. Battery weighing 80g was placed on top of the chassis.IMU, which comprises of a triple-axis
accelerometer and a dual-axis gyroscope, was chosen as robot tilt angle sensor. Analog voltage readings from
IMU were converted to tilt angle values and passed through Kalman filter for data fusion. A PID controller was
incorporated to each motor for motor closed loop speed control with motor back-EMF readings as motor speed
feedback and PWM duty cycle as controller output. A main PID controller was implemented as the control
system for robot balancing with Kalman filtered tilt angle readings as feedback and motor PID controller speed
set point value as controller output. A pair of 315MHz RF module was used for robot remote controlling. Data
transmitted were encoded to minimize probability of interference by similar source. Microcontroller was linked to
the computer through UART for data analyzing on the computer as well as real-time tuning of Kalman filter as
well as PID controller through the computer. Lastly, the aim for this project was fully achieved. The robot was
able to balance by itself on two wheels with little drift on smooth surface while powered up. The robot can be
controlled by the RF controller to move in four directions with random delay caused by noise, which was
expected due to low cost RF module used.

Key words: IMU, Accelerometer, Gyroscope, Kalman Filter, PID Controller, Motor Back-EMF,
PWM, RF Controlled Robot, UART

88
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

1 Introduction
A two-wheeled self balancing robot is a robot that can balance itself on its two wheels. Over the last decade,
research institutes, commercial companies, and independent hobbyists had been inspired to develop and implement
control system for the two-wheeled self balancing robot in different applications [7].
Control system for two-wheeled self balancing robot can be implemented in all sorts of platform, such as automobile,
wheelchair, robot, and even military transport. A two-wheeled self balancing robot offers following advantages over
three or more wheels platform:

Higher mobility with zero turn-radius.

Higher speed due to less friction from fewer wheels.

Simpler structural design.

Tolerance to impulsive forces [7].

Lesser parts that needs replacing over time such as wheels.

Greater stability on inclines as in [3].

2 Literature Review
2.1

IMU Implementation to Obtain Tilt Angle

An IMU consists of two sensors, accelerometer and gyroscope.

2.1.1 Accelerometer
As stated by [10], an accelerometer is a device that measures inertial force that is in the opposite direction of
acceleration vector with respect to freefall in terms of g-force. This means, an accelerometer will indicates 0g force
during freefall where it accelerates constantly at 1g downwards due to gravity. When an accelerometer is at rest on
Earth surface, its casing will be supported by ground with an equivalent force of 1g upwards. Hence, it will indicate a
constant downward force of 1g perpendicular to ground at rest. This characteristic can be utilized to obtain tilt angle
using Pythagoras Theorem.

2.1.2 Gyroscope
A gyroscope is a device that measures angular rate around an axis. Tilt angle can be obtained by integrating angular
rate over sampled time.

2.2

Kalman Filter

The Kalman filter was introduced by Rudolf E. Kalman in his paper titled A New Approach to Linear Filtering and
Prediction Problems in year 1960 [8]. Kalman filter is a mathematical model that performs recursive computations to
estimate the state of a linear process with minimum squared error, as stated in [8]. The filter combines data from
multiple sources. Hence, filtered value tends to be closer to the true values than each individual noisy measured
value.
From [8], Kalman filter has two phases that alternate between each other, predict phase and update phase. Predict
phase use estimated values of previous state to project current state estimate. Update phase update the projected
estimated with actual measurement. The update phase is skipped if measurement is unavailable during a particular
state. The drawback of Kalman filter is that, it needs to be tuned properly before it can be implemented into a system
and there is no fixed tuning method available as it is widely applicable in numerous fields.

2.3

DC Motor Speed Control

Motor speed is directly proportional to motor voltage. However, reducing motor voltage for lower motor speed
reduces motor torque as well.

89
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Pulse width modulation, in short PWM, can be use to counter the problem. PWM works by sending a square wave to
turn the motor on and off at a very high frequency in such a way that the motor never really turns off. The motor still
receives full supplied voltage momentarily which results in higher torque than directly reducing motor voltage for
speed control, as stated by [2]. In [9], PWM duty cycle is proportional to the motor average voltage. Thus, PWM duty
cycle is proportional to motor speed.

2.4

DC Motor Back EMF Speed Sensing

Motor converts electrical energy to mechanical energy in the form of rotation. On the contrary, generator converts
mechanical energy to electrical energy. DC motor can be generator at the same time by rotating the motor shaft. In
[1], Back-EMF is the voltage generated by a rotating motor which is directly proportional to the rotating speed.
According to [1], two alternating steps are required to sense the back-EMF. First, the motor is run for a period of time.
Then, the motor is stop for another period of time and measurement is taken within that time period.

Figure 2.1: DC Motor Back-EMF, excerpt from [1]


The back-EMF does not reach its stable region immediately after the motor was stopped as shown in Figure 2.1
above. This method decreases the maximum motor speed as it is in the form of PWM. Due to that, the measurement
time gap must be kept to the minimum while allowing enough time for stable back-EMF measurement.

2.5

PID Control System

PID controller is a closed loop feedback controller for a linear system. PID controller calculates the error between
measured values with its desired set point and attempts to correct the calculated error. PID controller stands for
proportional, integral and derivative controller.
Based on [5], proportional, integral and derivative control characteristics were summarized as follows:

Proportional control deals with present error. Proportional factor is the product of gain and measured error.
Hence, larger proportional gain has faster response time and smaller steady state error but causes
overshoots over the desired set point. Setting the proportional gain too high causes a system to oscillate
around the set point without settling.

Integral control deals with accumulation of past errors. When error is too small, proportional factor output
becomes negligible, which causes steady state error. Integral factor is the product of gain and summation of
past errors. Hence, it corrects even a very small error and eliminates the steady state error. Similar to
proportional controller, setting the integral gain too high causes overshoots over the set point.

Derivative control deals with prediction of future errors. Derivative factor is the product of gain and rate of
change of error. Therefore, it is use to reduce the overshoot caused by proportional and integral factor. The
downside is that, derivative gain amplifies noise as well, which can cause the system to become unstable if
the gain is too high.

The downside of PID control is that when there is a large change in set point, the integral factor will
accumulates a large error during response time and eventually overshoot. It will continue to increase over the
set point until the accumulated error is decreased by errors in other direction. This situation is called integral
windup.
90

22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

3 Design Methodology
3.1

Block Diagram and Program Flowchart

Figure 3.1 shows the block diagram for the whole system design.

Figure 3.1: Block Diagram

Figure 3.2: Program Flowchart


91
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

3.2

This paper is available online at


http://ijnmt.com/

Method Alternatives Evaluation and Choice Justification

3.2.1 Tilt Angle Sensor


The tilt angle sensor is the most crucial part for the self balancing robot. The sensor used must be able to provide
fast and accurate tilt angle readings. Otherwise, the robot will not be able to balance itself when sudden changes of
tilt angle occur. Three types of sensors were considered for the robot.

Inertial Measurement Unit, IMU:


The IMU comprises of accelerometer and gyroscope to sense tilt angle by placing directly on the
PCB. Both sensors complements with each other to produce a more accurate tilt angle
measurements. The IMU provides very fast and accurate measurements but it is very expensive and
advance filtering needed due to its noisy measurements.

Infrared Sensor:
Infrared sensors can be used to sense robot tilt by comparing the difference in distance from ground
between two sets of sensors on the robot chassis directing downwards with one attached in front and
another at the rear of the chassis. Infrared sensors are very cheap and simple to use but it can only
sense the direction of tilt and its approximate magnitude instead of the exact tilt angle. Its response is
slow compared to the IMU. Furthermore, it needs a smooth and flat floor surface to reflect properly.

Potentiometer:
Potentiometer can be used to sense robot tilt by attaching a rod to it that touches the ground at
another end. When the robot tilts, the rod will turn the knob of the potentiometer changing
resistances which changes voltage drop across it. Tilt angle can be sensed approximately by
o
comparing voltage acquire with voltage at 0 . It is very simple and very cheap but its response is very
slow. It is not very accurate as resistance changes with temperature. The rod may cause drag to the
robot movement.

Sensors
Method

Measurement
Resolution
Sensitivity
Cost
Problem

Table 3.1: Tilt Angle Sensors Comparison


IMU
Infrared Sensor
Senses tilt angle using
Senses difference in distance
combination of accelerometer
from ground between front and
and gyroscope.
rear sensors to obtain tilt.
Tilt angle
Magnitude representation of
tilt.
High
Moderate
Very high but noisy
Moderate
Very expensive. RM350.
Very cheap. Less than RM10.
Advance filtering needed to
Need smooth and flat surface
filter out the noise.
to reflect.

Potentiometer
Senses robot tilt through rod
with contact to the ground.
Magnitude representation of
tilt.
Low
Low
Very cheap. Less than RM2.
Resistance changes with
temperature.
Floor feeler may cause drag
to the robot.

After some considerations, IMU was chosen for sensing tilt angle. First, both infrared sensor and potentiometer
cannot sense actual tilt angle and their response is slow compared to IMU. To compensate for that, high torque high
speed motors are needed, which cost more than IMU alone. Second, IMU noisy measurements can be filtered by
o
combining both accelerometer and gyroscope measurements. Third, IMU has resolution of 0.1 , which is highest
among the three.

3.2.2 Filter for MU

Complementary Filter
Complementary filter works by low-passing measurement from accelerometer and high-passing
measurements from gyroscope, which only involves basic averaging calculations [4]. It produces a
smooth but slow response due to the averaging, which causes delay. Furthermore, it neglects the
gyroscope bias in the calculation, which may cause severe offset in the output if the gyroscope bias
changes.

Kalman Filter
Kalman filter uses complex mathematical calculations for data filtering. Therefore, it consumes a lot
of processor speed. It response is fast and can recover from error very quickly.

92
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Table 3.2: Filters Comparison


Complementary Filter
Kalman Filter
Basic averaging calculations.
Complex mathematical calculations.
Moderate
High
Smooth but slow
Fast
Severe offset if the gyroscope bias changes.
Consumes a lot of processor speed.
Difficult to tune.

Filters
Algorithm
Reliability
Response
Problem

Both filters were roughly tested on their performance beforehand. Complementary filter produces a smooth graph
output due to the averaging but its response is slow. It produces a constant offset when gyroscope bias changes due
to its assumption of constant gyroscope bias. On the contrary, Kalman filter corrects the gyroscope bias by
comparing with accelerometer measurement. A high performance microcontroller can be used to counter the
processing problem. After testing, Kalman filter was chosen as it is clearly better even though it was roughly tuned.

3.2.3 Motor Speed Feedback Method

Back-EMF
Back-EMF feedback method senses the back-EMF generated by the motor itself, which is
proportional to motor speed, by stopping the motor for a short duration. Therefore, it decreases the
motor maximum speed. This method is free of charge but it can only sense the magnitude
representation of velocity in the form of back-EMF.

Quadrature Encoder
Quadrature encoder considered senses motor speed by using two magnetic sensors to measure the
rotation speed of custom made wheel. Its output is in the form of pulses. It can sense actual motor
speed but it is very expensive and consumes a lot of processor speed.

Rotary Encoder
Rotary encoder senses motor speed using infrared sensor and rotary disc. The rotary disc needs to
be installed on the motor rotating part. It is very cheap and can sense actual motor speed.

Sensors
Method

Measurement
Cost
Disadvantages

Table 3.3: Motor Speed Feedback Method Comparison


Back-EMF
Quadrature Encoder
Rotary Encoder
Senses back-EMF generated Senses motor speed through
Senses motor speed using
by the motor itself.
two magnetic sensors.
infrared sensor and rotary
disc.
Magnitude representation of
Actual motor speed.
Actual motor speed.
motor speed.
Free
Very expensive. RM75 for
Very cheap. Less than RM10.
each motor.
Decreases motor maximum
Consumes a lot of processor
Need modification on motor
speed.
speed.
and robot chassis.
Need special wheel.

Back-EMF feedback method was chosen because it is free and does not require any modification on motor and robot
chassis. Actual motor speed is insignificance to the control system. Magnitude and direction alone is sufficient. Its
problem in decreasing maximum motor speed does not matter as balancing is done in low speed.

3.2.4 Data Acquisition Method


A method of data acquisition was required to analyze data acquired by microcontroller. UART was chosen as the
data acquisition method because it supports full-duplex communication between microcontroller and computer. This
allows data analyzing on the computer as well as real-time tuning through the computer.

3.2.5 Control System


PID closed loop controller was chosen for the robot due to its simplicity and effectiveness in linear system control.

3.2.6 Microcontroller
After serious considerations, dsPIC30F4013 was chosen as the microcontroller for the robot. First, it is a high
performance digital signal controller that can run up to maximum of 30 MIPs, which is more than sufficient for the
Kalman filter. Second, it has 12-bit ADC that is necessary for acquiring measurements from IMU with high resolution.
93
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Third, it has two addressable UART modules for communication with computer and for remote controlling. Fourth, it
has built-in PWM module for DC motor speed control.

3.2.7 Wireless Control Method


315MHz RF module was easily chosen due to its low cost compared to other remote control method such as
Bluetooth and XBee. The problem is that, it is very susceptible to noise. This can be overcome by encoding the data
transmitted.

3.2.8 Battery and Motor


Battery and motor was considered as a set because the mass of battery determines the motor torque needed. 12V
battery and motor was eliminated because 12V battery is too heavy for acquirable 12V DC motors with sufficient
speed.
Batteries for 6V DC motors were compared as follows:

Batteries
Rated Voltage
Mass
Cost

Table 3.4: Batteries Comparison


Lithium Polymer Battery
Sealed Lead Acid Battery
7.4V
6V
Around 80g
Around 200g
RM175 including charger. RM155 including charger.

Based on the comparison, Lithium Polymer battery was chosen initially but during time of purchase, its charger is
temporarily out of stock. Sealed Lead Acid battery was chosen instead.
6V DC motors from Cytron Technologies were compared as follows:

Motors
Free-Run RPM
Stall Torque

Table 3.5: Motor Comparison


150:1 Micro Metal
30:1 Micro Metal Gearmotor
Gearmotor
440
85
0.3kg-cm
1.1kg-cm

298:1 Micro Metal


Gearmotor
45
1.8kg-cm

Based on Table 3.5, 298:1 Micro Metal Gearmotor is too slow for balancing. 30:1 Micro Metal Gearmotor was
preferred with highest speed but its torque is insufficient for the 6V Sealed Lead Acid battery. Hence, 150:1 Micro
Metal Gearmotor was chosen instead.

3.3

Electronic Circuit Design

The electronic part was designed based on modular design concept. The design for the robot was split into three
major parts, microcontroller board, motor driver board, and a main board which connects every part together through
ribbon cable. LED indicators were placed at each board to indicate power connections for easier troubleshooting.
Significance components such as IMU, RF receiver, motors, and battery were connected through connectors to
prevent soldering damage as well as easier replacement for damaged parts. To control the robot remotely, a RF
transmitter board was designed and built.

3.4

Robot Chassis Design

Before building the actual robot chassis, a prototype was made from cardboard paper for initial testing of the system.
The main purpose of the testing was to check whether the two motors can move under the weight of the entire
chassis. After testing, the actual chassis was constructed using acrylic by following the measurements from the
prototype. Acrylic was chosen due to its lightweight property.

3.5

Software Design

The program for the robot was written in C language and was compiled into hex file for microcontroller
dsPIC30F4013 using MikroC PRO for dsPIC software. Similarly, the program for RF controller was written in C
language and was compiled into hex file for microcontroller PIC16F627A using MikroC PRO for PIC software. Hex
file compiled was burned into microcontroller using PICkit 2 software through UIC00A programmer.

94
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

3.5.1 UART
UART communication was made from the microcontroller to the computer serial port through RS232 Shifter Board
for data analyzing on the computer as well as real-time tuning through the computer. Program module for sending
and receiving integer and float data between microcontroller and the computer through UART was written and tested.

3.5.2 Inertial Measurement Unit, IMU


The IMU used comprises of a triple-axis accelerometer, ADXL335 and a dual-axis gyroscope, IDG500. Both sensors
complements with each other to produce a more accurate tilt angle.

Accelerometer, ADXL335
ADXL335 triple-axis accelerometer has a maximum output of 3g per axis in the form of analog voltage. Its readings
were sampled through dsPIC30F4013 12-bit ADC module. Pythagoras Theorem was applied to obtain tilt angle from
the accelerometer by utilizing its characteristic of indicating a constant downward force of 1g perpendicular to ground
at rest. Readings from z-axis were used to obtain tilt angle due to the orientation of IMU on the robot structure.

Figure 3.3: Accelerometer Side View on Robot Structure with 0 Tilt Angle

Figure 3.4: Accelerometer Side View on Robot Structure with

o Tilt Angle

Calculations for obtaining tilt angle from accelerometer are shown as follows:
Analog voltage,

sampled through dsPIC30F4013 12-bit ADC module was calculated as follow:

95
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

(3.1)
where
= 12-bit ADC value
= Number of bits of ADC module
= Voltage reference for ADC module
The accelerometer z-axis analog voltage,

was obtained using (3.1) and was converted to g-force,

:
(3.2)

where
= Accelerometer z-axis output voltage at 0g
= Accelerometer sensitivity in mV/g
Both

and

were obtained in ADXL335 triple-axis accelerometer datasheet.

Pythagoras Theorem was applied to calculate tilt angle in degree based on Figure 3.4 using the g-force,
in (3.2):

obtained

(3.3)
(3.4)
where
= Accelerometer tilt angle in radian
= Accelerometer tilt angle in degree
The ADXL335 accelerometer has a maximum output of 3g per axis. Mathematical error will occur at (3.4) if is
outside the range of 1g due to acceleration and mechanical noise. Therefore, readings were limited within the
range of 1g.

Gyroscope, IDG500
IDG500 dual-axis gyroscope measures angular rate around an axis in the form of analog voltage. It has two separate
outputs per axis, standard and high sensitivity. Similar to the accelerometer, its readings were sampled through
dsPIC30F4013 12-bit ADC module.
Readings from y-axis high sensitivity output were used to obtain tilt angle.
Calculations for obtaining tilt angle from gyroscope are shown as follows:
The sampled gyroscope y-axis analog voltage,

was obtained using (3.1) and was converted to angular rate,

(3.5)
where
= Gyroscope y-axis zero rate output voltage
= Gyroscope sensitivity in mV//s
Discrete integration is the sum of all integrated discrete components. Hence, tilt angle,
accumulating integration of angular rate,

was obtained by

obtained in (3.5), over sampled time, dt:


(3.6)

where
= Tilt angle from previous state

96
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

The tilt angle obtained from gyroscope had smaller changes than the one obtained from accelerometer when the
o
IMU was rotated. Deduced that, the sensitivity of 9.1mV/ /s for IDG500 gyroscope stated in its datasheet is not
accurate. Thus the solution was that the IDG500 sensitivity was investigated and calculated manually using (3.7)
with accelerometer tilt rate as reference.

(3.7)

3.5.3 Kalman Filter


Kalman filter was used for data fusion between accelerometer and gyroscope to suppress noise from the
accelerometer and angular rate bias from the gyroscope. Kalman filter consists of two parts, time update and
measurement update [8]. From [8], the general Kalman filter equations are as follows:
Time update:
General model for a process:
(3.8)
where
= Estimate of state
= Previous state of
= Previous state measurement
= Coefficient matrix of
= Coefficient matrix of
Estimate of error covariance:
(3.9)
where
= Estimate of
= Previous state of
= Process noise covariance
Measurement update:
Kalman gain:
(3.10)
where
= Kalman gain
= mxn matrix which relates to measurement
= Measurement noise covariance
Process measurement update:
(3.11)
where
= Update of
by fusing with measurement
= Process measurement
Error covariance update:
(3.12)
where
= Error covariance
= Identity matrix
Kalman filter equations for IMU were derived as follows:
Gyroscope angular rate bias changes with temperature. Hence, it was considered as an individual part in the model.
Based on (3.8):

97
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

(3.13)
where
= Tilt angle estimate based on gyroscope measurement
= Gyroscope angular rate bias estimate
= Tilt angle of previous iteration
= Angular rate bias of previous iteration
= Sampling time
= Gyroscope angular rate measurement
From (3.13),

. Based on (3.9):
(3.14)

Based on (3.10), where

:
(3.15)

(3.16)
As stated by [8],

. Based on (3.11),
(3.17)

(3.18)
where
= Accelerometer tilt angle measurement
= Tilt angle update
= Angular rate bias update
Based on (3.12),
(3.19)

(3.20)
Matrix calculations consume a lot of microcontroller processing time. Hence, all calculations were expressed in
algebraic form inside the program to minimize processing time needed by the Kalman filter. Process noise
covariance, Q and measurement noise covariance, R of the Kalman filter were tuned to minimize mechanical noise
from accelerometer and bias from gyroscope. The update frequency of the Kalman filter was set to 500Hz. Three
constants, , , and R, were tuned.
value determines the weight between the two sensors. Smaller value
means gyroscope is trusted more by the filter.
is the angular rate bias expected from the gyroscope. R is the
noise expected from accelerometer. , , and R values were set experimentally. Kalman filtered tilt angle and
accelerometer tilt angle were sent to the computer continuously in real-time for comparison. While the data was
sending, the robot was tilted back and forth gently for a few times and then vibrated roughly for at least 10 times. The
data acquired for the two actions were plotted on graph using Microsoft Excel. Based on the comparison on graph,
changes were made to , , and R values and the process was repeated until the Kalman filter produces an
acceptable tilt angle response.
Problems of Kalman Filter

Kalman filter response cannot match up with actual changes in robot tilt angle when more data were sent to
the computer during the same iteration as shown in Figure 4.4. Found out that, the UART transmission of
multiple data during the same iteration caused delay to the update time period. The solution to solve this
problema was to set the UART baud rate to maximum of 115200bps.
98

22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Kalman filter angle started to change after 15min of continuously powering up the robot. Found out that, the
output voltage from 7805 voltage regulator, which was used as ADC reference voltage, dropped when the
battery level dropped due to discharging caused problem to the ADC module. The solution to this problema is
as follows:
First attempt: 1N4007 diode was replaced by 1N5817 diode with lower forward voltage and output
voltage from 3.3V voltage regulator was used as ADC reference voltage instead. However,
this only prevented the problem for half hour.
Final solution: The 7805 voltage regulator was replaced by LDO 5V voltage regulator, which produces
output voltage of 4.99V to 5.01V with minimum input voltage of 5.8V from battery.

3.5.4 PID Closed Loop Controller


PID stands for proportional, integral and derivative. Three PID closed loop controllers were used for the control
system, one for balancing and two for each motor. Below shows the general equation for a PID controller summarize
from [6].
is the difference between value desired for the system with actual feedback value:
(3.21)
where
= Value desired for the system
= Feedback value returned to the controller from the system
Proportional term:
(3.22)
where
= Proportional gain
Integral term:
(3.23)
where
= Integral gain
Derivative term:(3.24)
where
= Integral gain
From (3.22), (3.23), and (3.24) above, PID controller output can be obtained:
(3.25)

3.5.5 Motor PID Controller


PID closed loop control was required for each motor because motors do not run at the same speed on different
surfaces even with the same PWM. PID controller was implemented onto each motor using the general PID equation
mentioned, where Set Point is the motor speed desired, Process Variable is the back-EMF feedback from the motors,
and Output is in the form of PWM value in percentage. Limit was set to integral term to prevent integral windup.
Before tuning the motor PID controller, back-EMF feedback from the motor was tested. A constant duty cycle of
PWM pulse was sent to the motor. Every 2ms, PWM pulse was stopped temporarily for 100s and the back-EMF
reading acquired was sent to the computer. The process was repeated for 200 iterations. The PWM duty cycle was
decreased and the process was repeated to verify that the back-EMF is proportional to the PWM duty cycle which is
proportional to motor speed. Brute force tuning method was used to tune the each motor PID controller. Proportional
gain,
and derivative gain,
were both set to start from 1 to 5 with increment of 1. Integral gain, was set to start
from 0.01 to 0.05 with increment of 0.01. PWM frequency was set to 20 kHz. The motor set point was set to a
constant speed of 300. Back-EMF readings for all possible combinations of the three gains within their respective set
range and increments were acquired for 200 iterations each and were sent to the computer for analysis. The motor
was stopped for 0.5s between each combination. After testing, all acquired back-EMF readings from gains
combinations were plotted on separate graphs using Microsoft Excel and was compared. Gain combination that
produces best response was selected and was tested with different motor speed to ensure it produces similar
response over different speed.

99
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

3.5.6 Balance PID Controller


PID closed loop controller was used as the control system for robot balancing, where Set Point is the balance angle
of the robot, Process Variable is the tilt angle from IMU, and Output is in the desired speed for the motors. The
balance angle for the robot was acquired by trial and error approach. Limit was set to integral term to prevent integral
windup. The balance PID controller was tuned in real-time by sending the Proportional gain, , integral gain, , and
derivative gain,
value to the microcontroller using Tera Term software. The robot response was observed and
changes were made to the three gain values.It is not possible to send balance PID controller data to computer
because the UART wires cause drag to the robot movement. Hence, the three gain values were set experimentally
with different combinations and their effect on the robot response was observed and recorded. Based on the
observation, the robot was tuned until it can balance on its upright position. After the robot can balance itself, it was
tested to move in forward and backward directions by giving offset to the angle set point accordingly. Then, it was
tested to turn left and right by giving offset to each motor PID controller accordingly.
Problem and Solution

The robot moved out of balance when its tilt angle approaches set point angle. Each PID terms was sent to
computer and their values were observed when the robot moved out of balance. Found out that MikroC PRO
for dsPIC compiler generates error value for float data multiplication of 1.0 * 0. The solution was 1.0 was
changed to 1 instead.

The robot moved faster forward than backward with the same magnitude of offset angle. Deduced that, the
uneven weight distribution of the robot structure caused the robot to fell faster in forward direction. The
solution was the motor speed was used to limit the tilt angle offset.

Figure 3.5: Robot Center of Gravity

Failed to balance the robot with 6V Sealed Lead Acid battery and 150:1 Micro Metal Gearmotor after
o
hundreds of trials. The motor cannot balance the robot after it tilt more than 1 . Deduced that, robot with
higher center of gravity has longer distance to fall before reaching tilt angle, than one with lower center of
gravity as illustrated in Figure 3.5 above. This allows more time for motor to balance the robot. Hence,
concluded that, 150:1 Micro Metal Gearmotor with 85RPM is insufficient to balance the robot with center of
gravity lower than 15 cm.The solution, changed to initial plan of using Lithium Polymer battery and 30:1 Micro
Metal Gearmotor after the battery charger was available. The 200g 6V Sealed Lead Acid battery cannot be
used with new motor due to its low torque of 0.3 kg-cm.

The robot cannot balance on one fixed position. It drifted from one position to another on smooth surface. The
solution was the robot was programmed to move back and forth repeatedly to minimize the drift.

The robot turn out of balance when offset was set to each motor PID controller. After numerous tests, the
robot was found to be more stable to turn by giving offset for 5 iterations and stop giving offset for 25
iterations for the robot to regain balance. The same process was repeated until there was no command
received.

100
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

3.5.7 Remote Control using RF Module


The RF module was tested by transmitting a fixed data to the receiver and displayed on the computer. Header S
and footer E were added to each data as shown in Table 3.6 to minimize the probability of getting interference from
other transmitter. Only data in Table 3.6 will be processed by the microcontroller at the receiving end by
dsPIC30F4013.
Table 3.6: RF Data
Direction Button
Direction
Encoded Data
Up
Down
Left
Right
1
0
0
0
Forward
SFFE
1
0
1
0
Forward Left
SFLE
1
0
0
1
Forward Right
SFRE
0
1
0
0
Backward
SBBE
0
1
1
0
Backward Left
SBLE
0
1
0
1
Backward Right
SBRE
0
0
1
0
Turn Left
SLLE
0
0
0
1
Turn Right
SRRE
After finish testing data encoding and decoding, the control of the robot was tested for each direction respectively.
Problem and Solution
The receiver reads error data which persisted until button from transmitter was released and pressed.
Deduced that, the receiver cannot recover from error occurred on the first bit of data due to the continuous
transmitting of data. The solution was the transmitter programmed to transmit data every 50ms instead of
continuously for the receiver to recover from error bits.

The robot randomly stopped although the controller was still transmitting. Found out that, the RF receiver
reads too much noise in between each data causing delay. Thus, the robot was programmed to move for at
least 500ms when no command was received from the transmitter to minimize the effect of the delay.

4 Results and Discussion


4.1

Gyroscope Sensitivity

Figure 4.1: Graphs for Finding Gyroscope Sensitivity


101
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

The values acquired in Figure 4.1 were substituted into (3.7) to calculate the gyroscope sensitivity. The gyroscope
o
sensitivity was calculated to be 3.6mV/ /s.

Figure 4.2: Graph of Gyroscope Tilt Angle with Sensitivity Set to 9.1mV/ /s

Figure 4.3: Graph of Gyroscope Tilt Angle with Sensitivity Set to 3.6mV/ /s
Figure 4.2 and Figure 4.3 above show the gyroscope tilt angle readings with accelerometer tilt angle readings as
o
reference. It is clear that gyroscope tilt angle readings were inaccurate when its sensitivity was set to 9.1mV/ /s from
o
its datasheet. More accurate readings were acquired by setting the gyroscope sensitivity to 3.6mV/ /s. The linear line
in Figure 4.3 shows the drift of gyroscope tilt angle caused by angular rate bias of unfiltered gyroscope readings.

4.2

Kalman Filter Graph Response

Figure 4.4: Effect of UART Delay on Kalman Filter Graph Response

102
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.5: Graph of Kalman Filter Tune Response A

Figure 4.6: Graph of Kalman Filter Tune Response B

Figure 4.7: Graph of Kalman Filter Tune Response C

103
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.8: Completely Tuned Kalman Filter Graph Response


Figure 4.4 shows the effect of UART delay on Kalman filter output when too much data were transmitted to the
computer at during the iteration. As shown, the Kalman filtered tilt angle did not match up with the changes in actual
tilt angle of the robot shown by the accelerometer. Figure 4.5 to Figure 4.7 show some of the significance response
of Kalman filtered tilt angle compared to accelerometer tilt angle during fine tuning. Different value of , which is the
angular rate bias expected from gyroscope, ranging from 0.1 to 0.00000001 produces similar response from the
Kalman filter. Therefore,
was set to 0.00001, which is the value in between.
By comparing Figure 4.5 and Figure 4.6, it can be seen that, when R was increased from 50 to 200, noise from
accelerometer when the robot was vibrated was reduced after Kalman filtering. By comparing Figure 4.5 and Figure
4.7, it can be seen that, when
was decreased from 0.5 to 0.005, the overshoot of the accelerometer during slow
tilt of the robot was filtered by the Kalman filter.
Figure 4.8 shows the Kalman filter response after it was tuned, with
,
, and
. As
shown, the overshoot from the accelerometer during slow tilt was filtered. The noise from accelerometer when the
robot was vibrated was reduced greatly. Finally, the angular rate bias from the gyroscope was eliminated completely.

4.3

Motor PID Controller Graph Response

Figure 4.9: Graph of Motor Back-EMF with Different PWM Duty Cycle
As shown in Figure 4.9, the motor back-EMF values are proportional to PWM duty cycle. Hence, it was verified that
motor back-EMF values are proportional to motor speed.

104
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.10: Graph of Motor PID Tune Response A

Figure 4.11: Graph of Motor PID Tune Response B

Figure 4.12: Graph of Motor PID Tune Response C

105
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.13: Graph of Motor PID Tune Response D

Figure 4.14: Graph of Motor PID Tune Response F


A total of 225 graphs were acquired through brute force tuning of the motor PID controller with a constant set point of
300. Figure 4.10 to Figure 4.14 show some of the significance response acquired.
Figure 4.10 shows a constant steady-state error where the controller settled at 250 instead of 300. As shown in
Figure 4.11, increment of increases oscillation, further increment in
worsened the oscillation. Hence,
value
was selected as 1.
The steady-state error was eliminated in Figure 4.12 when
. Further increase in
controller response as shown in Figure 4.13. Hence, value was selected as 0.01.
Finally, increment in

did not improve the

causes the controller become unstable as shown in Figure 4.14.

From the analysis above, the motor PID controller gain was set to

, and

106
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.15: Graph of Left Motor Response with Different Speed Set Point

Figure 4.16: Graph of Right Motor Response with Different Speed Set Point
107
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

Figure 4.15 and Figure 4.16 show the tuned motor PID controller response on left and right motor with different
speed set point. Negative sign indicates opposite direction of rotation. As shown, both motors produced similar
response in different speed.

4.4

Balance PID Controller

No.

Table 4.1: Different Balance PID Gain Combinations Effect on Robot Response
Gains
Results

50

200

50

50

100

50

100

50

20

Robot too slow.


Cannot balance entirely.
Robot fast.
Its motors keep vibrating.
Balanced for few seconds and fell over.
Robot oscillated and moved back and forth violently.
Balanced for more than ten seconds and fell over.
The oscillation in No.3 decreases.
Robot too slow.
Cannot balance entirely.
The oscillation in No.3 decreases.
Robot motors vibrate slightly.
Can balance when motor was not vibrating.
The oscillation in No.3 was eliminated.
Robot motors rotate like a stepper motor.
Robot can balance itself.
Robot movement was not smooth.
Robot movement was smoother than in No.6.
Robot can balance itself.

Table 4.1 shows some of the significance balance PID controller gain combinations effect on the robot response.
After countless of fine tuning, the robot was able to balance itself with the balance PID controller gain set to
,
, and
.

4.5

Remote Control Results


Button Pressed
Forward
Backward
Left
Right

Table 4.2: Remote Control Results


Results
Robot moved forward.
Flag set to forward.
Robot moved backward.
Flag set to backward.
Turned forward left if flag is forward.
Turned backward left if flag is backward.
Turned forward right if flag is forward.
Turned backward right if flag is backward.

Overall, the robot can be moved and turned using the remote control. The robot control was not very smooth due to
signal corruption by noise causing delay to the commands onto the robot. This outcome was expected due to low
cost RF module used for the remote control.

5 Conclusion
Due to the time constraints, the robustness of the robot on different environment has yet to be tested. The robot still
suffered from a little drift on smooth surface. Finally, the balance PID controller response may still be improved with
current hardware. As the recommendations for Further Work, we proposed that the Back-EMF feedback for motor
speed control used in this project cannot acquire the actual distance the robot had travelled. Encoders can be used
on the motors to sense the exact position so that the robot can be programmed for autonomous functions. The PID
controllers used in this project need to be re-tuned whenever there was a change in the structure. Research can be
done on self tuning PID controller to increase the robustness of the control system on different structures as well as
different environments. The remote controlling can be improved by using module that is less susceptible to noise
such as Bluetooth. Extra mechanism can be added to the robot for recovery from fall. In essence, this research and
building of the robot opens the door of possibility to build cheaper and affordable tools for more practical use,
especially in the search and rescue operations.
108
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

International Journal of Network and Mobile Technologies


ISSN 2229-9114 Electronic Version
VOL 2 / ISSUE 2 / MAY 2011

This paper is available online at


http://ijnmt.com/

References
[1] Acroname
Robotics.
(2006).
Back-EMF
Motion
Feedback.
Available:
http://www.acroname.com/robotics/info/articles/back-emf/back-emf.html.
[2] F.
Cook.
(n.d.)
PWM
Motor
Speed
Controller
/
DC
Light
Dimmer.
Available:
http://www.solorb.com/elect/solarcirc/pwm1/.
[3] J. S. Hu, J. J. Wang, and G. C. Sun, Self-balancing control and manipulation of a glove puppet robot on a twowheel mobile platform, in Proceedings of IEEE/RSJ International Conference on Intelligent Robots and Systems,
2009, pp. 424-425.
[4] R. A. Hyde, L. P. Ketteringham, S. A. Neild, and R. J. S. Jones, Estimation of upper-limb orientation based on
accelerometer and gyroscope measurements, IEEE Transactions on Biomedical Engineering, vol. 55, no. 2, pp.
746-754, 2008.
[5] M. A. Johnson, and M. H. Moradi, PID Control: New Identification and Design Methods. Springer, 2005.
[6] W. W. Kong, Robot head to toe, PID for Embedded Design, vol. 4, pp. 9-12, 2010.
[7] D. M. Ling, and W. W. Kong, Robot head to toe, Two Wheeled Balancing Robot, vol. 4, pp. 1-3, 2010.
[8] D. Simon, Kalman filtering with state constraints: A survey of linear and nonlinear algorithms, IET Proceediings
in Control Theory & Applications, vol. 4, no. 8, pp. 1303-1318, 2010.
[9] Society
of
Robots.
(n.d.)
SCHEMATICS
HOW
H-BRIDGES
WORK.
Available:
http://www.societyofrobots.com/schematics_h-bridgedes.shtml.
[10] A. Warnasch, and A. Killen, Low cost, high G, micro electro-mechanical systems (MEMS), inertial
measurements unit (IMU) program, IEEE Position Location and Navigation Symposium, 2002, pp. 299-305.

109
22

Wreless Controlled Two Wheel Balancing Robot

Charles Yong
Chiew Foong Kwong

Você também pode gostar