Controlling Quadcopter Altitude using PID-Control System

DOI : 10.17577/IJERTV8IS120118
Download Full-Text PDF Cite this Publication

Text Only Version

 

Controlling Quadcopter Altitude using PID-Control System

Ayele Terefe Bayisa 1

Tianjin Key Laboratory of Information sensing and Intelligent control

School of Automation and Electrical Enginering Tianjin University of Technology and Education, Tianjin 300222,P.R.China.

Abstract This work presents the stabilization of a quadcopter by using PID controllers to regulate its four basic movements: roll, pitch, yaw angles, and altitude. The quadcopter was originally equipped with sensors and software to estimate and control the quadcopters orientation, but did not estimate the current position. A GPS module, GPS antenna and a lidar have been added to measure the position in three dimensions. Filters have been implemented and developed to estimate the position, velocity and acceleration. The position controller maintains a constant position, while the trajectory controller maintains a constant velocity while travelling along a straight line. These position and trajectory controllers calculate the reference angles required to direct the thrust necessary to control the quadcopters movement. The system also consists of IMU (Inertial Measurement Unit) which consists of accelerometer and gyro sensors to determine the system orientation and speed control of four motors to enable the quadcopter fly. Simulations analysis of quadcopter is carried out using MATLAB Simulink.

KeywordsQuadcopter, altitude control, PID-controller.

  1. INTRODUCTIONA quadcopter is the most popular configuration of multirotor unmanned aerial robot, extensively for civilian applications [1,2]. In recent years, significant growth of interest is witnessed towards the academic research of the quadrotor. This is possibly attributed to their certain features, such as simple mechanical structure, hovering, and agile maneuverability. With the increasing requirement of autonomous flight under different conditions, control of the quadrotor is an important challenge.Complex rotation and translation operations are also commonly encountered in the mathematical model, resulting in complex equations that have to be taken into account when designing control laws. On the other hand, the position control and attitude control of the quadrotor are extremely sensitive to external disturbance, such as wind gusts. Particularly, robustness issues may be critical for the control of quadrotor since they are subjected to the complicated dynamics and external disturbances. Several proper control methodologies for the quadrotor have been reported in the literatures, such as proportion integration differentiation (PID) control [3], backstepping control [4], sliding mode control [5], and model predictive control [6].
  2. RELATED WORKIn order to weaken the effect of wind gusts, some authors have proposed complicated control techniques to achieve stability. In the literatures [7, 8] adaptive controllers of different structures were verified by simulations and experiments on test bench. For control of a multirotor aircraft, Salazar et al.
    1. proposed a novel mathematical model of the wind gusts and designed a simple nonlinear control law to resist the wind disturbance. The effect of wind disturbance was discussed towards the issue of (unmanned air vehicle) UAV path planning in the literatures [10, 11]. From the analysis, compensation control for the aircraft may be an effective method. Dong et al. [12] designed a flight controller with disturbance observer (DOB) to guarantee the high- performance trajectory tracking of a quadrotor. The DOB- based controller is robust to wind gusts without the use of high control gain or extensive computational power.In the past years there has been increasing interest in Unmanned Aerial Vehicles (UAVs). Among different UAVs, quadrotors are of special interest in control from both theoretical and applied perspectives [1319]. The quadrotor dynamics involve challenges such as parametric uncertainties, non-linearity, coupling and external disturbances [1619]. A high-performance attitude control is a prerequisite for developing any other high-level control tasks [14,18]. In practical applications, the attitude of an UAV is automatically stabilized via an on-board controller and its position is generally controlled by an operator through a remote-control system [19].In its motion, quadcopter have three main factors: roll, pitch and yaw. Based on the roll, pitch and yaw, state estimation of quadrotors attitude model is challenging. The rotors are directed upwards and placed in a square formation with equal distance from the center of mass of quadrotor. In the early days of flight, quadrotors were seen as possible solutions to some of the persistent problems in vertical flight. The Euler angle are three angles introduced by Leonhard Euler, which used to describe the orientation of a rigid body. To describe such an orientation in the 3-dimensional Euclidean space, three parameters are required and they can be described in several ways. Using zyx Euler angle we will describe the

      orientation of a frame of reference relative to another. Euler angle represents a sequence of three elemental rotations, since any movement can be achieved by combining three elemental rotations.

  3. QUADROTOR DYNAMICSThe quadcopters motion is governed by the lift forces, produced by the rotating propeller blades, whereas the translational and rotational motions are achieved by means of difference in the counter rotating blades. Specifically, the forward motion is achieved by the difference in the lift force produced from the front and the rear rotors velocity, the sideward-motion by the difference in the lift force from the two lateral rotors, whereas the yaw motion is produced by the difference in the counter-torque between the two pairs of rotors frontright and backleft. Finally, motion at the perpendicular axis is produced by the total rotor thrust. The model of the quadcopter utilized in this paper assumes that the structure is rigid and symmetrical, the center of gravity and the body-fixed frame (BFF) origin coincide, the propellers are rigid and the thrust and drag forces are proportional to the square of propellers speed.Fig 1. Quadcopter structure and frames conguration

    The body frame is xed on the quadcopter. The origin is in the center of mass of the quadcopter, while Z axis ZB is pointing vertically upward and the X axis XB is pointing to rotor1.Based on this frame system, we dene the translational position as [X Y Z]T and the angular position as [ ]T

    First let us dene the elementary rotations about X, Y and Z axis.

    (1)

    (2)

    (3)

    For , it means a single rotation of radius around X axis. Column 1, 2, 3 refers to the expression of the unit vectors of and in the inertial frame E. Similarly, and can be interpreted in this way.

    Finally, we can obtain the rotation matrix of the body frame relative to inertial frame:

    Where = and =.

    In the case of a quadcopter, there is gyroscopic torque generated by the rotating propellers. However, it is relatively tiny compared to the other terms in the equation. We can nullify this term for a simpler control model in the following design.

    (5)

    Divide both side by Icm, we obtain the equation for rotational dynamics.

    – (6)

    Based on (5) and (6), we now have the equations for the state-space model

    <p(7)

    We define the trust and torque values as the control input of state space model

    (8)

    Where Jr is the rotor inertia and r = 2 + 4 – 1 – 3

  4. PARAMETER SPECIFICATION
    Parameters values units
    m 0.25 kg
    g 9.81 m/s2
    l 0.25 m
    0.019688 Kg.m2
    0.01961 Kg.m2
    0.03938 Kg.m2
    b 31.3*10-5 Nms2
    d 7.5*10-7 Nms2

    Table 1. Parameters value

  5. PID CONTROLLERPID stands for Proportional, Integral, Derivative, its part of a flight controller software that reads the data from sensors and calculates how fast the motors should spin in order to retain the desired rotation speed of the quadcopter.The goal of the PID controller is to correct the error, the difference between a measured value (gyro sensor measurement), and a desired set-point (the desired rotation speed). The error can be minimized by adjusting the control inputs in every loop, which is the speed of the motors.

    I/p

    O/p

    Fig 4. Input and output blocks using simulink

    The desired yaw rate is typically taken directly from the following command input

    Fig 2.PID-controller

      • P looks at present error the further it is from the set-point, the harder it pushes
      • D is a prediction of future errors it looks at howfast you are approaching a set-point and counteracts P when it is getting close to minimize overshoot
      • I is the accumulation of past errors, it looks at forces that happen over time; for example, if a

    quadrotor constantly drifts away from a set-point due to wind, it will spool up motors to counteract it

    A quadcopter controller and plant system will be shown in simulink model as shown below

    Fig 3. quadcopter controller and plant system.

    This series of blocks of input and outputs are shown below

    Fig 5. Desired yaw rate

    The desired roll and pitch angles computed by the position controller and combined with the desired altitude controller as shown below

    Fig 6. Roll and pitch angle using simulink

    The angular velocity controller computes the final three moment control inputs. Each PID block contains the individual proportional, integrator and derivative control shown in block diagram below

    Fig 7. PID control simulink

    A quadcopter dynamic block diagram is shown as the following figure

    Fig 8. Quadcopter dynamic model simulink

    The motor speed calculator limits the control inputs to the physical motor parameters

    Fig 9. Speed control system simulink

    A sample plot depicting the systems response to step inputs is shown below validating the control system design and simulaion

    Fig 10.x,y,z and yaw position

    The position and altitude of quadcopter output is shown in figure below.

    Fig 11. Quadcopter altitude position

    Fig 12. PID-control Simulation diagram

  6. CONCLUSION AND FUTURE WORK

