검색 전체 메뉴
PDF
맨 위로
OA 학술지
Constant Altitude Flight Control for Quadrotor UAVs with Dynamic Feedforward Compensation
  • 비영리 CC BY-NC
  • 비영리 CC BY-NC
ABSTRACT
Constant Altitude Flight Control for Quadrotor UAVs with Dynamic Feedforward Compensation
KEYWORD
Altitude control , Feedforward compensation , Quadrotor , Unmanned aerial vehicle
  • 1. Introduction

    The field of unmanned aerial vehicles (UAVs) has gained increasing research interest in recent years. This is mainly because of their ability to effectively perform different tasks in a wide range of military and commercial applications. Currently, UAVs are being used in several applications such as search and rescue missions [1], power plant inspection [2], surveillance [3], agricultural services [4], and mapping and photography [4].

    Four-rotor or quadrotor UAVs belong to a promising class of UAVs, and significant research progress has been achieved in the field in recent years. Because of their small size, low weight, and high maneuverability, they are suitable for both indoor and outdoor applications. The significant advantage of quadrotors is their ability to perform vertical take-off and landing, whereas their main disadvantage is their limited flight time.

    A quadrotor is an underactuated helicopter with four input forces and six output coordinates with highly coupled dynamics; for this reason, controller design for quadrotors is a challenging issue. Currently, researchers are primarily focused on the design of linear controllers, such as proportional-integral-differential (PID) controllers [5] and linear quadratic regulators (LQregulators) [6], and nonlinear control methods, which include sliding mode controllers [7], backstepping control approaches [8], adaptive controllers [9], and model predictive attitude controllers [10]. Several studies have investigated the design of controllers for quadrotor stabilization during hovering [11], whereas others are dedicated to controller design for trajectory tracking [12]. This paper focuses on the design of a dynamic feedforward controller that improves the behavior of the UAV during the transition period when the flying mode changes from hovering to translational motion in the horizontal plane. A significant drop in altitude can occur in this period if linear controllers like PID or LQR are used. In this paper, a feedforward compensator that improves the performance of the altitude controller and does not require increased computational power is proposed. To further improve altitude control, a fuzzy logic controller is introduced into the control system.

    The rest of the paper is organized as follows. In Section 2, we describe the quadrotor dynamic model. Section 3 describes the design of the proposed dynamic feedforward controller and fuzzy controller. Simulation results are presented in Section 4. We present our concluding remarks and outline out future work in Section 5.

    2. System Model and Dynamics

    In this section, we examine the dynamics of a quadrotor helicopter to gain the insight necessary for quadrotor controller design.

    Quadrotors consist of four rotors attached to a rigid crossshaped airframe, as shown in Figure 1, with two opposing rotors rotating clockwise (1,3) and the other two rotating counterclockwise (2,4). The quadrotor is controlled by using the differential control of the thrust generated by each rotor. Vertical motion is accomplished by simultaneously increasing or decreasing the speed of all four rotors. Pitch motion is achieved by increasing the difference in the speed between the front and rear set of rotors. Roll motion is archived in the same manner using the left and right set of rotors. A quadrotor is an underactuated system, which means that the forward/backward and left/right motions are coupled with pitch and roll motions, respectively, and the quadrotor can be controlled through them. The remaining yaw motion can be realized by increasing the speed of the two rotors rotating in the clockwise direction and by decreasing the speed of the remaining two rotors.

    The dynamics of quadrotor helicopters have been studied in detail by several groups [13, 14]. A rigid-body model of a quadrotor can be obtained using Newton’s equations [15], as given in Eq. (1):

    image

    where m and are the mass and rotational inertia matrix of the flyer. 𝘨 denotes acceleration due to gravity. The matrix R ∈ SO(3) describes the rotational transformation from frame {A} to frame {B}, where {A} is the right-hand inertial frame denoted by with aligned with the direction of gravity, is the body-fixed frame with its origin at The vector describes the linear velocity of the quadrotor expressed in a right-hand inertial frame {A}. Ω ∈ {B} is the angular velocity of the quadrotor expressed by {B}. Ω× denotes the skew-symmetric matrix, such that Ω × 𝜐 = Ω × 𝜐 for the vector cross product x and any vector 𝜐.

    image

    where ϕ, θ, and Ψ are the Euler angles, roll, pitch, and yaw, respectively.

    The total thrust and torques produced by the four rotors are denoted by T and τ {B}, respectively, and can be obtained using the following model:

    image
    image

    where ωi denotes the speed of rotor i. The distance from the rotor to the center of mass is denoted by l. The parameters b and k are the positive proportionality constants relative to the density of air, the shape of the blades, the number of the blades, the chord length of the blades, the pitch angle of the blade airfoil, and the drag constant. Eq. (4) can be written in a matrix form as [15]

    image

    The rotor speeds required for the given values of thrust and moments can be found using Eq. (5) and the inverse of the constant matrix .

    The model given in Eq. (1) is a simplified model that does not consider several aerodynamic effects such as vortex ring state, blade flapping, etc. [15]. However, it is reasonable to neglect these effects at low values of UAV speed for the sake of model simplicity.

    3. Controller Design

       3.1 General Control of Quadrotor

    The control problem is challenging for several reasons. First, the system is underactuated: there are four inputs, whereas the workspace is six dimensional. Second, the aerodynamic model described above has been simplified. In addition, practical motor controllers must overcome the drag moments to generate the required speeds and realize the input thrust T and torques τ . The dynamics of the motors and their interactions with the drag forces on the propellers can be difficult to model, although first-order linear models are a useful approximation. A hierarchical control approach is commonly applied to quadrotors; one such control system is shown in Figure 2 (all the variables with an asterisk superscript (*) are desired values). The lowest level control controls the rotor rotational speed. The next level controls vehicle attitude. The top level controls position along a trajectory.

    This paper focuses on the design of a dynamic feedforward compensator incorporated into the position controller. Position control is achieved by means of conventional proportionaldifferential (PD) controllers, because low velocities are assumed.

       3.2 Dynamic Feedforward Compensator Design

    A quadcopter position controller can be separated into an altitude controller and a translational motion controller. In the hovering mode, only the altitude controller needs to operate; this controller is usually a PD-regulator with constant feedforward compensation for the gravity term. However, when the UAV changes the flight mode from hovering to translational motion, the performance of the altitude controller may deteriorate.

    Quadrotor UAVs must change their roll and/or pitch angles to perform translational motion in the X- or Y-direction. Because the thrust provided by the propellers is always normal to the quadrotor plane, the vertical component of the thrust, which is required to maintain the altitude, can be significantly reduced as a result of quadrotor roll. This results in the UAV losing altitude, which is considered undesirable in most applications and may cause a collision between the vehicle and the environment.

    As quadrotors are conventionally equipped with sensors monitoring the posture of the UAV, the values of pitch and roll angles are available to the control system. Using an accurate mathematical model, it is possible to compensate for the loss of thrust by employing a feedforward term, if the pitch and roll angles are known.

    The equation for altitude dynamics can be derived as an extension of the second expression in Eq. (1).

    image

    Substituting the expression for R given by Eq. (2) into Eq. (6) and dividing both sides of the equation by m, one can obtain the altitude dynamics as

    image

    Normally, quadrotor control systems use static feedforward gravity compensators, as shown in Figure 3a. The compensation term TFF = mg can be obtained from Eq. (7) by assuming that ϕ and θ are zero (the quadcopter is in hovering mode) and setting . However, calculating feedforward term this way may prove to be insufficient in cases when the angles ϕ and θ are different from zero, which occurs in all flight modes except hovering. The insufficiency of the gravity compensation may lead to a decrease in UAV altitude. In addition, the loss of altitude will increase for bigger angles ϕ and θ, although their maximal values are usually restricted in most practical quadcopter UAVs.

    Therefore, we propose the use of a dynamic feedforward compensator term that will change with the roll and pitch angles according to TFF = mg = (cosϕcosθ), as shown in Figure 3b. If the roll and pitch angles are zero, the proposed compensator behaves identically to the conventional static gravity compensator. However, if the roll and pitch angles start to change, the value of the feedforward term increases, which reduces the drop in the UAV altitude. In this manner, it is possible to decrease the loss in altitude when the quadcopter flight mode transitions from hovering to normal flight. The effect of changes in the roll and pitch angles on the feedforward compensator value is demonstrated in Figure 4.

       3.3 Design of Fuzzy Controller

    To improve the performance of altitude control, the PD controller was replaced by a fuzzy logic controller. The proposed fuzzy logic controller provides a faster response with less overshoot by allowing different system parameters to exhibit their most advantageous features at different times. In the proposed fuzzy logic controller, the desired height value z* is compared with the actual height z of the UAV. The difference between these two signals is called the position error (ez). The slope angle (θez) of the error derivative, or the error change rate, can be then calculated as

    image

    The inputs of the fuzzy controller are the position error ez (proportional action) and the theta error θez (derivative action). The output of the proposed fuzzy controller u is multiplied by a gain KF = 0.25TFF . Both inputs and the output of the controller are designed to have five membership functions, namely negative large (NL), negative small (NS), zero (Z), positive small (PS), and positive large (PL). The membership functions of the inputs and output are shown in Figure 5a-c, respectively.

    The fuzzy logic controller’s output indicates how much we need to add to the initial feedforward speed. The output thrust due to the height controller is calculated as need to add to the initial feedforward speed. The output thrust due to the height controller is calculated as

    image

    It should be noted that, in the proposed rules, “negative error” means that the value of the actual position is greater than that of the desired position. Therefore, in this case, we need to decrease the speed of all four motors so as to reduce the thrust force. On the contrary, ’positive error’ means that the value of the actual position is lower than that of the desired position; thus, the speed of the motors should be increased to create a larger thrust force. Using these restrictions, the rules of the fuzzy controller are shown in Table 1. Fuzzy inference generated using the Mamdani method is used. The method of defuzzification used is centroid.

    4. Numerical Simulation

    The effects of the proposed feedforward compensator and the proposed fuzzy logic controller on the UAV performance were investigated in a series of computer simulations. A MATLAB model of a quadrotor UAV was used, with the physical parameters of the quadrotor adopted from the model provided in robotics toolbox for MATLAB. In the four simulation cases, the UAV moves from its starting position (0,0,1)

    to a given point along the X-axis (desired end point is (1,0,1))along the X-axis with a constant speed ( = 1 m/s)along the X- and Y-axis with a constant speed ( = 1 m/s, = 1 m/s)along a circular trajectory in the X-Y plane (x = cos 0.3t m, y = sin0.3t m).

    In all simulation scenarios described above, the altitude of the UAV is required to remain constant.

    The simulation results are shown in Figure 6. In all of the simulation cases, the root-mean-square error (RMSE) and maximum error (Emax) were measured; their values are presented in Table 2.

    [Table 2.] RMSE and maximum altitude drop (Emax) for a system with A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers

    label

    RMSE and maximum altitude drop (Emax) for a system with A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers

    It should be noted that the proposed feedforward controller improved the performance of the system in all simulation cases. The effect of the controller is more significant in the first and fourth scenarios, when the RMSE decreased from approximately 0.4 cm to 0.1 cm and the maximum error decreased from 1.3 cm to 0.3 cm, which corresponds to an approximately 75% reduction in the altitude drop. In the case of motion along a straight line (cases 2 and 3), implementation of the proposed controller resulted in a reduction in RMSE and maximum altitude error by approximately 21% and 24%, respectively. Implementation of the proposed fuzzy logic controller instead of the PD controller allowed further improvement in the performance of the system in all simulation cases. The effect of height drop is nearly canceled in all four scenarios as a result of the implementation of the proposed fuzzy logic controller. In addition, the RMSE decreased by a factor of 100, and the maximum error decreased by a factor of 104.

    5. Conclusions and Future Work

    In this paper, we proposed a dynamic feedforward compensator for altitude control of quadrotor UAVs. The main concept was to incorporate pitch and roll measurements into the feedforward term of the altitude controller so as to provide a higher thrust force when the UAV flight mode changed from hovering to translational motion in the horizontal plane. To further improve altitude control of the quadrotor UAV, we proposed a fuzzy logic based controller that was designed using expert knowledge and was more flexible than a PD controller. A series of numerical simulations were performed to analyze the performance of both controllers; they showed that the implementation of the proposed controllers led to improved results.

    Future work will consider improvements to the proposed controller. Additionally, we intend to investigate the performance of the proposed algorithm in a hardware implementation. Conflict of Interest No potential conflict of interest relevant to this article was reported.

    Conflict of Interest

    No potential conflict of interest relevant to this article was reported.

