arXiv:1307.0276v3 [cs.SY] 2 Mar 2014 1 Controllability Analysis and Degraded Control for a Class of Hexacopters Subject to Rotor Failures Guang-Xun Du, Quan Quan, Kai-Yuan Cai Abstract This paper considers the controllability analysis and fault tolerant control problem for a class of hexacopters. It is shown that the considered hexacopter is uncontrollable when one rotor fails, even though the hexacopter is over-actuated and its controllability matrix is row full rank. According to this, a fault tolerant control strategy is proposed to control a degraded system, where the yaw states of the considered hexacopter are ignored. Theoretical analysis indicates that the degraded system is controllable if and only if the maximum lift of each rotor is greater than a certain value. The simulation and experiment results on a prototype hexacopter show the feasibility of our controllability analysis and degraded control strategy. Index Terms Hexacopter, fault tolerant control, controllability, degraded control strategy, safe landing. The authors are with Department of Automatic Control, Beihang University, Beijing 100191, China (dgx@asee.buaa.edu.cn; qq buaa@buaa.edu.cn; kycai@buaa.edu.cn) October 29, 2018 DRAFT 2 N OMENCLATURE h = altitude of the multirotor helicopter, m φ, θ, ψ = roll, pitch and yaw angles of the multirotor helicopter, rad v h = vertical velocity of the multirotor helicopter, m/s p, q, r = roll, pitch and yaw angular velocities of the multirotor helicopter, rad/s T = total thrust of the multirotor helicopter, N L, M, N = airframe roll, pitch and yaw torque of the multirotor helicopter, N · m m a = mass of the multirotor helicopter, kg g = acceleration of gravity, kg · m/s 2 J x , J y , J z = moment of inertia around the roll, pitch and yaw axes of the multirotor helicopter frame, kg · m 2 f i = lift of the i -th rotor, N K = maximum lift of each rotor, N η i = efficiency parameter of the i -th rotor d = distance from the center of the rotor to the center of mass k μ = ratio between the reactive torque and the lift of the rotors I. I NTRODUCTION Multirotor helicopters are attracting increasing attention in recent years because of their important contribution and cost effective application in several tasks such as surveillance, search and rescue missions and so on. However, there exists a potential risk to civil safety if the helicopters crash especially in an urban area. Therefore, it is of great importance to consider the flight safety of multirotor helicopters in the presence of rotor faults or failures. Over-actuated aircraft have the potential to improve safety and reliability. Fault tolerant control of over-actuated aircraft subject to actuator failures is discussed widely [1][2][3]. Most works on fault tolerant control implicitly assume that the control systems are still controllable in the event of failures. However, few works consider the controllability of the systems with faults. If the system is October 29, 2018 DRAFT 3 uncontrollable, any fault tolerant control strategy will be unavailable. In [4], Schneider et al . proposed a useful method to study the controllability of multirotor systems with rotor failures based on the construction of the attainable control set. However, they did not give theoretical analysis of the controllability of the multirotor systems. This is one of our motivations. Sometimes, a hexacopter is uncontrollable if one rotor fails. Owing to this, the hexacopter subject to rotor failures is often controlled by leaving the yaw states uncontrolled, the feasibility of which has been tested by [4][5]. This is very useful in emergency situations. However, we find that not all the uncontrollable hexacopters can be controlled by the degraded way mentioned in [4][5]. If the maximum lift of each rotor is lower than a certain value then the degraded system, where the yaw states of the considered hexacopter are ignored, is still uncontrollable. Our another motivation is to specify this lower bound value. In this paper, the controllability of a class of hexacopters subject to one rotor failure is analyzed based on the positive controllability theory in [6], and the results show that the hexacopter is uncontrollable. In order to land the hexacopter safely, a Degraded Control Strategy (DCS) is proposed for the degraded system. The lower bound of the maximum lift of each rotor is specified, which can help the designers in choosing the proper rotors for improving the fault-tolerant capability of the hexacopter. The major contributions of this paper are: (i) a theoretical controllability analysis for a class of hexacopters, and (ii) the specification of the lower bound of the maximum rotor lift. II. P ROBLEM F ORMULATION A. Hexacopter Model This paper considers a class of PNPNPN hexacopters shown in Fig.1. The linear dynamical model around hover conditions is given as follows [7][8]: ̇ x = Ax + B ( F − G ) ︸ ︷︷ ︸ u (1) October 29, 2018 DRAFT 4 1 e 2 e 3 e 1 f 4 f 2 f Yaw Roll T I \ 5 f 6 f 3 f y e z e b O I O Roll Pitch x e d Fig. 1. Kinematic scheme of a PNPNPN hexacopter, where P denotes that a rotor rotates clockwise and N denotes that a rotor rotates anticlockwise where x = [ h φ θ ψ v h p q r ] T ∈ R 8 , F = [ T L M N ] T ∈ R 4 , G = [ m a g 0 0 0] T ∈ R 4 , A =     0 4 × 4 I 4 0 0     ∈ R 8 × 8 , B =     0 J − 1 f     ∈ R 8 × 4 , J f = diag ( − m a , J x , J y , J z ) and u = F − G ∈ U ⊂ R 4 . (2) According to the geometry of the hexacopter shown in Fig.1, the mapping from the rotor lift f i , i = 1 , · · · , 6 to the system total thrust/torque F is [4][7]: F = H η 1 , ··· ,η 6 f (3) where f = [ f 1 · · · f 6 ] T ∈ R 6 and the control effectiveness matrix H η 1 , ··· ,η 6 ∈ R 4 × 6 in parameterized October 29, 2018 DRAFT 5 form is H η 1 , ··· ,η 6 =             η 1 η 2 η 3 η 4 η 5 η 6 0 − √ 3 2 η 2 d − √ 3 2 η 3 d 0 √ 3 2 η 5 d √ 3 2 η 6 d η 1 d 1 2 η 2 d − 1 2 η 3 d − η 4 d − 1 2 η 5 d 1 2 η 6 d − η 1 k μ η 2 k μ − η 3 k μ η 4 k μ − η 5 k μ η 6 k μ             . (4) The parameter η i ∈ [0 , 1] , i = 1 , · · · , 6 is used to account for rotor wear/failure. If the i -th rotor fails, then η i = 0 . Since the rotors of the hexacopter can only provide upward lifts, we let f i ∈ [0 , K ] , i = 1 , · · · , 6 . As a result, we have f ∈ F = Π 6 i =1 [0 , K ] . (5) B. Control Constraint In this section, we will specify the control constraint U . Combining (2), (3) and (5), we can get the control constraint U 0 η 1 , ··· ,η 6 = { u | u = H η 1 , ··· ,η 6 f − G, f ∈ F} . (6) Next, we consider the control constraint U under a control allocation. In practice, the virtual control F is often designed first. Then, the control allocation is used to obtain f as f = P η 1 , ··· ,η 6 F (7) where P η 1 , ··· ,η 6 ∈ R 6 × 4 is the allocation matrix satisfying H η 1 , ··· ,η 6 P η 1 , ··· ,η 6 = I 4 . (8) Since F = u + G from (2), we can get the control constraint U under the control allocation (7) as U a η 1 , ··· ,η 6 = { u | P η 1 , ··· ,η 6 ( u + G ) ∈ F} . (9) The pseudo-inverse matrix (PIM) method [8][9] is often used to choose P η 1 , ··· ,η 6 as follows P η 1 , ··· ,η 6 = H † η 1 , ··· ,η 6 = H T η 1 , ··· ,η 6 ( H η 1 , ··· ,η 6 H T η 1 , ··· ,η 6 ) − 1 . (10) The relation between U a η 1 , ··· ,η 6 and U 0 η 1 , ··· ,η 6 is stated as Theorem 1 , which is consistent with the results in [8] and [10]. October 29, 2018 DRAFT 6 Theorem 1 . U a η 1 , ··· ,η 6 ⊆ U 0 η 1 , ··· ,η 6 . Proof . For any u ∗ ∈ U a η 1 , ··· ,η 6 , there exists a f ∗ ∈ F such that f ∗ = P η 1 , ··· ,η 6 ( u ∗ + G ) . By (8), we have H η 1 , ··· ,η 6 f ∗ − G = H η 1 , ··· ,η 6 P η 1 , ··· ,η 6 ( u ∗ + G ) − G = u ∗ . This implies u ∗ ∈ U 0 η 1 , ··· ,η 6 , namely U a η 1 , ··· ,η 6 ⊆ U 0 η 1 , ··· ,η 6 .  C. Objective The first objective is to show that the system (1) will lose controllability 1 when one rotor fails. That is, the system (1) is uncontrollable subject to the control constraint U = U 0 η i =0 where, for simplicity, the subscript η i = 0 is used to denote that only the i -th rotor fails and the remaining rotors have neither wear nor failures. The second objective is to study the controllability of the degraded system, where the yaw states are removed from (1), and specify the lower bound of the maximum lift of each rotor. Remark 1. Not all the hexacopters are configured as Fig.1. For example, a class of PPNNPN hexacopters are considered in [4]. It is pointed out that other type of hexacopters can be analyzed in the same way as the popular PNPNPN hexacopter. Remark 2 . Classical controllability theories of linear systems often require the origin to be an interior point of U so that C ( A, B ) being row full rank is a necessary and sufficient condition [6]. However, for the system (1) the control constraint U = U 0 η i =0 does not have the origin as its interior point when some rotors are damaged or fail. Consequently, C ( A, B ) being row full rank is not sufficient to test the controllability of the system (1). 1 The system (1) with constraint set U ⊂ R 4 is called controllable if, for each pair of points x 0 ∈ R 8 and x 1 ∈ R 8 , there exists a bounded admissible control, u ( t ) ∈ U , defined on some finite interval 0 ≤ t ≤ t 1 , which steers x 0 to x 1 . Specifically, the solution to (1), x ( t, u ( · )) , satisfies the boundary conditions x (0 , u ( · )) = x 0 and x ( t 1 , u ( · )) = x 1 . October 29, 2018 DRAFT 7 III. C ONTROLLABILITY OF THE H EXACOPTER S UBJECT TO O NE R OTOR F AILURE A. Preliminaries In this section, we will study the controllability of the hexacopter subject to one rotor failure based on the positive controllability theory proposed in [6]. Applying the positive controllability theorem in [6] to the system (1) directly, we have Theorem 2 . Consider the system (1), suppose that the set U contains a vector in the kernel of B (i.e., there exists u ∈ U satisfying Bu = 0 ) and the set CH ( U ) 2 has nonempty interior in R 4 . Then, the following conditions are necessary and sufficient for the controllability of (1): (c1) Rank C ( A, B ) = 8 , where C ( A, B ) = [ B AB · · · A 7 B ] . (c2) There is no non-zero real eigenvector v of A T satisfying v T Bu ≤ 0 for all u ∈ U . For the considered linear hexacopter model (1), Theorem 2 is simplified as follows. Corollary 1 . The system (1) is controllable if and only if min v ∈V max u ∈U v T Bu > 0 (11) where V = { v | A T v = 0 , ‖ v ‖ = 1 , v ∈ R 8 } . Proof: The proof is straightforward. For the system (1), it is easy to check that rank C ( A, B ) = 8 . According to Theorem 2 , then the system (1) is controllable if and only if there is no non-zero real eigenvector v of A T satisfying v T Bu ≤ 0 for all u ∈ U . Since all the eigenvalues of A T are zero, all the real eigenvectors of A T can be obtained by solving linear equations A T v = 0 . Then the system (1) is controllable if and only if (11) is satisfied. The constraint ‖ v ‖ = 1 is used to make (11) verifiable, which does not change the sign of v T Bu .  B. Controllability Analysis of the Hexacopter Subject to One Rotor Failure For the controllability of the hexacopter subject to one rotor failure, we have the following theorem: 2 CH ( U ) is the convex hull of U . According to [11], the convex hull of ∆ is the set of all convex combinations of points in ∆ . If ∆ is convex, then CH (∆) = ∆ . October 29, 2018 DRAFT 8 Theorem 3. The system (1) constrained by U = U 0 η i =0 , ∀ i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is uncontrollable. Proof: This proof is accomplished by counterexamples. For each η i = 0 , we find a vector ˆ v i ∈ V satisfying max u ∈U 0 ηi =0 ˆ v T i Bu = 0 (12) Then min v ∈V max u ∈U v T Bu ≤ 0 . Consequently, the system (1) constrained by U = U 0 η i =0 , ∀ i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is uncontrollable ac- cording to to Corollary 1 . See Appendix A for details.  As analyzed above, the PNPNPN hexacopter subject to one rotor failure is uncontrollable. A question follows consequentially: how a hexacopter can land safely after one rotor fails. In [4][5], the author suggested a degraded control way that was to leave the yaw states uncontrolled. However, neither a controllability analysis nor a concrete DCS exists. IV. D EGRADED C ONTROL AND A NALYSIS FOR S AFE L ANDING W ITHOUT Y AW According to Section III, the yaw states of the hexacopter may be left uncontrolled for safe landing when one rotor fails. In this section, a DCS for the case with one of η i , i = 1 , · · · , 6 being zero is approached, which does not require any change on the original controller. Furthermore, it is shown that the hexacopter subject to one rotor failure can land by the DCS if and only if the maximum lift of each rotor is greater than a certain value. This lower bound value will be specified in this section. A. DCS for Safe Landing Without Yaw Control In practice, the virtual control F is often designed first. Then if no rotor fails, f is obtained by f = P F where F = [ T L M N ] T and P is expressed by (10). If one of η i , i = 1 , · · · , 6 is zero, the DCS for the system (1) includes the following two steps: Step 1: Leave the yaw states uncontrolled. One simple way is to let ( ψ s , r s ) = ( ψ c , r c ) , where ( ψ s , r s ) are the sensed yaw states and ( ψ c , r c ) the commanded yaw states. October 29, 2018 DRAFT 9 Step 2: Reallocate ̄ F to the set of rotor lifts f by f = ̄ P ̄ F , (13) ̄ P η 1 , ··· ,η 6 = ̄ H T η 1 , ··· ,η 6 ( ̄ H η 1 , ··· ,η 6 ̄ H T η 1 , ··· ,η 6 ) − 1 (14) where ̄ F = [ T L M ] T and ̄ H η 1 , ··· ,η 6 =         η 1 η 2 η 3 η 4 η 5 η 6 0 − √ 3 2 η 2 d − √ 3 2 η 3 d 0 √ 3 2 η 5 d √ 3 2 η 6 d η 1 d 1 2 η 2 d − 1 2 η 3 d − η 4 d − 1 2 η 5 d 1 2 η 6 d         . (15) However, there is no theoretical analysis of the DCS in the existing literatures according to our knowledge. In the following section, the lower bound of the maximum lift of each rotor is specified through controllability analysis. B. Controllability Analysis of the Hexacopter Removing the Yaw States The degraded system that the yaw states are removed from (1) is given as ̇ x ∗ = ̄ Ax ∗ + ̄ B ( ̄ F − ̄ G ) ︸ ︷︷ ︸ ̄ u (16) where x ∗ = [ h φ θ v h p q ] T ∈ R 6 , ̄ F = [ T L M ] T ∈ R 3 , ̄ G = [ m a g 0 0 ] T ∈ R 3 , ̄ A =     0 3 × 3 I 3 0 0     ∈ R 6 × 6 , ̄ B =     0 ̄ J − 1 f     ∈ R 6 × 3 , ̄ J f = diag ( − m a , J x , J y ) and ̄ u = ̄ F − ̄ G ∈ ̄ U ⊂ R 3 . Similar to the system (1), the control constraint ̄ U is ̄ U 0 η 1 , ··· ,η 6 = { ̄ u | ̄ u = ̄ H η 1 , ··· ,η 6 f − ̄ G, f ∈ F } . (17) and the control constraint ̄ U under the control allocation (14) is ̄ U a η 1 , ··· ,η 6 = { ̄ u | ̄ P η 1 , ··· ,η 6 ( ̄ u + ̄ G ) ∈ F } . (18) October 29, 2018 DRAFT 10 Similar to Theorem 1 , we have ̄ U a η 1 , ··· ,η 6 ⊆ ̄ U 0 η 1 , ··· ,η 6 . Similarly to Corollary 1 , the following theorem is obtained: Theorem 4. The system (16) constrained by ̄ U is controllable if and only if min v ∈ ̄ V max ̄ u ∈ ̄ U ̄ v T ̄ B ̄ u > 0 (19) where ̄ V = { v | ̄ A T v = 0 , ‖ v ‖ = 1 , v ∈ R 6 } . Proof: This proof is similar to the proof of Corollary 1 . See Appendix B for details.  Theorem 5 . The system (16) constrained by ̄ U = ̄ U a η i =0 , ∀ i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is controllable if and only if K > 5 18 m a g. (20) Furthermore, the system (16) constrained by ̄ U = ̄ U 0 η i =0 , ∀ i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is controllable if (20) holds. Proof: Under ̄ U = ̄ U a η 2 =0 we first prove that the following two propositions hold (see Appendix C). Proposition 1: there is a ̄ v 2 ∈ ̄ V satisfying max u ∈U 0 η 2=0 ̄ v T 2 ̄ B ̄ u ≤ 0 (21) if K ≤ 5 18 m a g . Proposition 2: there is no such a ̄ v 2 ∈ ̄ V satisfying (21) if K > 5 18 m a g . With Proposition 1 and Proposition 2 , the system (16) constrained by ̄ U = ̄ U a η 2 =0 is controllable if and only if (20) holds according to Theorem 4 . If (20) holds, then for each pair of points ̄ x 0 ∈ R 6 and ̄ x 1 ∈ R 6 there exists a ̄ u ∗ ( t ) ∈ ̄ U a η 2 =0 , which steers x 0 to x 1 . Since ̄ U a η 2 =0 ⊆ ̄ U 0 η 2 =0 , ̄ u ∗ ( t ) ∈ ̄ U 0 η 2 =0 , namely the system (16) constrained by ̄ U = ̄ U 0 η 2 =0 is controllable. Similarly, we can conclude this proof for ̄ U = ̄ U a η i =0 , ∀ i ∈ { 1 , 3 , 4 , 5 , 6 } .  Remark 3. According to Theorem 5 , the designers should choose proper rotors satisfying K > 5 18 m a g so as to make sure that the hexacopter can adopt the DCS proposed in this paper. October 29, 2018 DRAFT 11 Fig. 2. A prototype hexacopter V. S IMULATION AND E XPERIMENT In order to show the feasibility of the proposed DCS, simulations and an experiment of a prototype hexacopter (see Fig.2) are carried out. The physical parameters of the prototype hexacopter are shown in Table I. In the simulation, the hexacopter is controlled by Proportional-Derivative (PD) controllers and the proposed DCS for safe landing is applied. After η 2 = 0 , the hexacopter keeps its ( h, φ, θ ) to the desired targets by leaving the yaw states uncontrolled. In the experiment, a real flight test for the prototype hexacopter was carried out. During the real flight test, η 2 was set to zero. Then the DCS for safe landing kept the hexacopter level and the hexacopter was landed by the remote-controller avoiding loss of control. A. Simulation Results Based on the parameters in Table I, a digital simulation is performed. The hexacopter hovers at h c = 1 m and [ φ c θ c ψ c ] T = [0 0 5] T rad controlled by Proportional-Derivative (PD) controllers which are expressed by L = 20 ( φ − φ c ) + 3 p, M = 20 ( θ − θ c ) + 3 q, N = 20 ( ψ − ψ c ) + 3 r, T = 10 ( h − h c ) + 6 v h + m a g. (22) If no rotor fails, f is obtained by f = H T η 1 , ··· ,η 6 ( H η 1 , ··· ,η 6 H T η 1 , ··· ,η 6 ) − 1 F (23) October 29, 2018 DRAFT 12 TABLE I HEXACOPTER PARAMETERS Parameter Description Value Units m Mass 1.535 kg g Gravity 9.80 m/ s 2 d Rotor to mass center distance 0.275 m K Maximum lift of each rotor 6.125 N J x Moment of inertia 0.0411 kg.m 2 J y Moment of inertia 0.0478 kg.m 2 J z Moment of inertia 0.0599 kg.m 2 k μ k/μ 0.1 - where F = [ T L M N ] T . And if one of η i , i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is zero, f is obtained by f = ̄ H T η i =0 ( ̄ H η i =0 ̄ H T η i =0 ) − 1 ̄ F (24) where ̄ F = [ T L M ] T . Fig.3 shows the simulation results when no rotor fails, where h, φ, θ , and ψ are controlled to the desired target with nice performance. At time instant t = 1 s , η 2 is set to 0 . Fig.4 shows the simulation results when η 2 = 0 and the DCS is not adopted. It is shown that h, φ, θ , and ψ diverge from their targets. With the DCS, h, φ , and θ are controlled to the desired targets with nice performance (see Fig.5) which avoids loss of control. According to Theorem 5 , not all the uncontrollable hexacopters can land in the degraded way proposed in this paper. It should be pointed out that if K ≤ 5 18 m a g , then h, φ , and θ are not controllable and the hexacopter will crash to the land if one rotor fails. In the simulation, we change the value of K to 4 . 9 18 m a g and the simulation results of h, φ, θ are shown in Fig.6 where the DCS is adopted. Obviously, the hexacopter is out of control. Remark 4 . In Fig.5, the yaw angle changes with a constant angular velocity at last. When the hexacopter rotates fast, the damping moment N D = K N D r 2 can not be ignored, where K N D is October 29, 2018 DRAFT 13 0 1 2 3 4 5 6 7 8 9 10 −1 0 1 2 m h 0 1 2 3 4 5 6 7 8 9 10 −0.05 0 0.05 rad Roll 0 1 2 3 4 5 6 7 8 9 10 −0.05 0 0.05 rad Pitch 0 1 2 3 4 5 6 7 8 9 10 5 5.2 5.4 5.6 rad Yaw time/s Fig. 3. No rotor fails and h, φ, θ, ψ are controlled to the desired target the damping coefficient. In the simulation we choose K N D = 0 . 2 N · m/rad 2 to make the simulation results be consistent with the experiment results. Parameters η i , i = 1 , · · · , 6 , which in practice can be obtained by fault diagnosis strategies [12][13], are assumed to be known. Since the effect of fault diagnosis strategies are not in the scope of this paper, they will not be discussed here and will be invertigated in our future researches. B. Experimental Results In order to show the feasibility of the proposed DCS, a real flight test of the prototype hexacopter shown in Fig.2 was carried out. During the flight, [ φ c θ c ψ c ] T = [0 0 5] T rad and h was controlled by a remote-controller. Part of the flight data is shown in Fig.7. The hexacopter was in a stabilize mode (where φ, θ, ψ were controlled by Proportional-Integral-Derivative controllers and h was controlled October 29, 2018 DRAFT 14 0 1 2 3 4 5 6 7 8 9 10 −0.5 0 0.5 1 m h 0 1 2 3 4 5 6 7 8 9 10 0 0.5 1 1.5 rad Roll 0 1 2 3 4 5 6 7 8 9 10 −1 −0.5 0 0.5 rad Pitch 0 1 2 3 4 5 6 7 8 9 10 3 4 5 6 rad Yaw time/s Fig. 4. The DCS is not adopted after η 2 = 0 and h, φ, θ, ψ diverge from their target by a remote-controller) before time t = 1 s . At time instant t = 1 s , η 2 was set to 0 , then the controller kept φ, θ around zero by the DCS. And the hexacopter was landed slowly by the remote-controller avoiding a flight crash. Remark 5 . According to Fig.7, the hexacopter rotates fast (nearly 2 π rad/s) after η 2 = 0 . But the h can be controlled by the remote-controller to achieve a safe landing. The video of the experiment is online [14]. VI. C ONCLUSIONS In this paper, the controllability and fault tolerant control problem of a class of hexacopters are investigated. The following two conclusions are obtained: i) although the considered hexacopter is over-actuated and its controllability matrix is row full rank, it is uncontrollable when one rotor fails, October 29, 2018 DRAFT 15 0 1 2 3 4 5 6 7 8 9 10 −1 0 1 2 m h 0 1 2 3 4 5 6 7 8 9 10 −0.05 0 0.05 rad Roll 0 1 2 3 4 5 6 7 8 9 10 −0.05 0 0.05 rad Pitch 0 1 2 3 4 5 6 7 8 9 10 0 5 10 rad Yaw time/s Fig. 5. The DCS is adopted after η 2 = 0 and h, φ, θ, ψ are controlled to the desired target with nice performance and ii) the uncontrollable hexacopter can land in a degraded way by the proposed Degraded Control Strategy (DCS) under the condition that the maximum lift of each rotor is greater than 5 18 of the hexacopter’s gravity. The simulation and experiment results on a prototype hexacopter show the feasibility of the proposed DCS. The focus of our future work is to extend the controllability theory in this paper to analyze the controllability of general multirotor helicopters. VII. A PPENDIX A. Proof of Theorem 3 This proof is accomplished by counterexamples. October 29, 2018 DRAFT 16 0 1 2 3 4 5 6 7 8 9 10 −1 0 1 2 m h 0 1 2 3 4 5 6 7 8 9 10 0 0.02 0.04 0.06 rad Roll 0 1 2 3 4 5 6 7 8 9 10 −0.05 0 0.05 rad Pitch 0 1 2 3 4 5 6 7 8 9 10 0 5 10 rad Yaw time/s Fig. 6. K = 4 . 9 18 m a g and the hexacopter is out of control even though the DCS is adopted (i) Case η 2 = 0 . The control effectiveness matrix H η 2 =0 is expressed by H η 2 =0 =             1 0 1 1 1 1 0 0 − √ 3 2 d 0 √ 3 2 d √ 3 2 d d 0 − 1 2 d − d − 1 2 d 1 2 d − k μ 0 − k μ k μ − k μ k μ             . (25) By solving H η 2 =0 f = F based on the theory of linear algebra [15], U 0 η 2 =0 = { u | u = [ T − m a g L M N ] T } October 29, 2018 DRAFT 17 0 2 4 6 8 10 12 14 16 −1 −0.5 0 0.5 Roll/rad Real−time flight data 0 2 4 6 8 10 12 14 16 −0.2 0 0.2 0.4 0.6 Pitch/rad 0 2 4 6 8 10 12 14 16 0 2 4 6 8 Yaw/rad time/s Fig. 7. Real-time flight test for a prototype hexacopter is given by the following inequalities 0 ≤ 1 2 T + 2 3 d M + 1 6 k μ N − α ≤ K (26a) 0 ≤ − √ 3 3 d L − 1 3 d M − 1 3 k μ N + α ≤ K (26b) 0 ≤ 1 2 T + 1 2 d N − α ≤ K (26c) 0 ≤ √ 3 3 d L − 1 3 d M − 1 3 k μ N ≤ K (26d) 0 ≤ α ≤ K. (26e) Let v 2 = [ 0 0 0 0 0 − √ 3 J x 3 d J y 3 d J z 3 k μ ] T and ˆ v 2 = v 2 ‖ v 2 ‖ , we have ˆ v 2 ∈ V and ˆ v T 2 Bu = − √ 3 3 d L + 1 3 d M + 1 3 k μ N ‖ v 2 ‖ . October 29, 2018 DRAFT 18 According to (26d), max u ∈U 0 η 2=0 ˆ v T 2 Bu = 0 . (ii) Case η i = 0 . Similar to the case η 2 = 0 , we can find a ˆ v i ∈ V satisfying max u ∈U 0 ηi =0 ˆ v T i Bu = 0 , i ∈ { 1 , 3 , 4 , 5 , 6 } . From (i) and (ii), we have min v ∈V max u ∈U v T Bu ≤ 0 and the system (1) constrained by U = U 0 η i =0 , ∀ i ∈ { 1 , 2 , 3 , 4 , 5 , 6 } is uncontrollable according to Corollary 1 . B. Proof of Theorem 4 We apply the positive controllability theorem in [6] to the system (16) directly. Suppose that the set ̄ U contains a vector in the kernel of ̄ B and the set CH ( ̄ U ) has nonempty interior in R 3 , the following conditions are necessary and sufficient for the controllability of (16): (i) Rank C ( ̄ A, ̄ B ) = 6 , where C ( ̄ A, ̄ B ) = [ ̄ B ̄ A ̄ B · · · ̄ A 5 ̄ B ] . (ii) There is no non-zero real eigenvector v of ̄ A T satisfying v T ̄ B ̄ u ≤ 0 for all ̄ u ∈ ̄ U . For the system (16), it is easy to check that rank C ( ̄ A, ̄ B ) = 6 . Since all the eigenvalues of ̄ A T are zero, all the real eigenvectors of ̄ A T can be obtained by solving linear equations ̄ A T v = 0 . Then the system (16) is controllable if and only if (19) is true.  C. Proof of Theorem 5 1) Proof of Proposition 1: According to (14) and (15), ̄ P η 2 =0 = ̄ H T η 2 =0 ( ̄ H η 2 =0 ̄ H T η 2 =0 ) − 1 . Then ̄ U a η 2 =0 = { ̄ u | ̄ u = [ T − m a g L M ] T } is given by the following inequalities according to (18) October 29, 2018 DRAFT 19 − 5 18 T ≤ − √ 3 9 d L + 4 9 d M ≤ K − 5 18 T, − 5 18 T ≤ − 5 √ 3 18 d L − 1 18 d M ≤ K − 5 18 T, − 1 6 T ≤ − 1 3 d M ≤ K − 1 6 T, − 1 9 T ≤ 2 √ 3 9 d L − 2 9 d M ≤ K − 1 9 T, − 1 6 T ≤ √ 3 6 d L + 1 6 d M ≤ K − 1 6 T. (27) Denote E c = { c | c = ( L, M ) T , L, M satisfy (27) } which is closed and convex. If T ≥ 18 5 K , c 0 = [0 0] T is not an interior point of E c . Then there is a non-zero vector c k = [ k c 1 k c 2 ] T satisfying c T k ( c − c 0 ) = k c 1 L + k c 2 M ≤ 0 (28) for all c = ( L, M ) T ∈ E c according to [16]. Let v 2 = [ 0 0 0 0 k c 1 J x k c 2 J y ] T and ̄ v 2 = v 2 ‖ v 2 ‖ , we have ̄ A T ̄ v 2 = 0 and ̄ v T 2 ̄ B ̄ u = k c 1 L + k c 2 M ‖ v 2 ‖ . According to (28), max u ∈U 0 η 2=0 ̄ v T 2 ̄ B ̄ u = 0 . Thus, the system (16) is uncontrollable if T ≥ 18 5 K according to Theorem 4 . Under hovering conditions, we have T = m a g . Thus, Proposition 1 is true. 2) Proof of Proposition 2: According to the proof of Proposition 1 , If T < 18 5 K , then c 0 = [ 0 0 ] T is an interior point of E c . According to [16], we cannot find a non-zero vector c k = [ k c 1 k c 2 ] T satisfying c T k c ≤ 0 for all c ∈ E c . We will prove this by the proof of contradiction. Suppose that there is a non-zero vector ̄ v 2 = [ 0 0 0 0 ̄ k 1 ̄ k 2 ] T satisfying max u ∈U 0 η 2=0 ̄ v T 2 ̄ B ̄ u = 0 then we have ̄ v T 2 ̄ B ̄ δ = ̄ k 1 L/J x + ̄ k 2 M/J y ≤ 0 . October 29, 2018 DRAFT 20 Let c k = [ k c 1 k c 2 ] T = [ ̄ k 1 /J x ̄ k 2 /J y ] T . Then we get c T k c = ̄ k 1 L/J x + ̄ k 2 M/J y ≤ 0 and this contradicts with the fact that there is no non-zero vector c k satisfying c T k c ≤ 0 for all c ∈ E c . Thus, the system (16) is controllable if T < 18 5 K according to Theorem 4 . Under hovering conditions, we have T = m a g . Thus, Proposition 2 holds. R EFERENCES [1] Zhang, Y., and Jiang, J.: ‘Bibliographical review on reconfigurable fault-tolerant control systems’, IFAC Annual Reviews in Control , 2008, 32, (2), pp. 327-338. [2] Balint, A.: ‘Advances in flight control systems’ (InTech, 2011) [3] Ducard, G.: ‘Fault-tolerant flight control and guidance systems: practical methods for small unmanned aerial vehicles’ (Springer-Verlag, 2009) [4] Schneider, T., Ducard, G., Rudin, K., Strupler, P.: ‘Fault-tolerant control allocation for multirotor helicopters using parametric programming’. International Micro Air Vehicle Confrence and Flight Competition , Braunschweig, Germany, July 2012. [5] http://new.ted.com/talks/raffaello d andrea the astounding athletic power of quadcopters [6] Brammer, R. F.: ‘Controllability in linear autonomous systems with positive controllers’, SIAM Journal on Control , 1972, 10, (2), pp. 779-805. [7] Du, G.-X., Quan, Q., Cai, K.-Y.: ‘Additive-State-Decomposition-Based Dynamic Inversion Stabilized Control of A Hexacopter Subject to Unknown Propeller Damages’. In Proceedings of the 32nd Chinese Control Conference , Xi’an, China, July 2013. [8] Ducard, G. and Hua, M-D: ‘Discussion and Practical Aspects on Control Allocation for a Multi-rotor Helicopter’. In Proceedings of the 1st International Conference on UAVs in Geomatics, UAV-g 2011 , Zurich, Switzerland, September 2011. [9] Oppenheimer, M., Doman, D., and Bolender, M.: ‘Control allocation for over-actuated systems’. In 14th Mediterranean Conference on Control and Automation , Ancona, Italy, June 2006. [10] Demenkov, M.: ‘Geometric algorithms for input constrained systems with application to flight control’, Dissertation, De Montfort University, Leicester, UK, 2007. [11] Boyd, S. and Vandenberghe, L.: ‘Convex Optimization’ (Cambridge University Press, 2004) [12] Zhang, Y., Chamseddine, A., Rabbath, C., Gordon, B., Su, C.-Y., Rakheja, S., Fulford, C., Apkarian, J., and Gosselin, P.: ‘Development of Advanced FDD and FTC Techniques with Application to an Unmanned Quadrotor Helicopter Testbed’, Journal of the Franklin Institute , 2013, 350, (9), pp. 2396-2422. October 29, 2018 DRAFT 21 [13] Amoozgar, M., Chamseddine, A., and Zhang, Y.: ‘Experimental Test of a Two-Stage Kalman Filter for Actuator Fault Detection and Diagnosis of an Unmanned Quadrotor Helicopter’, Journal of Intelligent and Robotic Systems , 2013, 70, (1), pp. 107-117. [14] http://www.youtube.com/watch?v=rxaW8F98smw or http://www.tudou.com/programs/view/bWUS0CNVp-E/ [15] Greub, W.: ‘Linear Algebra (third edition)’ (New York: Springer-Verlag, 1967) [16] Goodwin, G., Seron, M., and De Don ́ a, J.: ‘Constrained control and estimation: an optimisation approach’ (Springer- Verlag, 2005) October 29, 2018 DRAFT