In this paper, the working and implementation of pitch, roll and yaw movement of quadcopter based on PID logic controller is presented. Mathematical modeling of quadcopter is done using MATLAB Simulink model. For stabilization of quadcopter, PID logic controller was chosen. PID logic was implemented successfully in MATLAB. A prototype of quadcopter is build using PID logic controller embedded on it. The working and performance of quadcopter is tested and desired outputs were obtained using PID controller. But, Ziegler-Nichols tuning method is more effective controller.

REFERENCES

  1. Amin R, Aijun L, Shamshirband S. A review of quadrotor UAV: Control methodologies and performance evaluation. International journal of automation and control engineering, 2016, vol. 10, no. 2, pp. 87103.
  2. Tofigh M A, Mahjoob M J, Ayati M. Dynamic modeling and nonlinear tracking control of a novel modified quadrotor. International journal of robust and nonlinear control, 2018, vol. 28, no. 2, pp. 552567.
  3. An S, Yuan S, Li H. Self-tuning of PID controllers design by adaptive interaction for quadrotor UAV in Proceedings of the 7thIEEE Chinese guidance, Navigation and Control Conference, August 2016, CGNCC 2016, pp. 15471552.
  4. Das A, Lewis F, Subbarao K. Backstepping approach for controlling a quadrotor using Lagrange form dynamics: Journal of intelligent & robotic systems, 2009, vol. 56, no. 1-2, pp. 127151.
  5. Lee D, Kim H J, Sastry S. Feedback linearization vs adaptive sliding mode control for a quadrotor helicopter. International journal of control, automation and systems,2009, vol. 7, no. 3, pp. 419428.
  6. Chamseddine A, Zhang Y, Rabbath C A, Fulford C, Apkarian J. Model reference adaptive fault tolerant control of a quadrotor UAV. USA, March 2011.
  7. Chen F, Lu F, Jiang B, Tao G. Adaptive compensation control of the quadrotor helicopter using quantum information technology and disturbance observer. Journal of the Franklin institute, 2014, vol. 351, no. 1, pp. 442455.
  8. Salazar S, Romero H, Lozano R. Modeling and real-time stabilization of an aircraft having eight rotors. Journal of intelligent and robotic systems, 2008, vol. 54, no. 1-3, pp. 455 470.
  9. Ding L, Ma R, Wu H, Feng C, Li Q, Yaw control of an unmanned aerial vehicle helicopter using linear active disturbance rejection control. Proceedings of the Institution of Mechanical Engineers: Journal of Systems and Control Engineering, 2017, vol. 231, no. 6, pp. 427435.
  10. Jackson S, Tisdale J, Kamgarpour M, Basso B, Hedrick J K. Tracking controllers for small UAVs with wind disturbances: theory and flight results. Proceedings of the 47th IEEE Conference on Decision and Control, December 2008, pp. 564 569.
  11. Jennings A L, Ordóñez R, and Ceccarelli N. An ant colony optimization using training data applied to UAV way point path planning in wind. Proceedings of IEEE Swarm Intelligence Symposium, 2008.
  12. Dong W, Gu G Y, Zhu X, Ding H. High-performance trajectory tracking control of a quadrotor with disturbance observer, Sensors and Actuators, 2014, vol. 211, pp. 6777.
  13. Bouabdallah S. Design and control of quadrotors with application to autonomous ying. Lausanne Polytechnic University,2007.
  14. Tomic T, Schmid K, Lutz P, Domel A, Kassecker M, Mair E, Grixa I L, Ruess F, Suppa M, Burschka D. Toward a fully autonomous UAV: Research platform for indoor and outdoor urban search and rescue. Robotics & Automation Magazine, IEEE,2012, 19(3), pp. 4656.
  15. Mahony R, Kumar V, and Corke P. Multirotor aerial vehicles: modeling, estimation, and control of quadrotor. 2012, Robotics & Automation Magazine, IEEE, 19(3), pp. 2032.
  16. Bergamasco M, Loveram M. Identication of linear models for the dynamics of a hovering quadrotor. Control Systems Technology,2014, IEEE Transactions on, 22(5), pp. 16961707.
  17. Liu H, Lu G, Zhong Y. Robust LQR attitude control of a 3-DOF laboratory helicopter for aggressive maneuvers. Industrial Electronics, IEEE Transactions ,2013, 60(10), pp. 46274636.
  18. Bouabdallah S, Siegwart R. Full control of a quadrotor: In Intelligent robots and systems. IROS2007. IEEE/RSJ international conference, 2007, pp. 153158
  19. Franchi A, Secchi C, Ryll M, Bulthoff H, Giordano P R. Shared control: Balancing autonomy and human assistance with a group of quadrotors uavs. Robotics & Automation Magazine, IEEE,2012, 19(3), pp. 5768

2 thoughts on “Controlling Quadcopter Altitude using PID-Control System

  1. Tariku says:

    What a wonderful journal it is! World needs such admirable, meaningful and result oriented journals and projects!
    Long live Engineer Terefe

  2. Werkisa Buzayehu says:

    Congratulations my brother! Your effort is succeeded now happy again and again. Have a nice life Engineer Terefe Bayisa

Leave a Reply to Werkisa Buzayehu