참고문헌
  • 1. Ryan A., Hedrick J. K. December 12-15, 2005 “A mode-switching path planner for UAV-assisted search and rescue,” [in 44th IEEE Conference on Decision and Control and European Control Conference] P.1471-1476 google cross ref
  • 2. Alexis K., Nikolakopoulos G., Tzes A., Dritsas L., Valavanis K. P. 2009 “Coordination of helicopter UAVs for aerial forest-fire surveillance,” P.169-193 google
  • 3. Caprari G., Breitenmoser A., Fischer W., Hrzeler C., Tche F., Siegwart R., Schoeneich P., Rochat F., Mondada F., Moser R. October 5-7, 2010 “Highly compact robots for inspection of power plants,” [in 1st International Conference on Applied Robotics for the Power Industry] P.1-6 google cross ref
  • 4. Herwitz S. R., Johnson L. F., Dunagan S. E., Higgins R. G., Sullivan D. V., Zheng J., Lobitz B. M., Leung J. G., Gallmeyer B. A., Aoyagi M., Slye R. E., Brass J. A. 2004 “Imaging from an unmanned aerial vehicle: agricultural surveillance and decision support,” [Computers and Electronics in Agriculture] Vol.44 P.49-61 google cross ref
  • 5. Jeong S., Jung S. 2013 “Design, control, and implementation of small quad-rotor system under practical limitation of cost effectiveness,” [International Journal of Fuzzy Logic and Intelligent Systems] Vol.13 P.324-335 google cross ref
  • 6. Bouabdallah S., Noth A., Siegwart R. September 28-October 2, 2004 “PID vs LQ control techniques applied to an indoor micro quadrotor,” [in Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems] P.2451-2456 google cross ref
  • 7. Benallegue A., Mokhtari A., Fridman L. June 5-7, 2006 “Feedback linearization and high order sliding mode observer for a quadrotor UAV,” [in International Workshop on Variable Structure Systems] P.365-372 google
  • 8. Das A., Lewis F., Subbarao K. 2009 “Backstepping approach for controlling a quadrotor using lagrange form dynamics,” [Journal of Intelligent and Robotic Systems] Vol.56 P.127-151 google cross ref
  • 9. Dydek Z. T., Annaswamy A. M., Lavretsky E. 2013 “Adaptive control of quadrotor UAVs: a design trade study with flight evaluations,” [IEEE Transactions on Control Systems Technology] Vol.21 P.1400-1406 google cross ref
  • 10. Alexis K., Nikolakopoulos G., Tzes A. 2011 “Switching model predictive attitude control for a quadrotor helicopter subject to atmospheric disturbances,” [Control Engineering Practice] Vol.19 P.1195-1207 google cross ref
  • 11. Hamel T., Mahony R., Lozano R., Ostrowski J. 2002 “Dynamic modelling and configuration stabilization for an X4-flyer,” [in Proceedings of the 15th IFAC World Congress] P.846 google cross ref
  • 12. Zuo Z. 2010 “Trajectory tracking control design with command-filtered compensation for a quadrotor,” [IET Control Theory & Applications] Vol.4 P.2343-2355 google cross ref
  • 13. Bouabdallah S., Murrieri P., Siegwart R. April 26-May 1, 2004 “Design and control of an indoor micro quadrotor,” [in Proceedings of the IEEE International Conference on Robotics and Automation] P.4393-4398 google cross ref
  • 14. McKerrow P. April 26-May 1, 2004 “Modelling the Draganflyer four-rotor helicopter,” [in Proceedings of the IEEE International Conference on Robotics and Automation] P.3596-3601 google cross ref
  • 15. Mahony R., Kumar V., Corke P. 2012 “Multirotor aerial vehicles: modeling, estimation, and control of quadrotor,” [IEEE Robotics & Automation Magazine] Vol.19 P.20-32 google cross ref
