Design and Implementation of Self Balancing Vehicle by using Microcontroller

DOI : 10.17577/IJERTCONV6IS07096

Download Full-Text PDF Cite this Publication

Text Only Version

Design and Implementation of Self Balancing Vehicle by using Microcontroller

Asha. P 1, Dr. Latha. R 2, Bharanidharan. G. R 3, Ajay Prakadeesh. K 4, Dhivakar. S 5 1Asst. Prof, Department of ECE, K.S.K College of Engineering And Technology,

Darasuram, Thanjavur, Tamil Nadu, India.

2Prof, Department of ECE, K.S.K College of engineering and technology, Darasuram, Thanjavur, Tamil Nadu, India.

3,4,5Student, Department of ECE, K.S.K College of engineering and technology, Darasuram, Thanjavur, Tamil Nadu, India.

ABSTRACTThis paper reports the design, construction andcontrol of a two-wheel self-balancing robot. The system ar-chitecture comprises a pair of DC motor and an Arduino microcontroller board; a single- axis gyroscope and a 2-axis accelerometer are employed for attitude determination. In addition, a complementary filter is implemented to compen-sate for gyro drifts. Electrical and kinematic parameters are determined experimentally; PID and LQR-based PI-PD control designs, respectively, are performed on the linearized equations of motion. Experimental results show that self- balancing can be achieved with PI-PD control in the vicinity of the upright position.

  1. INTRODUCTION

    In the past decade, mobile robots have stepped out of the military and industrial settings, and entered civilian and personal spaces such as hospitals, schools and ordinary homes. While many of these robots for civil applications are mechanically stable, such as Aibo the Sony robotic dog, or four-wheel vacuum cleaners, one that

    ordinary on-lookers would find awe-inspiring is the Segway personal transport,mechanically unstable, two-wheel self-balancing vehicle that has seen deployment for law- enforcement,

    tourism, etc. This vehicle can be rightfully called a robot because,

    without the sensory capability and intelligent control that accompany every

    robot, the Segway can never stay upright.

    While Segway may have been a well-known commercial product, research into the control of such a mechanical system has been diverse. A two-wheel self-balancing robot is very similar to the inverted pendulum, which is an important testbed in control education and research; see, for example . Besides the development of Segway, studies of

    two-wheel self-balancing robots have been widely reported. For example, JOE and nBot are both early versions complete with inertia sensors, motor encoders and on-vehicle microcontrollers. See also an updated reference at the nBot website . Since then, there has been active research on the control design for such platforms, including classical and linear multivariable control method , nonlinear backstepping controls, fuzzy-neural control and combinations of the above . A related and interesting work that is worth mentioning concerns balancing of a four wheeled vehicle on its two side-wheels, using classical control .

    One of the key enabler for this research in the academia is arguably the increasing affordability of commercial off-the- shelf (COTS) sensors and microprocessor boards. While JOE featured a digital signal processor board, controller boards based on microprocessor such as the 68HC11, ARM and the ATmega series of the Atmel architecture have become the staple in recent years. Arduino is an open prototyping platform based on ATmega processors and a C language-like software development environment, and can be connected with a variety of COTS sensors. It is fast becoming a popular platform for both education and product development, with applications ranging from robotics ,

    construction and control of a two-wheel self-balancing robot. The robot is driven by two DC motors, and is equipped with an Arduino Mega board which is based on the ATmega2560 processor, a single-axis gyroscope and a 2-axis accelerometer for attitude determination. To compensate for gyro drifts common in COTS sensors, a complementary filter is imple-mented ; for a single-axis problem such as this balancing robot, the complementary filter approach is significantly simpler than the Kalman filter. Two control designs based on the linearized equations of motion is

    adopted for this project: a proportional-integral-differential (PID) control, and

    a proportional-integral proportional-differential control based on linear quadratic regulator (LQR) design. The approach is found to be robust to modeling errors which can be incurred during experimental determination of such electrical and kinematic parameters as moments of inertia and motor gains. Simulation and experimental results are presented, which show that stability of the upright position is achieved with PI-PD control within small tilt angles.

    This paper is organized as follows: Section 2 describes the hardware and system architecture of the robot; Section 3 details the designs of the complementary filter, inner control loop to equilibrate the two motors, and balancing control; Section 4 presents the experimental results, followed by some concluding remarks in Section 5.

  2. ST RUCTURE OF THE

    TWO-WHEEL BALANCINGROBOT

    The structure of a self-balancing robot can be classi-fied into three parts: sensors, motor and motor control, and develop board Section II-A introduces the application and advantage of the sensors on the proposed balancing robot, and how these sensors are employed to obtain measurements of acceleration, distance traveled, and

    robot tilt angle. Section II-B describes motor selection and control for the balancing robot. Section II-C discusses the reason behind choosing the Arduino develop board, and how it is deployed.

    1. Selection and Application of Sensors

      1. Gyroscope: The gyroscope is the sensor which canmeasure the angular velocity of the balancing robot, and send the data to the development board. The present robot uses the Parallax L3G4200D MEMS Gyroscope, which sends data via serial communication to the develop board, and has the advantage of three-axis angular measurement (although only one axis is used), low-power consumption, and low-cost. Theoretically, integrating the angular velocity will yield the angle directly; however, this process will also integrate noise in the gyroscope measurement. As a result, the value of will diverge. Section III-A will explain compensation of angular drift using the complementary filter approach.

      2. Accelerometer: The accelerometer measures the totalexternal acceleration of the balancing robot, which includes the gravitational and motion accelerations. In this project, we choose the LilyPad ADXL330 which features properties such as three-axis sensing, output-voltage signal conditioning, and low cost. Following the direction cosine method, one can use the X – and Z-axis gravitational acceleration measurements to calculate the tilt angle . Although this method gives quickly, it can be easily influenced by external forces and noise.

      3. Encoders: The encoders return the rotation angles ofindividual motor shafts as digital signals, which are sent to the processor. After conversion based on gear ratio and wheel radius, the distance traveled can be calculated. The encoder chosen for this project is the Pololu 64 cycle-per- revolution hall effect encoder, which provides a resolution of 64 counts per revolution of the motor shaft.

    2. Motor and Motor Control Board

      Motor selection for the balancing robot emphasizes torque output instead of velocity, because it has to oppose the rotational moment that gravity applies on the robot. Hence, the motors need to provide enough torque to correct the robots body pose back to a balanced state. Base on a preliminary calculation of the maximum torque required to correct the robot from a tilt angle of 20 degree, we choose a pair of the Pololu 67:1 Metal Gearmotor 37Dx54L mm with the above 64 CPR Encoder. Each motor provides a torque of

      200 oz-in, sufficient for our purpose. The large currents drawn by the motors are supplied by the Pololu Dual VNH2SP30 motor control board, which can delivery a 14- Ampere continuous output current at a maximum operating voltage of 16 Volts.

    3. Arduino Mega Development Board

      Selection of the development board is based on the fol- lowing considerations:

      1. Performance: The self-balancing robot needs almostreal-time response to estimate and correct its tilt angle. Hence, the development board must provide a processing speed that is sufficiently fast to perform the processing tasks, including data acquisition, control computation and signal output, within the sampling time. Based on preliminary calculations, a sampling time smaller than 0.05 seconds is required. The Arduino Mega development board is equipped with the ATmega2560 processor, which features a maximum clock rate of 16 MHz. In our implementation, a sampling time of 0.01 seconds can be achieved with a 30% to 40% buffer.

      2. I/O Pins: Another issue is the number of I/O pinsavailable. On the robot, sensors are deployed to obtain measurements of its motion: a gyroscope and an accelerom- eter are used to estimate the tilt angle, encoders are used to obtained odometric measurements. In addition, a motor control board is interfaced with the development board for delivery of PWM signals. Base on the pin-outs of these sensors and the motor control board, it has been determined that at least thirty I/O pins are needed. The Arduino Mega features 54 general-purpose digital I/O pins of which 15 provide PWM output. Some of the digital I/O pins also support serial communication such as I2C and SPI, as well

        as interrupt handles. The board also features sixteen 10-bit analog inputs for 0-5V input, giving a quantization limit of 4.9mV.

      3. Open Source: To alleviate difficulties in programming,a user-friendly development environment, useful function libraries and references are preferred. These requirements are well met by the Arduino development environment which is based on the C language. User- contributed function libraries like PWM control, I2C and SPI communication reduce difficulties in learning to program the Arduino boards. Most importantly, Arduino is open-source with a large user community and up-to-date discussion forums. This allows students to study other users codes, compare results, and make modifications according to the projects needs.

      4. price and Expansions: Arduino boards are low-costand expandable, where optional peripherals called shields can be purchased as and when needed. The accessibility of these products in terms of price versus functionality makes them ideal solutions for academic and student projects.

    4. Power Supply

    For power supply, the motors need a voltage between 12V to 16V, and the development board needs between 5V to 15V. Hence, two sets of batteries are incorporated: for the motors we select a 14.8 volt lithium battery, and for the development board, we choose a four-cell (4×1.5 volts) Ni- MH battery pack.

  3. ANGLE ESTIMATION AND BALANCING CONTROL

    The system architecture of the self-balancing robot is as shown in Fig. 2, where the forward loop comprises the robot, a balancing controller which delivers a motor-control signal, and a inner-loop controller for wheel synchronization. Feedback is provided through a complementary filter whose function is to provide an estimate of the robot tilt angle from gyroscope and accelerometer measurements. In the following sections, we shall first describe the complementary filter, followed by the wheel- synchronization controller, and finally the balancing controller.

    1. Angle Estimation via Complementary Filter

      In Section II, it has been seen that a gyroscope is used to measure the angular velocity of the robot, whereas an accelerometer measures the Y – and Z-components of grav- itational acceleration, and encoders measure the distance travelled by the wheels. In the balacning control, the tilt angle is corrected to the upright position by using wheel motion. This requires a measurement of the tilt angle which must be accurate. The easiest way to obtain the angle is to use the gyroscope; since the gyroscope provides the angular velocity, integrating the latter will produce the angle. However, the gyroscope measurement contains noise. Hence the previous method will not only integrate the angular

      velocity, but also the noise. This will make the integrated data diverge from the correct angle. Another method is to apply the direction-cosine method to the gravity components measured by the accelerometer to obtain immediately; however, this is also affected by noise and the robots accelerating motion.

      To solve the problem of angle measurement, we design a complementary filter [20], a block diagram of which is shown in Fig. 3. The complementary filter uses the measurementsof the gyroscope and accelerometer, and respectively

    2. Inner-loop Control for Wheel Synchronization

      Ideally, if the same motor control signal is sent to the motors control board, both motors should rotate at the same speed. But in the real environment there are many reasons for which the motors rotate at different velocities under the same input signal, such as defects of the motors, terrain and hindrance on the ground. Thus, a method to synchronize both motors is needed. To solve this problem we design a wheel synchronization controller consisting of a simple PI con-troller with the block diagram given in Fig. 5. This controller adjusts the PWM inputs to the motors so that the difference between the left and right encoders tracks zero. Fig. 6 shows the experimental results of wheel travel distances with and without wheel synchronization, and Fig. 7 shows the motor control signals under wheel synchronization. It is clear that wheel synchronization is effective.

      Fig. 5. Block diagram of wheel synchronizer

      Time (sec)

      36

      0 2 4 6 8 10 12

      Time(sec)

      Fig. 7. Motor control signals with wheel synchronization

      (C.G.) ; is the tilt angle [rad], = is the angular rate [rad/s]; and Va is the motor input voltage [V]. The model parameters are defined as:

      2 Iw

      Fig. 6. Test results of of wheel travel distances. Top: The wheels travel distances coincide when wheel synchronization control is employed. Bottom: At equal

      = Ip + 2Mpl (Mw +

      2Iw

      = 2Mw+ r2 + Mp,

      r2 ),

      motor input, the wheels travel at different speed with without wheel synchronization.

    3. Dynamical Model

      4

      3

      4

      M Value

      2

      4

      1

      4

      0

      r

      3

      9

      3

      8

      Mp= mass of the robots chassis, [kg] Ip= moment of inertia of the robots chassis, [kg.m2]

      l = distance between the center of the

      wheel and the robots center of gravity, [m] Mw= mass of robots wheel, [kg]

      km= motors torque constant, [N.m/A]

      ke= back EMF constant, [V.s/rad]

      R = terminal resistance, []

      r = wheel radius. [m]

      The above physical parameters are determined experimen- tally, either by mechanical procedures (e.g. the trifilar pendu-lum method) or electrical measurement. The values obtained are listed below:

      = 0.0180, = 1.7494,

      M = 1.51 [kg], I = 0.0085 [kg.m2],

      p p

      37 l = 0.0927 [m], Mw= 0.08 [kg],

      Fig. 8. Definition of motion variables

      0.2

      0.1

      5

      0.1

      0.0

      5

      0

      0.

      05

      0.

      1

      0.

      15

      0.

      2

      3 40

      0 02

      Root Locus

      10 0 10 20

      Real Axis

      1. PID Control via Root-Locus Design: PID control isa fundamental method wich has been extensively studied and implemented in many modern industrial applications. The PID control is chosen because it is easy to learn and implement, for which text-book design methods are available.

        Fig. 10. Root-locus of the loop gain L(S) =C(S)G(S), with closed-loop

        poles at a gain of K= 45 (diamond). A third pole is further in the left-half

        plane.

        Fig. 9. Block diagram of balancing robot

        The block diagram of the PID controller is as shown in

        Fig. 11. The block diagram of PI-PD controller

      2. LQR Design and PI-PD Control Implementation: Asan alternative to PID control, we also develop an LQR design

    for the plant (1), which can be written in the form =

    T

    Fig. 9, wherein the complementary filter generates estimates

    A + Bu, with the state vector = [x x ]

    . Given the

    of the angular velocity and angle . Instead of differ- entiating the angle measurement which will amplify noise, differential control is implemented by multiplying with

    the differential gain Kd. Proportional control is given by multiplied by the proportional gain Kp, whereas numerical integration of and multiplication by the integral gain Ki yields the integral control.

    Taking the tilt angle as output, the transfer function from Va to can be derived from the model (1) as:

    (s) 6.304s

    covariance matrices Q and R, LQR control is given by

    Va=K , K = R1BT P, (6)

    where P is the solution of the associated Ricatti equation AT P + P A P BR1BT P + Q = 0. Choosing Q =

    diag([0.00001, 0.0001, 10, 0.05]) and R = 0.001, we obtain the following LQR gains:

    k1 k2 k3 k4 = 10 33.8 1052.9 77.6 ,(7)

    with the closed-loop eigenvalues

    Va(s)

    = G(s) =

    s3+ 23.68s2135.7s 2162

    . (3)

    (446.5, 14.1, 0.06, 0.34).

    The transfer function of a PID controller can be expressed as:

    Implementation of the input function Va is achieved using the output variables in (2); hence,

    where K = Kd , z1+ two zeros and a pole at the

    Ki (s + z1)(s + z2)

    Kp+ Kds + = K = K C(s),(4)

    z2= Kp/Kd and z1z2= origin to the loop gain L(s) = Ki /Kd. Hence, PID C(s)G(s), and by determining

    s s design can be the control gain K via root-locus performed by adding

    The resulting root locus of the loop gain is shown in Figure

    1. It can been seen that the closed-loop poles enter the open left-half-plane for a large enough gain K . At a damping ratio equal to 1, we obtain the gain K = 0.614

      In practice, the above LQR control can be implemented as a PI-PD controller as shown in Fig. 11, where the actual mea- surements used are the wheel velocity v measured with the encoder, and the tilt angle returned by the complementary 638 filter. Hence, in Laplace notation,

      Ki

      V a(s) = s v(s) +Kp2v(s) +Kp1(s) +Kds(s),(9)

      2.126s2 140.7

      where v(s) = V a(s),

      1. Remote control: Low-cost communicate hardware suchXbee may be added to the robot, so that the user can control its motion remotely and read the data via telemetry. Also, user-controlled motion such as forward, backward, turn right and left, may be implemented.

      2. Obstacle avoidance and perimeter following: A pos- sible extension is to combine the Arduino system and other sensors such ultrasonic and IR senses, GPS, digital compass and Camera to address other advanced applications, e.g. obstacle avoidance and perimeter following.

      REFERENCES

      1. R. Fierro, F. Lewis, and A. Lowe, Hybrid control for a class of underactuated mechanical systems, IEEE Transactions on Systems,Man

        (s) =

        s3 + 23.68s2 135.7s2162

        6.304s

        V a(s). s3 + 23.68s2 135.7s2162

        and Cybernetics, Part A: Systems and Humans, vol. 29, no. 6, pp. 6494, nov 1999.

      2. K. Xu and X.-D. Duan, Comparative study of control methods of single- rotational inverted pendulum, in Proceedings of the First In-ternational Conference on Machine Learning and Cybernetics, vol. 2,2002, pp. 7768.

  4. COMPARISON IN EXPE RIME NT

    Comparison between the PID and PI-PD controllers is conducted in experiment. From the results shown in Fig. 12, it can be seen that stability with PID control is marginal: beyond 25 seconds angular oscillations exceed the torque limit of the motors and cannot be contained. Moreover, it is found that the robots position drifts during balancing due to

    C.G. misalignment. On the other hand, much improved stability is achieved by PI-PD control rather than the PID control. Moreover, PI-PD control is able to compensate for

    C.G. misalignment and allow the robot to return to its initial position.

    10 Tilt angle (deg)

    5

    0

    5

    15

    20

    25

    30

    35

    40

    45

    50

    15

    20

    25

    30

    35

    40

    45

    50

    100 5 10

    10

    Tilt angle (deg)

    5

    0

    5

    100 5 10

    time (sec)

    Fig. 12. Experimentally obtained history of tilt angle: PID controller (top), PI-PD controller (bottom).

  5. CONCL UDING RE MARKS

