=Paper=
{{Paper
|id=Vol-2744/short4
|storemode=property
|title=Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems (short paper)
|pdfUrl=https://ceur-ws.org/Vol-2744/short4.pdf
|volume=Vol-2744
|authors=Evgeny Strashnov,Mikhail Mikhaylyuk
}}
==Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems (short paper)==
Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems* Evgeny Strashnov1 [0000-0003-0937-4052], and Mikhail Mikhaylyuk2 [0000-0002-7793-080X] Federal State Institution «Scientific Research Institute for System Analysis of the Russian Academy of Sciences», Moscow, Russia 1 strashnov_evg@mail.ru, 2 mix@niisi.ras.ru Abstract. The paper considers the task of simulation quadcopter motion control in virtual environment systems. The proposed solution of this task is based on the application of a mathematical model of quadcopter dynamics, in which qua- ternion and axis-angle representation of the attitude are used. In this work, a feedback linearization method for the equations of quadcopter and its electric motors dynamics is proposed to control the quadcopter. With the application of this approach, quadcopter motion is achieved by the obtained expressions for linear acceleration and the desired quaternion. The proposed methods and ap- proaches for quadcopter simulation were implemented in the software package of virtual environment and tested using examples of the motion of a quadcopter model along a given path. Keywords: Quadcopter, Simulation, Quaternion, Axis-Angle Representation, Feedback Linearization Method, Virtual Environment System. 1 Introduction Quadcopter is a special case of an unmanned aerial vehicle with four rotors. Due to the relative simplicity of the construction, such devices are widely used in various fields where it is necessary to carry out aerial photography and video, aerial recon- naissance, cargo delivery, etc. The quadcopter control is performed by changing the rotation speed of the rotors, which allows to realize its vertical take-off, landing and maneuver in the horizontal plane. The current area of research is the use of virtual environment systems for quadcop- ter dynamics simulation and control. In this paper, we consider the task of virtual quadcopter model motion along a given arbitrary trajectory. The complexity of this Copyright © 2020 for this paper by its authors. Use permitted under Creative Commons Li- cense Attribution 4.0 International (CC BY 4.0). * The publication is made within the state task on carrying out basic scientific re- searches (GP 14) on topic (project) “34.9. Virtual environment systems: technolo- gies, methods and algorithms of mathematical modeling and visualization” (0065- 2019-0012). 2 E.Strashnov, M.Mikhaylyuk task consists in the fact that the quadcopter is an under-actuated mechanical system (the control number is less than the number of degrees of freedom). This leads to the fact that the translational and rotational motion of the quadcopter are interconnected. At the same time, for the implementation of complex motions (such as flips), it is necessary to provide arbitrary orientation of the quadcopter. In recent years several strategies, such as [1-5], based on Euler angles are used to control the rotational motion of the quadcopter. However, this approach leads to the fact that it is impossible to uniquely restore the Euler angles (so-called "gimbal lock" problem) for certain orientations of the quadcopter. Therefore, an alternative solution is that the quaternion can be used to the quadcopter dynamics and control [6-8]. In this work, quadcopter simulation is realized in the virtual environment system with using an approach in which the quaternion and axis-angle representation of the quadcopter attitude are used. The quadcopter control is performed by the feedback linearization method for the equations of quadcopter and its electric motor dynamics. Within this method, simulation of quadcopter motion along a given trajectory is per- formed by providing relationships in which linear acceleration is associated with the quaternion. Approbation of proposed solution was carried out in the virtual environ- ment software package using the example when quadcopter moving along a complex acrobatic figure. 2 Quadcopter Dynamics The quadcopter is an under-actuated system, since the number of actuators (four ro- tors) is less than the number of its degrees of freedom (six degrees of freedom for a rigid body). Figure 1 shows a model of a quadcopter with a structure of type “X”, according to the arrangement of the rotors. To describe the motion of the quadcopter, we introduce the following coordinate systems: the inertial frame EI , the body-fixed frame EB , and the desired frame ED . The quadcopter's position is defined with radius vector r = OO B = ( x, y, z ) , and the attitude is defined with unit quaternion T q = ( qw , qx , q y , qz ) , where q = qw2 + qx2 + q y2 + qz2 = 1 . T To obtain a linear model of quadcopter motion, consider the logarithmic mapping [6] of a quaternion q: qv arccos(qw ), q v 0; ln(q) = q v (1) 0, q = 0, v where q v = ( qx , q y , qz ) is the vector part of quaternion. T Then the vector α = 2ln(q) defines the rotation of the quadcopter around the unit axis α / α by an angle α . In this case, the kinematics of the quadcopter is defined using the linear equations r = v; α =ω, (2) Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems 3 where v = ( vx , v y , vz ) T denotes the quadcopter's linear velocity in the inertial frame EI , ω = ( x , y , z ) the quadcopter's angular velocity in the body-fixed frame EB . T Fig. 1. Virtual quadcopter model. Rotation of rotors create thrusts Ti = k i2 , i = 1, 4 , applied in the attachment points and are directed parallel to the axis OB Z B of the body-fixed frame EB , where i and k denotes, respectively, angular velocity of rotor i and the lift constant. Also, opposite the rotor rotation there are torques i = bi2 , where b denotes the drag constant of rotor. Hence, the four rotors create total thrust F = Ti and torque τ = ( x , y , z ) , T which are computed as F = k (12 + 22 + 32 + 42 ) ; x = kl y (12 + 22 − 32 − 24 ) ; y = klx (−12 + 22 + 32 − 42 ) ; z = b(−12 + 22 − 32 + 42 ) , (3) where lx and l y are the rotor coordinate's positions in the body-fixed frame EB . The mathematical model of quadcopter's motion is described as the Newton-Euler equations, which, taking into account the kinematic relations (2), become 0 0 mr = R(q) 0 + m 0 ; (4) F −g Iα = −ω Iω + τ , (5) where m is the quadcopter mass, I the inertia matrix in the body-fixed frame EB , R(q) the quaternion rotation matrix, g the gravity acceleration. 4 E.Strashnov, M.Mikhaylyuk Formulas (4) and (5) are supplemented by the rotor dynamics equations [5] based on their passport parameters: I m i = M S (U i − i ), i = 1, 4 , (6) idle where U i denotes the voltage supplied to armature of the motor, I m the motor iner- tia, M S the motor starting torque, idle the motor idling speed. Equations (4), (5) and (6) define a mathematical model of quadcopter and rotor dy- namics, where control variables F, x , y and z are given by formulas (3). 3 Quadcopter Control To control the quadcopter, we apply the feedback linearization method for equations (4) - (6). This method consists in the fact that the control variables are selected in a such way that the closed-loop system of quadcopter motion equations will be linear with given characteristics. The control task is to compute the thrust force F and tor- ques τ = ( x , y , z ) T in order to realize translational and rotational motion of the quadcopter. These control variables are used to solve the system of equations (3) with respect to i . The obtained solution is then used to calculate the voltages U i sup- plied to the rotor electric motors. 3.1 Attitude Control Here we will consider a more convenient and intuitive approach in which the de- sired attitude of the quadcopter is specified using Euler angles. Let the desired frame ED be obtained relative to the inertial frame EI by a sequence of rotations, where first performed around Z-axis on the jaw angle d , then around Y-axis on the roll angle d and finally around X-axis on the pitch angle d . With this sequence of rota- tions, the desired quaternion is derived through the Euler angles as follows [8]: cos( d / 2) cos( d / 2) cos( d / 2) + sin(d / 2) sin( d / 2) sin( d / 2) sin( / 2) cos( / 2) cos( / 2) − cos( / 2) sin( / 2) sin( / 2) qd = d d d d d d . (7) cos( d / 2) sin( d / 2) cos( d / 2) + sin(d / 2) cos( d / 2) sin( d / 2) cos( d / 2) cos( d / 2) sin( d / 2) − sin( d / 2) sin( d / 2) cos( d / 2) Then the desired attitude is defined using the vector α d = ln(qd ) , which is given by the formula (1). Let's transform equation (5) of quadcopter's rotation motion to the linear form. To do this, we select torque τ = ( x , y , z ) as T τ = ω Iω − K pr (α − α d ) − K vr (ω − ω d ) , (8) where K pr 0 and Kvr 0 are the diagonal matrices with positive linearization coef- Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems 5 ficients. The control law (8) leads to the fact that the system of equations (5) becomes linear and α(t ) tends to α d (t ) as t → . 3.2 Trajectory Control This task is to ensure the motion of the quadcopter along a given path rd (t ) . To solve this problem, we apply the feedback linearization method for equations (4) so that linear accelerations a = r = ( ax , a y , az ) satisfy the following equation T a = − K pt (r − rd ) − K vt (r − rd ) , (9) where K pt 0 and Kvt 0 are the diagonal matrices with positive linearization coef- ficients. Expression (9) is used to compute the thrust F and the desired angles d and d , which are involved in the implementation of the horizontal motion of the quadcopter. After substituting (9) into (4), we obtain that the thrust F is expressed through accel- erations a as F = m ax2 + a y2 + (az + g ) 2 . (10) In turn, the angles d and d are derived from (4) by expressing the matrix R in terms of Euler angles. Applying some transformations in (4), we can show [5] that the following relations are valid: a sin( ) − a cos( ) d = arcsin x d y d ; (11) a 2 + a 2 + (a + g ) 2 x y z a cos( ) + a sin( d ) d = arctan x d y . (12) a z + g Formulas (11) and (12) express the relationship of rotational and translational mo- tion of the quadcopter. The angles d and d are provided using the torque are given by the formula (8). Thus, when selecting the thrust F and angles d and d , we ob- tain accelerations (9) that make equations (4) linear such that r (t ) tends to rd (t ) as t →. 3.3 Actuator Control Solving the system of equations (3), we obtain the values i , d of rotor speeds. To ensure these speeds, we apply the feedback linearization method for equations (6). Selecting voltage U i in the following form ( (1 − tc km,i )i + tc km,i i ,d ) , 1 Ui = (13) idle 6 E.Strashnov, M.Mikhaylyuk we get that equations (6) become linear such that i tends to i , d as t → . When deriving (13), the relation I m = M s tc / idle was used, where tc is the motor time con- stant. Fig. 2. Structure of the quadcopter control scheme. 4 Simulation Results The quadcopter simulation was carried out in the virtual environment system, which was developed at the SRISA RAS. This software package includes parts for control, dynamics and visualization of virtual objects. The quadcopter control algorithm is defined by constructing a block diagram scheme. In the control subsystem, this scheme is computed and at the output of which we obtain new values of the voltages supplied to the rotor motors. These voltages are sent to the dynamics subsystem, which computes the new coordinates of the quadcopter and the sensors readings. The resulting coordinates are sent to the visualization subsystem that renders the virtual scene. The coefficients of the feedback linearization method used were the following: K pr ,i = 100 , K vr ,i = 20 , K pt ,i = 0.2 , K vt ,i = 0.75 , i = 1,3 . The quadcopter control scheme is conventionally shown in Figure 2. The scheme inputs are the desired path rd (t ) , the yaw angle d (t ) , as well as the virtual sensors readings (position, orienta- tion and angular velocities). According to this scheme, in order to implement the quadcopter trajectory control, linear accelerations are first computed by formula (9). These accelerations are used to compute the thrust F, the roll d and pitch d angles Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems 7 by formulas (10)-(12). The angles are sent to the block, which implements control of the quadcopter attitude with the computation of the output torque τ . The obtained thrust F and torque τ are used to compute the rotor speeds i , d and the voltages U i supplied to the quadcopter actuators. Fig. 3. Quadcopter motion around the robot. Two examples were considered for simulation of the quadcopter motion. In the first example (see Fig. 3), a task is realized in a virtual scene in which the quadcopter flies around an object (MF-4 robot) from different sides. The path rd (t ) of the quadcopter motion is defined as 2 t 2 t xd (t ) = Cx + R cos ; yd (t ) = C y + R sin ; zd (t ) = H = const , T T where t [0, T ] , Cx and C y are the object coordinates, H the flight altitude, T the total flight time. At the same time, the yaw angle changes according to the d (t ) = 2 t / T so that the virtual camera is directed towards the robot. Figure 3 shows the different positions of the quadcopter during its motion, where the position with number 1 corresponds to a point in time t = 0 , with number 2 corre- sponds to t = T / 6 , etc. In the second example (see Fig. 4), quadcopter performs a complex aerobatics fig- ure in the form of a closed loop (corkscrew loop). The quadcopter motion is per- formed in its longitudinal plane and includes two stages. At the first stage, the quad- copter is accelerated to the required velocity along the Y axis of its body-fixed frame. At the second stage, the quadcopter performs a total rotation around the pitch axis. To implement this motion, the desired pitch angle is defined as 8 E.Strashnov, M.Mikhaylyuk − / 9, 0 t T1 d (t ) = , 2 t / (T2 − T1 ), T1 t T2 where t [0, T2 ] , T1 is the time of acceleration, T2 the time of the flip. Fig. 4. Quadcopter motion along a complex path. Figure 4 shows the different positions of the quadcopter when performing a cork- screw loop. The numbers indicate the sequential positions of the quadcopter, where numbers 1 and 2 corresponds to the quadcopter positions during acceleration, and numbers from 3 to 8 corresponds to the positions when the quadcopter performs a flip. Note that the position with number 4 corresponds to the quadcopter rotation on the pitch angle about of 90 degrees around the X axis. With such a rotation, it is im- possible to uniquely restore the quadcopter attitude, if Euler angles are used. 5 Conclusion In this paper, methods and approaches for quadcopter dynamics simulation and con- trol in virtual environment systems were developed. The proposed solution is based on a mathematical model of the quadcopter's dynamics, in which the quaternion and the axis-angle representation are used to define the quadcopter attitude. Testing the examples of a virtual model showed that the proposed methods and approaches make it possible to realize the trajectory motion of a quadcopter with any angle of rotation. It is assumed that the obtained results can be used to control a real quadcopter model. For this in the future, it is planned to improve the developed methods and approaches for quadcopter simulation taking into account external disturbances, wind and noise in the virtual sensors readings. Simulation of Quadcopter's Complex Spatial Motion in Virtual Environment Systems 9 References 1. I.C. Dickmen, A. Arisoy, and H. Temeltas: Attitude control of quadrotor. In: 4th Interna- tional Conference on Recent Advances in Space Technologies, pp. 722-727 (2009). 2. Z. Zuo: Trajectory tracking control design with command-filtered compensation for a quadrotor. IET Control Theory Appl., 4(11), 2343-2355 (2010). 3. T. Luukkonen: Modeling and control of quadcopter. Independent research project in ap- plied mathematics, Espoo: Aalto University (2011). 4. F. Sabatino: Quadrotor control: modeling, nonlinear control design and simulation. Mas- ter's Degree Project, Stockholm, Sweden (2015). 5. M.V. Mikhaylyuk, and E.V. Strashnov: Simulation of quadcopter motion control in virtual environment systems. Mathematica Montisnigri, XLIV, 60-72 (2019). 6. J. Carino, H. Abaunza, and P. Castillo: Quadrotor quaternion control. In: International Conference on Unmanned Aircraft Systems (ICUAS), Denver, USA (2015). 7. A. Chovancova, T. Fico, P. Hubinsky, and F. Duchon: Comprasion of various quaternion based control methods applied to quadrotor with disturbance observer and position estima- tor. In: Robotics and Autonomous Systems (2016). 8. E. Fresk, and G. Nikolakopoulos: Full quaternion based attitude control for a quadrotor, In: Proc. ECC, Zurich, CH, pp. 3864-3869 (2013).