OAK XML 통계
이미지 / 테이블
  • [ Figure 1. ]  Physical model of a quadrotor.
    Physical model of a quadrotor.
  • [ ] 
  • [ ] 
  • [ ] 
  • [ ] 
  • [ ] 
  • [ Figure 2. ]  Quadcopter control diagram.
    Quadcopter control diagram.
  • [ ] 
  • [ ] 
  • [ Figure 3. ]  Comparison of feedforward architectures for altitude controller: (a) with constant feedforward compensator (A-type); (b) with proposed dynamic feedforward compensator (B-type); (c) with proposed fuzzy controller and dynamic feedforward compensator (C-type).
    Comparison of feedforward architectures for altitude controller: (a) with constant feedforward compensator (A-type); (b) with proposed dynamic feedforward compensator (B-type); (c) with proposed fuzzy controller and dynamic feedforward compensator (C-type).
  • [ Figure 4. ]  Effect of FF compensator: (a) feedforward term; (b) pitch and roll angles.
    Effect of FF compensator: (a) feedforward term; (b) pitch and roll angles.
  • [ ] 
  • [ Figure 5. ]  Membership functions for: (a) error, ez; (b) theta error θez, and (c) output u.
    Membership functions for: (a) error, ez; (b) theta error θez, and (c) output u.
  • [ ] 
  • [ Table 1. ]  Rule base
    Rule base
  • [ Figure 6. ]  Simulation results for A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers: (a) motion to a given point along the X-axis (point-to-point); (b) motion along the X-axis with constant speed; (c) motion along the X- and Y-axis with constant speed (line); (d) motion along a circular trajectory in the X-Y plane.
    Simulation results for A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers: (a) motion to a given point along the X-axis (point-to-point); (b) motion along the X-axis with constant speed; (c) motion along the X- and Y-axis with constant speed (line); (d) motion along a circular trajectory in the X-Y plane.
  • [ Table 2. ]  RMSE and maximum altitude drop (Emax) for a system with A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers
    RMSE and maximum altitude drop (Emax) for a system with A-type (constant compensation), B-type (dynamic compensation), and C-type (fuzzy with dynamic compensation) controllers
(우)06579 서울시 서초구 반포대로 201(반포동)
Tel. 02-537-6389 | Fax. 02-590-0571 | 문의 : oak2014@korea.kr
Copyright(c) National Library of Korea. All rights reserved.