We have constructed a two-wheel self-balancing robot using low-cost components, and implemented a tilt-angle estimator and a stabilizing PI-PD controller for the balancing motion. The following are some future goals for improve- ment.

1) Design improvement: Design improvement for betterbalancing motion will require optimization of the mechanical design such as relocating the center of mass, better sensor placement, modification of the complementary filter to reject disturbances due to translational motion, and a robust control design.

    1. F. Grasser, A. DArrrigo, S. Colombi, and A. C. Rufer, JOE: A mo-bile, inverted pendulum, IEEE Transactions on Industrial Electronics, vol. 49, no. 1, pp. 10714, 2002.

    2. D. P. Anderson. (2003, Aug.) nBot balancing robot. Online. [Online].

      Available: http://www.geology.smu.edu/ dpa-www/robo/nbot

    3. R. C. Ooi, Balancing a two-wheeled autonomous robot, Final Year Thesis, The University of Western Australia, School of Mechanical Engineering, 2003.

    4. N. M. A. Ghani, F. Naim, and P. Y. Tan, Two wheels balancing robot with line following capability, World Academy of Science,Engineering and Technology, vol. 55, pp. 6348, 2011.

    5. X. Ruan, J. Liu, H. Di, and X. Li, Design and LQ control of a two-wheeled self-balancing robot, in Control Conference, 2008. CCC2008. 27th Chinese, july 2008, pp. 275 279.

    6. T. Nomura, Y. Kitsuka, H. Suemistu, and T. Matsuo, Adaptive backstepping control for a two-wheeled autonomous robot, in ICROS- SICE International Joint Conference, Aug. 2009, pp. 468792.

    7. G. M. T. Nguyen, H. N. Duong, and H. P. Ngyuen, A PID backstep-ping controller for two-wheeled self-balancing robot, in Proceedingsfo the 2010 IFOST, 2010.

    8. K.-H. Su and Y.-Y. Chen, Balance control for two-wheeled robot via neural-fuzzy technique, in SICE Annual Conference 2010, Proceed-ings of, aug. 2010, pp. 2838 2842.

    9. X. Ruan and J. Cai, Fuzzy backstepping controller for two-wheeled self- balancing robot, in International Asia Conference on Informaticsin Control, Automation and Robotics, 2009, pp. 1669.

    10. D. Arndt, J. E. Bobrow, S. Peters, K. Iagnemma, and S. Bubowsky, Two- wheel self-balancing of a four-wheeled vehicle, IEEE ControlSystems Magazine, vol. 31, no. 2, pp. 2937, April 2011.

    11. Arduino. [Online]. Available: http://arduino.cc/

    12. J. Sarik and I. Kymissis, Lab kits using the Arduino prototyping platform, in IEEE Frontiers in Education Conference, 2010, pp. T3C 15.

    13. G Guo and W. Yue, Autonomous platoon control allowing range-limited sensors, IEEE Trans. on Vehicular Technology, vol. 61, no. 7,

      pp. 29012912, 2012.

    14. P. A. Vignesh and G. Vignesh, Relocating vehicles to avoid traffic collision through wireless sensor networks, in 4th InternationalConference on Computational Intelligence, Communication Systems and Networks. IEEE, 2012.

    15. M. J. A. Arizaga, J. de la Calleja, R. Hernandez, and A. Benitez, Automatic control for laboratory sterilization process rsd on Arduino hardware, in 22nd International Conference on Electrical Communi-cations and Computers, 130-3, Ed., 2012.

    16. S. Krivic, M. Hujdur, A. Mrzic, and S. Konjicija, Design and implementation of fuzzy controller on embedded computer for water level control, in MIPRO, Opatija, Croatia, May 2125 2012, pp. 174751.

    17. V. Georgitzikis and I. Akribopoulos, O.and Chatzigiannakis, Control-ling physical objects via the internet using the Arduino platform over 802.15.4 networks, IEEE Latin America Transactions, vol. 10, no. 3,

      pp. 16869, 2012.

    18. A.-J. Baerveldt and R. Klang, A low-cost and low-weight attitude es- timation system for an autonomous helicopter, in IEEE InternationalConference on Intelligent Engineering Systems, sep 1997, pp. 3915.

Leave a Reply