Hostname: page-component-cd9895bd7-mkpzs Total loading time: 0 Render date: 2024-12-24T16:00:08.620Z Has data issue: false hasContentIssue false

Frequency-dependent $\textrm{H}_{{\infty }}$ control for wind disturbance rejection of a fully actuated UAV

Published online by Cambridge University Press:  15 April 2024

Jérémie X. J. Bannwarth
Affiliation:
Department of Mechanical and Mechatronics Engineering, University of Auckland, Auckland, New Zealand
Shahab Kazemi*
Affiliation:
Department of Mechanical and Mechatronics Engineering, University of Auckland, Auckland, New Zealand
Karl Stol
Affiliation:
Department of Mechanical and Mechatronics Engineering, University of Auckland, Auckland, New Zealand
*
Corresponding author: Shahab Kazemi; Email: [email protected]
Rights & Permissions [Opens in a new window]

Abstract

In this paper, an $\textrm{H}_{{\infty }}$ dynamic output feedback controller is experimentally implemented for the position regulation of a fully actuated tilted-rotor octocopter unmanned aerial vehicle (UAV) to improve wind disturbance rejection during station-keeping. To apply the lateral forces, besides the standard tilt-to-translate (attitude-thrust) movement, tilted-rotor UAVs can generate vectored (horizontal) thrust. Vectored-thrust is high-bandwidth but saturation-constrained, while attitude-thrust generates larger forces with lower bandwidth. For the first time, this paper emphasizes the frequency-dependent allocation of weighting matrices in $\textrm{H}_{{\infty }}$ control design based on the physical capabilities of the fully actuated UAV (vectored-thrust and attitude-thrust). A dynamic model of the tilted-rotor octocopter, including aerodynamic effects and rotor dynamics, is presented to design the controller. The proposed $\textrm{H}_{{\infty }}$ controller solves the frequency-dependent actuator allocation problem by augmenting the dynamic model with weighting transfer functions. This novel frequency-dependent allocation utilizes the attitude-thrust for low-frequency disturbances and vectored-thrust for high-frequency disturbances, which exploits the maximum potential of the fully actuated UAV. Several wind tunnel experiments are conducted to validate the model and wind disturbance rejection performance, and the results are compared to the baseline PX4 Autopilot controller on both the tilted-rotor and a planar octocopter. The $\textrm{H}_{{\infty }}$controller is shown to reduce station-keeping error by up to 50% for an actuator usage 25% higher in free-flight tests.

Type
Research Article
Creative Commons
Creative Common License - CCCreative Common License - BY
This is an Open Access article, distributed under the terms of the Creative Commons Attribution licence (http://creativecommons.org/licenses/by/4.0/), which permits unrestricted re-use, distribution and reproduction, provided the original article is properly cited.
Copyright
© The Author(s), 2024. Published by Cambridge University Press

1. Introduction

Performing outdoors is one of the most essential multirotor unmanned aerial vehicle (UAV) applications [Reference Zhou, Yi, Zhang, Chen, Yang, Han and Zhang1, Reference Elmokadem and Savkin2]. However, wind disturbances can adversely affect the performance of UAVs and destabilize them. Many studies have focused on active disturbance rejection with automatic control in multirotor UAVs [Reference Lin and Stol3, Reference Guo, Jiang and Zhang4]. $\textrm{H}_{{\infty }}$ control is a well-known method for its high disturbance rejection and stability robustness, which has been widely used to address different UAV problems [Reference Hu, Bohn and Wu5Reference Rich, Elia and Jones7]. The combination of model predictive control and $\textrm{H}_{{\infty }}$ was designed for the wind disturbance rejection of quadrotors in simulation [Reference Raffo, Ortega and Rubio8, Reference Chen and Huzmezan9]. In another simulation study, Massé et al. [Reference Massé, Gougeon, Nguyen and Saussié10] incorporated a thorough aerodynamics model in their plant model and compared the control performances of linear quadratic regulation (LQR) and structured $\textrm{H}_{{\infty }}$ synthesis. Structured $\textrm{H}_{{\infty }}$ design was shown to provide a more reliable framework in wind disturbance rejection compared to LQR. In an experimental study, Dai et al., presented acceleration feedback (AF) enhanced $\textrm{H}_{{\infty }}$ control to deal with the wind disturbance on an underactuated hexacopter [Reference Dai, He, Zhang, Gu, Yang and Xu11]. The experimental results suggested the superiority of AF-enhanced $\textrm{H}_{{\infty }}$ over $\textrm{H}_{{\infty }}$ control in effectiveness and robustness against wind disturbance.

Disturbance rejection through control is inherently limited by the bandwidth of the actuators. Planar UAVs (with all the rotors parallel) are underactuated which further limits the bandwidth of the actuation along translational axes [Reference Zeng, Zhong, Wang, Fan and Zhang12]. Planar UAVs must change their attitude to produce lateral thrust, which is not desirable during station-keeping (attitude-thrust). Meanwhile, vectored-thrust (horizontal thrust) UAVs, as fully actuated systems, can produce thrust in the body xy-plane without generating moments (as opposed to planar rotors). One way to achieve vectored-thrust is to attach one or more rotors on servomotors to actively adjust their tilt angle [Reference Zheng, Tan, Kocer, Yang and Kovac13Reference Panza, Lovera, Sato and Muraoka16]. This technique increases the number of moving parts and thus decreases reliability. Also, the servomotor bandwidth is a limiting factor, particularly under the influence of large gyroscopic moments.

Another way to design fully actuator UAV is to have (omnidirectional) fixed rotors by arranging them at extreme angles against each other [Reference Brescianini and D’Andrea17, Reference Crowther, Lanzon, Maya-Gonzalez and Langkamp18]. The downsides of this method are an increase in mass and reduction in hover efficiency. Finally, UAVs with passively tilted rotors [Reference Arizaga, Castaneda and Castillo19Reference Chen, Bannwarth, Stol and Richards26] can be used to achieve vectored-thrust. Their rotors are tilted around differing axes, increasing the controllable degrees of freedom of the system. In this study, a passive tilted-rotor octocopter is presented to simplify the control problem through a specific rotor tilt pattern and reduce the coupling between thrust generation and attitude control. Current vectored-thrust UAV literature is split between actuator allocation (converting virtual control signals, such as desired body torques and thrusts, to physical actuator commands) and control design. While some studies concentrated on designing actuator allocation schemes [Reference Zheng, Tan, Kocer, Yang and Kovac13, Reference Lee, Leang and Yim22], some other researchers considered wind disturbance rejection as a control goal and designed a controller accordingly. Many controllers such as adaptive [Reference Arizaga, Castaneda and Castillo19], robust chattering-free [Reference Kotarski, Piljek, Brezak and Kasać21], and integral SMC [Reference Yao, Krieglstein and Janschek24] were designed and simulated for vectored-thrust UAV disturbance rejection, while none of them were implemented experimentally.

This paper introduces a novel $\textrm{H}_{{\infty }}$ synthesis tailored for fully actuated UAVs (tilted-rotor octocopter), aiming to enhance wind disturbance rejection. $\textrm{H}_{{\infty }}$ synthesis is used due to its ability to weigh competing control goals in the frequency domain. Traditionally, the determination of weighting matrices relied on experimental data [Reference Hu, Bohn and Wu5]. However, this work proposes an experimental implementation of a novel frequency-dependent weighting function allocation, building on the vectored-thrust capability of the fully actuated UAV. Notably, this work incorporates the physical capabilities of the fully actuated UAV into the frequency-dependent allocation. The new controller optimally assigns weights, utilizing attitude-thrust for low-frequency disturbances and vectored-thrust for high-frequency disturbances. This frequency-dependent actuator allocation is desirable because the maximum horizontal thrust that can be produced by changing the attitude of the UAV is significantly larger than what is achievable using the vectored-thrust. This recognition is critical, as vectored-thrust is more prone to actuator saturation and better suited for smaller amplitude, higher-frequency commands. By harnessing the UAV’s ability to generate vectored-thrust, the controller achieves a targeted response to wind disturbances with different frequencies. This allows the total capacity of the fully actuated UAV in wind disturbance rejection while keeping an acceptable performance. In other words, this frequency-dependent weighting is applied to use attitude control to reject low-frequency disturbances and use vectored-thrust for high-frequency disturbances. The rest of the paper is organized as follows.

Initially, the tilted-rotor octocopter setup is introduced, and its coordinate frame and physical characteristics are presented. A comprehensive model including the effects of wind disturbances and rotor dynamics is proposed in Section 3. Section 4 describes the design of the proposed $\textrm{H}_{{\infty }}$ controller. The flight performance is experimentally examined in a wind tunnel in Section 5. Finally, conclusions are drawn in Section 6.

2. The physical setup and coordinate frame

The presented tilted-rotor octocopter is designed and built based on a parameter sweep process to maximize agility for a given endurance and payload [Reference Chen, Stol and Richards25, Reference Chen, Bannwarth, Stol and Richards26] (see Fig. 1). The bandwidth from the vectored-thrust design is ten times higher than a comparable tilt-to-translate design. The maximum produced vectored-thrust is 24% of its weight. With reference to Fig. 1b, producing a net force along the $x$ -axis is achieved by increasing the thrust of rotors 3 and 6, while decreasing the thrust of rotors 2 and 7. The moment generated by this operation can then be canceled by increasing the thrust of rotors 1 and 8 and decreasing that of rotors 5 and 4. Table 1 lists the parameters of the selected design. Vectors expressed by $\mathcal{W}$ , $\mathcal{B}$ , and $\mathcal{M}_{i}$ are expressed in the world, body, and ith-motor frame, respectively. The world frame and body frame use the typical north-east-down and front-right-down conventions, respectively. The rotors are tilted at an angle ${\unicode[Arial]{x03B6}}$ .

Figure 1. (a) Photo of the tilted-rotor octocopter that is used in this work. (b) The front and back rotors (1, 4, 5, 8) are tilted about the body $x$ -axis, while the left and right rotors (2, 3, 6, 7) are tilted around the body $y$ -axis. The rotors of the UAV are equally distributed around the center of mass.

3. Dynamics

Wind introduces uncertainties in the aerodynamic forces acting on the UAV. Modeling these forces accurately is challenging due to the dynamic and unpredictable nature of wind. However, a comprehensive dynamic model is needed to design the model-based controller. The position of the UAV in the world frame is defined as $\boldsymbol{\xi }=[\begin{array}{c@{\quad}c@{\quad}c} \textit{x} & \textit{y} & \textit{z} \end{array}]^{\textrm{T}}$ , and its attitude is defined by the Hamilton quaternion $\textbf{q}=[\begin{array}{c@{\quad}c@{\quad}c@{\quad}c} \textit{q}_{\textit{0}} & \textit{q}_{\textit{1}} & \textit{q}_{\textit{2}} & \textit{q}_{\textit{3}} \end{array}]^{\textrm{T}}=[\begin{array}{c@{\quad}c} \textit{q}_{\textit{0}} & \textbf{q}_{\textbf{1}\colon \textbf{3}}^{\textrm{T}} \end{array}]^{\textrm{T}}$ [Reference Nekoo, Acosta and Ollero27]. The absolute angular velocity of the craft expressed in the body frame is defined as ${ }^{\mathcal{B}}{\boldsymbol{\nu }}{}=[\begin{array}{c@{\quad}c@{\quad}c} { }^{\mathcal{B}}{\textit{p}}{} & { }^{\mathcal{B}}{\textit{q}}{} & { }^{\mathcal{B}}{\textit{r}}{} \end{array}]^{\textrm{T}}$ . Using Newton–Euler formulas, the acceleration of the UAV is obtained as

(1) \begin{equation}\ddot{\boldsymbol{\xi }}=\frac{1}{\textit{m}_{\textit{t}}}\left(\textbf{G}+{}_{\mathcal{B\!}}^{\mathcal{W}}{\textbf{R}}{}\left({ }^{\mathcal{B}}{\textbf{T}}{}+{ }^{\mathcal{B}}{\textbf{F}}{}_{\text{aero}} \right)\right),\end{equation}

where ${ }^{\mathcal{W}}{\textbf{G}}{}=[\begin{array}{c@{\quad}c@{\quad}c} 0 & 0 & 9.81\textit{m}_{\textit{t}} \end{array}]^{\textrm{T}}$ is the weight vector, ${ }^{\mathcal{B}}{\textbf{T}}{}$ is the total rotor thrust, ${}_{\mathcal{B}}^{\mathcal{W}}{\textbf{R}}{}$ is the rotation matrix from the body frame to world frame, and ${ }^{\mathcal{B}}{\textbf{F}}{}_{\text{aero}}$ represents the aerodynamic force acting on the frame. Likewise, the angular acceleration of the UAV is

(2) \begin{equation}{ }^{\mathcal{B}}{\dot{\boldsymbol{\nu }}}{}=\textbf{I}_{\mathcal{B}}^{-1}\left({ }^{\mathcal{B}}{\boldsymbol{\tau }}{}-{ }^{\mathcal{B}}{\boldsymbol{\nu }}{}\times \left(\textbf{I}_{\mathcal{B}}{ }^{\mathcal{B}}{{\unicode[Arial]{x03BD}} }{}\right)+{ }^{\mathcal{B}}{\textbf{M}}{}_{\text{aero}}\right),\end{equation}

where $\textbf{I}_{\mathcal{B}}=\text{ diag}(\textit{I}_{\textit{xx}},\textit{I}_{\textit{yy}},\textit{I}_{\textit{zz}})$ represents the mass moment of inertia of the frame, ${ }^{\mathcal{B}}{\boldsymbol{\tau }}{}$ is the total rotor torque, and ${ }^{\mathcal{B}}{\textbf{M}}{}_{\text{aero}}$ is the aerodynamic moment acting on the frame. The frame aerodynamic forces and moments are defined as

(3) \begin{align}{ }^{\mathcal{B}}{\textbf{F}}{}_{\text{aero}}&=-\frac{\textit{1}}{\textit{2}}{\rho }_{\textit{air}}\textit{A}_{\textit{UAV}}\textit{U}_{\textit{app},\textit{f}}^{\textit{2}}\left[\begin{array}{c@{\quad}c@{\quad}c} \textit{C}_{\textit{x},\textit{f}}\left({\alpha }_{\textit{f}}\right){\cos } {\beta }_{\textit{f}} & \textit{C}_{\textit{x},\textit{f}}\left({\alpha }_{\textit{f}}\right){\sin } {\beta }_{\textit{f}} & \textit{C}_{\textit{z},\textit{f}}\left({\alpha }_{\textit{f}}\right) \end{array}\right]^{T}\nonumber \\[5pt]{ }^{\mathcal{B}}{\textbf{M}}{}_{\text{aero}}&=\frac{\textit{1}}{\textit{2}}{{\rho }_{\textit{air}}}{\textit{A}_{\textit{UAV}}}{\textit{D}_{\textit{UAV}}}{\textit{C}_{\textit{M},\textit{f}}}\left({\alpha }_{\textit{f}}\right)\textit{U}_{\textit{app},\textit{f}}^{\textit{2}}\left[\!\begin{array}{c@{\quad}c@{\quad}c} -{\sin } {\beta }_{\textit{f}} & {\cos } {\beta }_{\textit{f}} & \textit{0} \end{array}\right]^{\textit{T}},\end{align}

where ${\alpha }_{\textit{f}}$ and ${\beta }_{\textit{f}}$ are the inflow angle and sideslip angle of the apparent wind vector (Fig. 2a), $\textit{A}_{\textit{UAV}}=\frac{{\pi }\textit{D}_{\textit{UAV}}^{\textit{2}}}{\textit{4}}$ is the area of the UAV, and $\textit{C}_{\textit{x},\textit{f}}({\alpha }_{\textit{f}})$ , $\textit{C}_{\textit{z},\textit{f}}({\alpha }_{\textit{f}})$ , and $\textit{C}_{\textit{M},\textit{f}}({\alpha }_{\textit{f}})$ are dimensionless aerodynamic coefficients defined in ref. [Reference Bannwarth, Chen, Stol, MacDonald and Richards28]. In the body frame, the apparent wind vector is expressed as ${ }^{\mathcal{B}}{\textbf{U}}{}_{\textit{app},\textit{f}}=-{}_{\mathcal{W}}^{\mathcal{B}}{\textbf{R}}{}(\dot{\boldsymbol{\xi }}+{ }^{\mathcal{W}}{\textbf{U}}{})$ , where ${ }^{\mathcal{W}}{\textbf{U}}{}=-[\begin{array}{c@{\quad}c@{\quad}c} \textit{U}_{\textit{x}} & \textit{U}_{\textit{y}} & \textit{U}_{\textit{z}} \end{array}]^{\textrm{T}}$ is the wind velocity vector.

Table 1. Parameters of tilted-rotor octocopter.

Figure 2. Aerodynamic forces and moments acting on octocopter frame and the ith-rotor. (a) Side view of the frame when the sideslip angle ${\beta }_{\textit{f}}$ = 0. (b) Side view of the rotor when the sideslip angle ${\beta }_{\textit{i}}$ = 0.

The total force ${ }^{\mathcal{B}}{\textbf{T}}{}=\sum _{\textit{i}=1}^{\textit{N}}{ }^{\mathcal{B}}{\textbf{T}}{}_{\textit{i}},$ and torque ${ }^{\mathcal{B}}{\boldsymbol{\tau }}{}=\sum _{\textit{i}=1}^{\textit{N}}({ }^{\mathcal{B}}{\boldsymbol{\tau }}{}_{\textit{i}}-{ }^{\mathcal{B}}{\boldsymbol{\nu }}{}({\mathcal{M}_{i}}^{\mathcal{B}}{\textbf{R}}{}{ }^{\mathcal{M}_{i}}{\textbf{I}}{}_{\textrm{R}}{ }^{\mathcal{M}_{i}}{\boldsymbol{\omega }_{\textit{i}}}{})),$ are generated by all the rotors, where ${ }^{\mathcal{M}_{i}}{\boldsymbol{\omega }_{\textrm{i}}}{}=[\begin{array}{c@{\quad}c@{\quad}c} 0 & 0 & {\omega }_{\textit{i}} \end{array}]^{\textrm{T}}$ represents the angular speed of the ith-rotor, and ${ }^{\mathcal{M}_{i}}{\textbf{I}}{}_{\textrm{R}}=\text{ diag}(0,0,\textit{I}_{\textit{R},\textit{zz}})$ is the combined mass moment of inertia of the motor and rotor. The forces and torques acting on a single rotor are

\begin{equation*} { }^{\mathcal{B}}{\textbf{T}}{}_{\textrm{i}}={\mathcal{M}_{i}}^{\mathcal{B}}{\textbf{R}}{}\left[\begin{array}{c@{\quad}c@{\quad}c} \textit{T}_{\textit{i},\textit{xy}}{\cos } {\beta }_{\textit{i}} & \textit{T}_{\textit{i},\textit{xy}}{\sin } {\beta }_{\textit{i}} & \textit{T}_{\textit{i},\textit{z}} \end{array}\right]^{\textrm{T}}, \end{equation*}
(4) \begin{equation}{ }^{\mathcal{B}}{\boldsymbol{\tau }}{}_{\textrm{i}}={\mathcal{M}_{i}}^{\mathcal{B}}{\textbf{R}}{}\left[\begin{array}{c} \textit{M}_{\textit{i},\textit{xy}}{\sin } {\beta }_{\textit{i}}\\[5pt] \textit{M}_{\textit{i},\textit{xy}}{\cos } {\beta }_{\textit{i}}\\[5pt] \left(-\textit{1}\right)^{\textit{i}+\textit{1}}\left(\textit{b}{\omega }_{\textit{i}}^{\textit{2}}+\textit{I}_{\textit{R},\textit{zz}}\dot{{\omega }}_{\textit{i}}\right) \end{array}\right]+{ }^{\mathcal{B}}{\textbf{L}}{}_{\textrm{i}}{\times }{ }^{\mathcal{B}}{\textbf{T}}{}_{\textit{i}},\end{equation}

where ${\beta }_{\textit{i}}$ and ${\alpha }_{\textit{i}}$ represent the sideslip angle and inflow angle of the wind on the ith-rotor (see Fig. 2b). The $(\!-1)^{\textit{i}+1}$ term accounts for the rotor direction. The aerodynamic forces and moments acting on each rotor are defined as

(5) \begin{align}\textit{T}_{\textit{i},\textit{xy}}&=-\frac{1}{2}{\rho }_{\textit{air}}\textit{A}_{\textit{prop}}\textit{D}_{\textit{prop}}\textit{C}_{\textit{x},\textit{i}}\left({\alpha }_{\textit{i}},{\lambda }_{\textit{i}}\right){\omega }_{\textit{i}}\textit{U}_{\textit{app},\textit{i}}\nonumber\\[5pt]\textit{T}_{\textit{i},\textit{z}}&=-\frac{1}{2}{\rho }_{\textit{air}}\textit{A}_{\textit{prop}}\textit{D}_{\textit{prop}}\left(\textit{D}_{\textit{prop}}\textit{C}_{\textit{z},\textit{1},\textit{i}}{\omega }_{\textit{i}}^{\textit{2}}+\textit{C}_{\textit{z},\textit{2},\textit{i}}\left({\alpha }_{\textit{i}}\right){\omega }_{\textit{i}}\textit{U}_{\textit{app},\textit{i}}\right),\nonumber\\[5pt]\textit{M}_{\textit{i},\textit{xy}}&=-\frac{1}{2}{\rho }_{\textit{air}}\textit{A}_{\textit{prop}}\textit{D}_{\textit{prop}}^{\textit{2}}\textit{C}_{\textit{M},\textit{i}}\left({\alpha }_{\textit{i}},{\lambda }_{\textit{i}}\right){\omega }_{\textit{i}}\textit{U}_{\textit{app},\textit{i}},\end{align}

where $\textit{A}_{\textit{prop}}=\frac{{\pi }\textit{D}_{\textit{prop}}^{\textit{2}}}{\textit{4}}$ is the area covered by the propeller. $\textit{C}_{\textit{x},\textit{i}}({\alpha }_{\textit{i}},{\lambda }_{\textit{i}})$ , $\textit{C}_{\textit{z},\textit{1},\textit{i}}$ , $\textit{C}_{\textit{z},\textit{2},\textit{i}}({\alpha }_{\textit{i}})$ , and $\textit{C}_{\textit{M},\textit{i}}({\alpha }_{\textit{i}},{\lambda }_{\textit{i}})$ are dimensionless aerodynamic coefficients defined in ref. [Reference Latif, Shahzad, Bhatti, Whidborne and Samar6]. Due to the offset between the rotors and the center of mass of the UAV, the apparent wind velocity at each rotor is affected by the rotational speed of the UAV and is given by

(6) \begin{equation}{ }^{\mathcal{M}_{i}}{\textbf{U}}{}_{\textit{app},\textit{i}}={\mathcal{B}}^{\mathcal{M}_{i}}{\textbf{R}}{}\left({ }^{\mathcal{B}}{\textbf{U}}{}_{\textit{app},\textit{f}}+{ }^{\mathcal{B}}{\boldsymbol{\nu }}{}\times { }^{\mathcal{B}}{\textbf{L}}{}_{\textrm{i}}\right),\end{equation}

where ${ }^{\mathcal{B}}{\textbf{L}}{}_{\textrm{i}}$ represents a position vector from the center of the UAV to the ith-rotor and is defined as

(7) \begin{equation}{ }^{\mathcal{B}}{\textbf{L}}{}_{\textit{i}}=\frac{1}{2}\textit{D}_{\textit{UAV}}\left[\begin{array}{c@{\quad}c@{\quad}c} {\cos } {\gamma }_{\textit{i}} & {\sin } {\gamma }_{\textit{i}} & \textit{0} \end{array}\right]^{\textit{T}}.\end{equation}

Note that in Eq. (7), ${\unicode[Arial]{x03B3}} _{\textit{i}}=45\textit{i}-22.5^{\circ}$ is the angle from the positive body x-axis to the arm holding rotor i and is measured positive counterclockwise around the body z-axis (see Fig. 1b). The angular acceleration of the ith-rotor is given by

(8) \begin{equation}\dot{{\omega }}_{\textit{i}}=\frac{1}{\textit{I}_{\textit{R},\textit{zz}}}\left(\frac{\textit{K}_{\textit{T}}}{\textit{R}}\left(\textit{V}_{\textit{i}}-\textit{I}_{\textit{0}}\textit{R}-\textit{K}_{\textit{E}}{\omega }_{\textit{i}}\right)-\textit{c}_{{\tau }}{\omega }_{\textit{i}}^{\textit{2}}\right),\end{equation}

where $\textit{I}_{0}$ is the motor idle current and $\textit{R}$ is the motor resistance [Reference Chen, Stol and Richards25]. $\textit{K}_{\textit{E}}$ is the back-EMF constant, $\textrm{K}_{\textrm{T}}=\textit{K}_{\textit{E}}$ is the motor torque constant, and $\textit{c}_{{\tau }}$ is the rotor torque aerodynamic constant. Finally, $\textit{V}_{\textrm{i}}$ is the input voltage to the motor. The PWM to motor voltage mapping for the motors is obtained by mounting a single motor on a RCBenchmark Series 1580 Thrust Stand. The relationship between the normalized PWM signal sent to a motor ( ${\chi }_{\textrm{i}}\in [0,1]$ ), and the input voltage is $\textit{V}_{\textit{i}}=6.982{\chi }_{\textit{i}}+2.351.$

4. Control architecture

To conduct the wind disturbance rejection while hovering at a fixed location, a cascaded closed-loop controller is designed and implemented for the presented tilted-rotor octocopter. For the implementation board and software, a Pixhawk Cube board running the PX4 Autopilot Firmware is employed. Note that the cascaded structure used in this work is mostly identical to that of the position hold control mode of the baseline (BL) PX4 Autopilot version 1.8.2 [Reference Meier, Agar, Küng, Gubler, Sidrane, Oes, Babushkin, Charlebois, Bapst, Mannhart, Antener, Goppert, Tridgell, Riseborough, Grob, Whitehorn, Wilks, Mohammed, Smeets, Kirienko, Marques, Tobler, Jansen, Rivizzigno, Gagne, Siesta, de Souza, Achermann and Lecoeur29].

The BL closed-loop control architecture is split into inner and outer loops. The inner loop controls the desired UAV attitude (orientation) and comprises of a globally stable nonlinear quaternion-based angular controller [Reference Brescianini, Hehn and D’Andrea30], and PID control for angular rate. Meanwhile, for the outer loop, the position controller consists of a proportional gain acting on the position error and a PID velocity controller for each axis. In this work, for the outer loop, a novel $\textrm{H}_{{\infty }}$ dynamic output feedback controller is designed to improve the wind disturbance rejection performance.

Fig. 3 illustrates the closed-loop cascaded architecture. As only performance in front-facing wind is investigated, the desired yaw angle ${\psi }_{\textrm{des}}=0$ ° for the remainder of this work. The output of the $\textrm{H}_{{\infty }}$ block is converted to a desired attitude, $\textbf{q}_{\textrm{des}}$ , and the normalized thrust ${ }^{\mathcal{B}}{\textbf{T}}{}_{\textrm{des}}=[\begin{array}{c@{\quad}c@{\quad}c} { }^{\mathcal{B}}{\textit{T}}{}_{\textit{des},\textit{x}} & { }^{\mathcal{B}}{\textit{T}}{}_{\textit{des},\textit{y}} & { }^{\mathcal{B}}{\textit{T}}{}_{\textit{des},\textit{z}} \end{array}]^{\textrm{T}}$ . The attitude controller outputs desired normalized roll, pitch, and yaw torques, in the form of ${ }^{\mathcal{B}}{\textbf{C}}{}_{{\unicode[Arial]{x03B7}} }=[\begin{array}{c@{\quad}c@{\quad}c} \textit{C}_{{\phi }} & \textit{C}_{{\theta }} & \textit{C}_{{\psi }} \end{array}]^{\textrm{T}}$ .

Figure 3. The control implementation architecture.

The actuator allocation is performed by the motor mixer. Note that the motor mixer accepts the desired thrust, ${ }^{\mathcal{B}}{\textbf{T}}{}_{\textrm{des}}$ , and torque commands, ${ }^{\mathcal{B}}{\textbf{C}}{}_{{\unicode[Arial]{x03B7}} }$ , in the body frame, whereas the position controller operates in the world frame. To deal with this, two virtual acceleration signals in the world frame are introduced; the virtual attitude-thrust acceleration $\textbf{a}_{\textrm{A},\textrm{des}}\in \mathfrak{R}^{3}$ and the virtual vectored-thrust (horizontal) acceleration $\textbf{a}_{\textrm{H},\textrm{des}}\in \mathfrak{R}^{3}.$ Initially, $\textbf{a}_{\textrm{H},\textrm{des}}$ is rotated to the body frame, yielding

(9) \begin{equation}{ }^{\mathcal{B}}{\textbf{a}}{}_{\textrm{H},\textrm{des}}={\mathcal{W}}^{\mathcal{B}}{\textbf{R}}{}\textbf{a}_{\textrm{H},\textrm{des}}= \left[\begin{array}{c@{\quad}c@{\quad}c} { }^{\mathcal{B}}{\textit{T}}{}_{\textit{des},\textit{x}} & { }^{\mathcal{B}}{\textit{T}}{}_{\textit{des},\textit{y}} & { }^{\mathcal{B}}{\textit{a}}{}_{\textit{H},\textit{des},\textit{z}} \end{array}\right]^{\textrm{T}}.\end{equation}

The first two elements in the x and y-axis can be produced by the tilted rotors. Yet, ${ }^{\mathcal{B}}{\textbf{a}}{}_{\textrm{H},\textrm{des},\textrm{z}}$ is an unintended side effect of the vectored-thrust scheme when the UAV is not level and must be compensated using attitude control. This element is isolated, rotated back to the world frame, and added to the desired attitude acceleration. Consequently, the total attitude acceleration $\textbf{a}_{\textrm{des}}$ is defined as

(10) \begin{equation}\textbf{a}_{\textrm{des}}=\textbf{a}_{\textrm{A},\textrm{des}}+{}_{\mathcal{B}}^{ \mathcal{W}}{\textbf{R}}{}\left[\begin{array}{c} 0\\[5pt] 0\\[5pt] { }^{\mathcal{B}}{\textit{a}}{}_{\textit{H},\textit{des},\textit{z}} \end{array}\right].\end{equation}

The PX4 Autopilot thrust-to-quaternion algorithm converts the total attitude acceleration setpoint to the desired quaternion, $\textbf{q}_{\textrm{des}},$ and vertical thrust, ${ }^{\mathcal{B}}{\textit{T}}{}_{\textrm{des},\textrm{z}}$ , that can be fed to the motor mixer (see Fig. 3). The desired vertical thrust is simply the magnitude of the desired attitude acceleration, ${ }^{\mathcal{B}}{\textit{T}}{}_{\textrm{des},\textrm{z}}=-\| \textbf{a}_{\textrm{des}}\| _{2}.$

In the next step, the motor mixer maps the desired thrust, ${ }^{\mathcal{B}}{\textbf{T}}{}_{\textrm{des}}$ , and the torque command, ${ }^{\mathcal{B}}{\textbf{C}}{}_{{\unicode[Arial]{x03B7}} }$ , into a vector of PWM signals ( $\boldsymbol{\chi }$ ) to be sent to the motors (see Fig. 3). Details of how the motor mixer is constructed can be found in ref. [Reference Chen, Bannwarth, Stol and Richards26]. The motor mixer is designed to accept vectored-thrust commands. The motor mixer depends on the angle between the rotor arms, ${{\Delta}} {\unicode[Arial]{x03B3}} =45$ °, and the tilt angle of the rotors, ${\zeta }$ , such that

(11) \begin{equation}\boldsymbol{\chi }=\left[\begin{array}{c@{\quad}c@{\quad}c@{\quad}c@{\quad}c@{\quad}c} -\textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & \textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & 1 & \textrm{a} & -\textrm{b} & 1\\[5pt] -\textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & \textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -1 & -\textrm{b} & \textrm{a} & 1\\[5pt] -\textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -\textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & 1 & \textrm{b} & \textrm{a} & 1\\[5pt] -\textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -\textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -1 & -\textrm{a} & -\textrm{b} & 1\\[5pt] \textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -\textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & 1 & -\textrm{a} & \textrm{b} & 1\\[5pt] \textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -\textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -1 & \textrm{b} & -\textrm{a} & 1\\[5pt] \textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & \textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & 1 & -\textrm{b} & -\textrm{a} & 1\\[5pt] \textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & \textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2} & -1 & \textrm{a} & \textrm{b} & 1 \end{array}\right]\left[\begin{array}{c} { }^{\mathcal{B}}{\textbf{C}}{}_{{\unicode[Arial]{x03B7}} }\\[5pt] { }^{\mathcal{B}}{\textbf{T}}{}_{\textrm{des}} \end{array}\right],\end{equation}

where $\textrm{S}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2}=\sin ({\unicode[Arial]{x03B3}} /2)$ , $\textrm{C}_{{{\Delta}} {\unicode[Arial]{x03B3}} /2}= \cos ({\unicode[Arial]{x03B3}} /2)$ , $\textrm{a}=2\frac{\tan \left({{\Delta}} {\unicode[Arial]{x03B3}} /2\right)}{\tan ( {\unicode[Arial]{x03B6}} )},$ and $\textrm{b}=\frac{2}{\tan {\unicode[Arial]{x03B6}} }$ . For comparison, the elements of the fourth and fifth column of the motor mixer matrix in Eq. (11) are zero in the BL PX4 motor mixer matrix.

Figure 4. $\textit{H}_{{\infty }}$ closed-loop control schematic with weighting matrices.

4.1. Linearized plant

Synthesizing the $\textrm{H}_{{\infty }}$ controller requires a linearized model of the plant. The attitude is expressed as $\boldsymbol{\eta }=[\begin{array}{c@{\quad}c@{\quad}c} {\phi } & {\theta } & {\psi } \end{array}]^{\textrm{T}}$ , where ${\phi }$ , ${\theta }$ , and ${\psi }$ are the roll, pitch, and yaw angles of the octocopter, respectively. The motor mixer and attitude controller are included in the plant model. The input vector of the plant is defined as $\textbf{u}=[\begin{array}{c@{\quad}c} \textbf{a}_{\textrm{A},\textrm{des}}^{\textrm{T}} & \textbf{a}_{\textrm{H},\textrm{des}}^{\textrm{T}} \end{array}]^{\textrm{T}}$ , and the wind velocity ( $\textbf{w}_{\textrm{d}}={ }^{ \mathcal{W}}{\textbf{U}}{}$ ) is the disturbance input (see Fig. 4). The state vector is $\textbf{x}= [\begin{array}{c@{\quad}c@{\quad}c@{\quad}c@{\quad}c@{\quad}c} \boldsymbol{\xi }^{\textrm{T}} & \dot{\boldsymbol{\xi }}^{\textrm{T}} & \boldsymbol{\eta }^{\textrm{T}} & { }^{\mathcal{B}}{\boldsymbol{\nu }}{}^{\textrm{T}} & \boldsymbol{\omega }^{\textrm{T}} & \textbf{x}_{\textrm{PID}}^{\textrm{T}} \end{array}]^{\textrm{T}}$ (27 states), where $\boldsymbol{\omega }=[\begin{array}{c@{\quad}c@{\quad}c@{\quad}c} {\omega }_{1} & {\omega }_{2} & {\cdots } & {\omega }_{8} \end{array}]^{\textrm{T}}$ is the rotors’ angular speed vector and $\textbf{x}_{\textrm{PID}}$ is a vector containing the internal states of the angular rate loop. The pitch and roll rate controllers use PID controllers with a second-order derivative filter (three states each). The yaw rate controller uses a PI controller and only has one state. The attitude controller already stabilizes the internal attitude and angular velocity states. Therefore, the output vector only contains the integral of position, position, and velocity of the UAV, $\textbf{y}= [\begin{array}{c@{\quad}c@{\quad}c} \int \boldsymbol{\xi }^{\textrm{T}} & \boldsymbol{\xi }^{\textrm{T}} & \dot{\boldsymbol{\xi }}^{\textrm{T}} \end{array}]^{\textrm{T}}$ .

The system is trimmed for the wind velocity $\textbf{U}^{\textrm{*}}=[\begin{array}{c@{\quad}c@{\quad}c} 5.6 & 0 & 0 \end{array}]^{\textrm{T}}$ m/s. This velocity corresponds to approximately 50% of the feasible velocity range of the boundary layer wind tunnel used. In the trimming algorithm, position and rate states are constrained to zero. Also, the vectored-thrust is not used at steady state, which simplifies the trimmed input to $\textbf{u*}=[\begin{array}{c@{\quad}c} \textbf{a*}_{\textrm{A},\textrm{des}}^{\textrm{T}} & \textbf{0} \end{array}]^{\textrm{T}}$ . As expected, the trimmed pitch angle, ${\theta }^{\textrm{*}}=-8.25$ °, is negative, corresponding to the UAV pitching into the wind to counteract its drag force. The model is then linearized around the calculated operating point (resulting from the trim process) using MATLAB’s linearize function. The linearized model now needs to be augmented by weighing matrices before controller synthesis.

The disturbance rejection, regulation performance, and actuator usage are competing and need to be weighted. Therefore, the linearized model also needs to be augmented by weighting matrices. The linearized plant and $\textrm{H}_{{\infty }}$ controller dynamics to be designed are denoted as the transfer function matrices $\textbf{G}(\textrm{s})$ and $\textbf{K}(\textrm{s})$ , respectively. $\textbf{W}_{\textrm{u}}(\textrm{s})$ , $\textbf{W}_{\textrm{d}}(\textrm{s})$ , $\textbf{W}_{\textrm{o}}(\textrm{s})$ , and $\textbf{W}_{\textrm{s}}(\textrm{s})$ represent the actuator, wind disturbance, output, and sensor noise weighting matrices, respectively (see Fig. 4). The regulated output vector, $\textbf{z}= [\begin{array}{c@{\quad}c} \textbf{z}_{\textrm{out}}^{\textrm{T}} & {\textbf{z}_{\textrm{act}}}^{\textrm{T}} \end{array}]^{\textrm{T}}$ , and the disturbance input vector, $\textbf{w}=[\begin{array}{c@{\quad}c} \textbf{w}_{\text{sens}}^{\textrm{T}} & {\textbf{w}_{\textrm{d}}}^{\textrm{T}} \end{array}]^{\textrm{T}}$ , are defined. The actuator weighting matrix is defined as $\textbf{W}_{\textrm{u}}(\textrm{s})=\text{diag} (\textit{W}_{\textit{u},\textit{A}}(\textrm{s}),\textit{W}_{\textit{u},\textit{A}}(\textrm{s}),\textit{W}_{\textit{u},\textit{A}}(\textrm{s}),\textit{W}_{\textit{u},\textit{H}}(\textrm{s}),\textit{W}_{\textit{u},\textit{H}}(\textrm{s})),$ where

(12) \begin{equation}\textit{W}_{\textit{u},\textit{A}}\left(\textrm{s}\right)= 50.1\frac{\textrm{s}+{\omega }_{\textit{co}}}{\textrm{s}+10{\omega }_{\textit{co}}},\textit{W}_{\textit{u},\textit{H}}\left(\textrm{s}\right)= 8.91\frac{\textrm{s}+{\omega }_{\textit{co}}}{\textrm{s}+0.1{\omega }_{\textit{co}}},\end{equation}

where ${\omega }_{\textit{co}}$ is the desired cross-over frequency (the frequency at which the vectored-thrust should take over from the attitude control). The controller should use the attitude controller for low-frequency disturbances and vectored-thrust for high-frequency disturbances. This frequency-dependent actuator allocation is desirable because the maximum attitude-thrust of the UAV is significantly larger than vectored-thrust. Consequently, vectored-thrust is more likely to saturate the actuators and is better suited to smaller amplitude, higher-frequency commands. The first three diagonal elements of $\textbf{W}_{\textrm{u}}(\textrm{s})$ correspond to the desired virtual attitude-thrust, and the last two correspond to the desired vectored-thrust. The virtual attitude-thrust is penalized at high frequencies, while vectored-thrust is penalized at low frequencies. The locations of zeros and poles are chosen based on a desired cross-over frequency, ${\omega }_{\textit{co}}={\unicode[Arial]{x03C0}}$ rad/s. This frequency is chosen to be below the cutoff frequencies of $\textit{a}_{\textit{A},\textit{des},\textit{x}}$ and $\textit{a}_{\textit{A},\textit{des},\textit{y}}$ , which are 8 rad/s. The DC gains of the attitude and vectored-thrust transfer functions are chosen to be 14 dB and 19 dB, respectively, by the trial-and-error process to prevent actuator saturation.

Figure 5. Fitting first-order transfer function to x-axis wind spectrum.

The wind disturbance weighting matrix, $\textbf{W}_{\textrm{d}}$ , can be deemed as a function that shapes white noise into the expected spectrum of the wind. Fig. 5 shows the $x$ -axis wind spectrum of the wind tunnel and a first-order transfer function fitted to it. The high-frequency roll-off of the spectrum is -28.5 dB/dec, which cannot be replicated using a transfer function. An asymptotic approximation is used to find the corner frequency of the spectrum ( $24.1$ rad/s). $\textbf{W}_{\textrm{d}}$ is given the same corner frequency, but its magnitude is set to 15 dB through trial-and-error to improve disturbance rejection while preventing actuator saturation, yielding

(13) \begin{equation}\textbf{W}_{\textrm{d}}\left(\textrm{s}\right)=5.62\frac{24.1}{\textrm{s}+24.1}\mathbb{I}\textbf{,}\mathbb{I}\in \mathfrak{R}^{3\times 3},\end{equation}

where $\mathbb{I}$ is the identity matrix. The output and sensor noise weighting matrices are arbitrarily chosen as

(14) \begin{equation}\textbf{W}_{\textrm{o}}=\frac{1}{2}\mathbb{I},\textbf{W}_{\textrm{s}}=\frac{1}{20}\mathbb{I},\mathbb{I}\in \mathfrak{R}^{9\times 9}.\end{equation}

Finally, the Laplace domain weighing matrices and linearized plant model are combined.

4.2. $\textrm{H}_{{\infty }}$ output feedback position controller

In the previous section, after trimming the plant, finding the operating point, and linearizing the plant around the operating point, the model was augmented with weighting matrices. According to Fig. 4, the state space dynamics of the controller, $\textbf{K}(\textrm{s})=(\textbf{A}_{\textrm{K}},\textbf{B}_{\textrm{K}},\textbf{C}_{\textrm{K}},\textbf{D}_{\textrm{K}})$ , are

(15) \begin{align} \dot{\textbf{x}}_{\textrm{K}}&=\textbf{A}_{\textrm{K}}\textbf{x}_{\textrm{K}}+ \textbf{B}_{\textrm{K}}\textbf{y},\nonumber\\[5pt] \textbf{u}&=\textbf{C}_{\textrm{K}}\textbf{x}_{\textrm{K}}+ \textbf{D}_{\textrm{K}}\textbf{y},\end{align}

where $\textbf{x}_{\textrm{K}}$ is the internal state vector of the controller, and $\textrm{A}_{\textrm{K}}$ , $\textbf{B}_{\textrm{K}}$ , $\textbf{C}_{\textrm{K}}$ , and $\textbf{D}_{\textrm{K}}$ are constant matrices. This controller is an output feedback controller because it acts on the measured output, y, rather than on the system state, x, that is described in Section 4.1.

$\textrm{H}_{{\infty }}$ techniques often use a high number of states, which can be undesirable and computationally expensive for real-time applications. Typical $\textrm{H}_{{\infty }}$ synthesis algorithms, such as MATLAB’s inbuilt hinfsyn, create full-order controllers with the same number of states as the plant. The octocopter plant in this work will result in a 38th-order controller. Combined with the controller’s nine inputs and five outputs, a discrete implementation will require more than two thousand multiplication operations at each time step. This complexity causes a substantial computational burden for the onboard flight controller, Pixhawk Cube. The open-source HIFOO 2.0 toolbox (MATLAB) [Reference Gumussoy, Henrion, Millstone and Overton31] solves this issue by allowing for the creation of reduced order controllers using an optimization-based algorithm. Therefore, HIFOO 2.0 synthesizes the controller from the linearized model described in Section 4.1. The reduced order controller (order of 1) is created to keep the performance like the full-order controller while significantly reducing the computation cost. Note that implementing the resulting controller on the original system requires accounting for the trimmed input, $\textbf{u}^{\textrm{*}}$ (see Section 4.1).

(16) \begin{align} \textrm{A}_{\textrm{K}}&=-11.0, \\[5pt] \textbf{C}_{\textrm{K}}&=\left[\begin{array}{c@{\quad}c@{\quad}c} -2.82 & 2.55 & \begin{array}{c@{\quad}c@{\quad}c} -0.956 & 5.99 & 0.0202 \end{array} \end{array}\right]^{T}, \nonumber\\[5pt]\textbf{B}_{\textrm{K}}&=[\begin{array}{c@{\quad}c@{\quad}c} 0.847 & \begin{array}{c@{\quad}c@{\quad}c} -2.39 & \ldots & -0.239 \end{array} & -0.0859 \end{array}]_{1\times 9},\nonumber\\[5pt]\textbf{D}_{\textrm{K}}&=\left[\begin{array}{c@{\quad}c@{\quad}c} -0.0616 & \cdots & -0.0147\\[5pt] \vdots & \ddots & \vdots \\[5pt] 0.0155 & \cdots & 0.0111 \end{array}\right]_{5\times 9}.\nonumber \end{align}

For the attitude control part, by choosing the Lyapunov candidate function as $V(\textit{z},\textbf{q})=\textbf{q}_{1\colon 3}^{\textrm{T}}\textbf{q}_{1\colon 3}+ ({\textit{q}_{\textit{0}}}-1)^{2}$ , where $\textrm{z} \in \{\begin{array}{c@{\quad}c} \textrm{z}_{1} & \textrm{z}_{2} \end{array}\}$ corresponds to the upper and lower hemisphere of the space of unit quaternions, we can show that $V(\textit{z},\textbf{q})\gt 0$ and $\dot{\textit{V}}(\textit{z},\textbf{q})\lt 0$ (see detailed proof of stability in ref. [Reference Bannwarth, Chen, Stol, MacDonald and Richards28]). This shows that the attitude controller stabilizes the internal attitude and angular velocity states. For the analytical proof of stability of the position control part, since $\textbf{W}_{\textrm{u}}(\textrm{s})$ , $\textbf{W}_{\textrm{d}}(\textrm{s})$ , $\textbf{W}_{\textrm{o}}(\textrm{s})$ , and $\textbf{W}_{\textrm{s}}(\textrm{s})$ are positive definite, we can use the standard linear matrix inequality positive definite solution (See Appendix B of [Reference Dai, He, Zhang, Gu, Yang and Xu11] for the detailed proof of stability). Meanwhile, from Eq. (16) for the newly designed position controller, the controller has a single pole at -11 rad/s. Fig. 6 shows the pole-zero map of the closed-loop system, including the linearized model and the controller. It can be seen that all poles are in the open left halfplane, proving the stability of the linear closed-loop position control system. Note that the other poles to the far left have been removed to improve visibility.

Figure 6. Upper half of the pole-zero map close to the imaginary axis for the linearized plant and closed-loop system.

Fig. 7 shows the Bode magnitude plot of the transfer function from the wind disturbance input, $\textrm{U}_{\textrm{x}}(\textrm{s})$ , to the attitude and vectored-thrust accelerations. The magnitude responses of these transfer functions indicate which actuator is used to compensate for wind disturbances. The magnitude response of vectored-thrust control is lower than that of attitude control at all frequencies due to the higher DC gain of the weighting function used. Nevertheless, the relative magnitudes of the transfer functions are not constant; at low frequencies, the attitude control response is 25 dB higher than the vectored-thrust response, whereas the difference narrows down to 10.1 dB as ${\unicode[Arial]{x03C9}} \rightarrow {\infty }$ . These magnitude responses demonstrate the desired frequency-dependent actuator allocation as the vectored-thrust is not used at low frequencies to prevent saturation and is used increasingly at higher frequencies to improve disturbance rejection. The peaks of both responses are at 2.5 rad/s, which is close to the cross-over frequency of the actuator weighting functions at ${\unicode[Arial]{x03C0}}$ rad/s.

Figure 7. Magnitude response of the transfer functions from the wind disturbance to the desired accelerations.

5. Free-flight experiments

5.1. Free-flight station-keeping performance

UAVs encounter a range of disturbances beyond wind, including atmospheric factors like turbulence and thermal updrafts, environmental elements, obstacles in the flight path, potential sensor inaccuracies and noise, communication disruptions, electromagnetic interference, and the risk of system faults. Physical interaction is also another considerable source of disturbance, in which the UAV is interacting through a tool with the surrounding environment. In this paper, however, we assumed all other factors negligible compared to the wind and turbulence disturbances. Also, the UAV is not in contact with its surroundings (free flight).

To validate the performance of the $\textrm{H}_{{\infty }}$ controller for wind disturbance rejection, and conducting a comparison, a comprehensive experiment is designed. Three cases are considered: the tilted-rotor octocopter with the $\textrm{H}_{{\infty }}$ controller, the tilted-rotor octocopter with the BL controller, and a planar version of the octocopter with the BL controller. The UAV is flown inside the wind tunnel in a test section outfitted with motion capture cameras to provide position feedback (see Fig. 8a). A disturbance-generating grid is mounted ahead of the flight location to generate turbulence intensities of approximately 10%.

Figure 8. Wind disturbance rejection experiment. (a) Octocopter station-keeping in the boundary layer wind tunnel, University of Auckland. (b) RMS error of the position norm. (c) RMS rotation error. (d) Mean RMS of the motor PWM signals.

Note that the octocopter is powered by two 40A power supplies through an approximately 3 m long tether, as shown in Fig. 8a. The power supplies are set to 13V to account for a measured 2V drop across the tether. This tethered solution is chosen over traditional batteries as it allows faster testing by removing the need to swap and charge batteries. Furthermore, the constant power supply voltage provides consistency between and during tests.

Three wind speeds of $\textbf{U}_{\text{mean}}=\{0,5.6,12.8\}$ m/s are investigated. Each flight starts with the UAV sitting on the floor, midway between the wind tunnel walls and 3.8 m away from the turbulence grid. The operator then switches the UAV to position hold mode to track a position setpoint at the center of the wind tunnel. The second phase of the experiment involves setting the wind tunnel to the desired speed setting and waiting for the transients to decay before recording the response of the UAV. Each flight yields 100 s of usable data after removing all transient behaviors.

Through 72 experimental tests, it was demonstrated that despite increasing the mean wind speed from 5.6 m/s to 12.8 m/s and also adding 10% turbulence intensity, the hovering RMS position error norm remained smaller than 5 cm (Fig. 8b). RMS principal axis rotation error also remained smaller than 1.5° (Fig. 8c). This shows that the presented linearized model-based controller (linearized based on 5.6 m/s wind with no turbulence) is valid for the actual nonlinear system operating under different conditions. These results are also promising compared to another experimental study on $\textrm{H}_{{\infty }}$ control (with a hexacopter roughly the same size of the octocopter used in this study) [Reference Dai, He, Zhang, Gu, Yang and Xu11], where the RMS position error was calculated between 10 to 15 cm. Note that in ref. [Reference Dai, He, Zhang, Gu, Yang and Xu11], the wind disturbance was generated by a simple fan, without turbulence (with the average wind speed of 7.5 m/s). Meanwhile, this study generated its wind disturbance in the wind tunnel, with 10% turbulence.

Figure 9. Tilted-rotor octocopter response to a step change in desired vectored-thrust acceleration in altitude hold mode. (a) Desired normalized horizontal accelerations, (b) Attitude, (c) Translational acceleration, (d) and motor PWM signals.

Fig. 8(b-d) shows the main performance metrics obtained from the experimental data. The presented $\textrm{H}_{{\infty }}$ controller significantly outperforms both BL cases in position error (see Fig. 8b). At the maximum wind speed of 12.8 m/s, the $\textrm{H}_{{\infty }}$ controller yields an RMS position error norm ( ${\sigma }_{{\xi }}$ ) 51% lower than the BL tilted case and 38% lower than the BL planar case. At 0 and 5.6 m/s, there is a significant overlap between the recorded data points for the two BL controllers. However, overlap at 12.8 m/s is minimal, with the BL planar case resulting in a 21% lower RMS error norm than the BL tilted case. The BL planar setup has a higher thrust ceiling, allowing it to outperform the BL tilted configuration slightly.

The RMS principal axis rotation error ( ${\sigma }_{{\Phi }}$ ), denoting the shortest rotation between the measured and desired orientations, shows considerable overlap of the three data sets at non-zero wind speeds (see Fig. 8c). Therefore, the configuration does not have a significant effect on the attitude control performance at those wind speeds. However, at zero wind speed, the BL planar case yields an RMS rotation error over twice as large as the other controllers. This difference is mainly due to the low yaw control authority of the planar arrangement, which results in higher errors. These increased errors are not seen at higher wind speeds, which could be due to the aerodynamic loadings acting on the UAV, but further experimentation is required to identify the source of this behavior.

Wind resistance increases energy consumption as the UAV works harder to overcome the wind disturbances. Having an energy-efficient control strategy to optimize UAV flight endurance and battery life in the presence of wind is important. The mean RMS of the motor commands ( $\overline{{\sigma }}_{{\chi }}$ ) is similar for both tilted cases at zero wind speed. However, the actuator usage of the $\textrm{H}_{{\infty }}$ controller is 23% and 25% higher than the BL tilted case at 5.6 and 12.8 m/s, respectively (Fig. 8d). This means the $\textrm{H}_{{\infty }}$ controller yields significantly improved station-keeping performance compared to the BL tilted configuration for only a marginal increase in actuator usage. The BL controller on the planar case requires significantly more actuator usage across all wind speeds, which is again due to the lack of yaw authority. Resolving this issue would involve replacing the motors and propellers with larger ones.

5.2. Vectored-thrust demonstration

To demonstrate the vectored-thrust capability and validate the motor mixer presented in Eq. (16), an experiment is carried out on the tilted-rotor octocopter with zero wind speed. The UAV is manually flown at an initial altitude of 1.25 m. A step command is applied along the positive ${ }^{\mathcal{B}}{\textit{x}}{}$ -axis at $\textit{t}=0.5$ s (see Fig. 9a). Despite the command, the attitude of the UAV does not change significantly, with all angles remaining below 0.25° (see Fig. 9b). Meanwhile, according to Fig. 9c, the UAV accelerates forward at a rate of around 2.4 m/s2. Fig. 9d shows how the motor mixer immediately converts the desired ${ }^{\mathcal{B}}{\textit{x}}{}$ -axis command to a PWM differential. Producing the horizontal acceleration without affecting the attitude of the UAV validates the motor mixer matrix.

6. Conclusion

A robust $\textrm{H}_{{\infty }}$ output feedback controller was designed and implemented within a cascaded control structure to regulate the position of a tilted-rotor octocopter under wind disturbances while hovering at a point. The tilted pattern of the octocopter allows for high-bandwidth, yet saturation-constrained vectored-thrust, which is not feasible on typical tilt-to-translate planar UAVs. The problem of frequency-dependent actuator allocation, which is largely ignored in current vectored-thrust UAV literature, is solved by augmenting the plant model with weighting transfer functions. Reduced order $\textrm{H}_{{\infty }}$ synthesis is conducted on a linearized version of the augmented model to yield robust performance. 72 free-flight wind tunnel tests were conducted at wind speeds of 0, 5.6, and 12.8 m/s to compare the $\textrm{H}_{{\infty }}$ controller’s performance to that of the BL controller on both a tilted and planar octocopter. The $\textrm{H}_{{\infty }}$ controller significantly reduced the RMS position error for a slight increase in actuator usage. The $\textrm{H}_{{\infty }}$ RMS position error decreased by 51% compared to the BL tilted case and 38% to the BL planar case. Conversely, its actuator usage is 25% higher than the BL tilted case. In free-flight experiments, the octocopter produced a forward acceleration of 2.4 m/s2 when subjected to a vectored-thrust step while regulating its pitch angle to less than 0.25°, successfully demonstrating the effectiveness of the new motor mixer.

Author contribution

JXB: writing initial draft, methodology, experiments, and data analysis. SK: writing, review, and revision. KS: supervision, review.

Financial support

The research reported in this article was conducted as part of “Enabling unmanned aerial vehicles (UAVs) to use tools in complex dynamic environments UOCX2104,” which is funded by the New Zealand Ministry of Business, Innovation and Employment.

Competing interests

The authors declare no competing interests exist.

Ethical approval

None.

References

Zhou, B., Yi, J., Zhang, X., Chen, L., Yang, D., Han, F. and Zhang, H., “An autonomous navigation approach for unmanned vehicle in outdoor unstructured terrain with dynamic and negative obstacles,” Robotica 40(8), 28312854 (2022).CrossRefGoogle Scholar
Elmokadem, T. and Savkin, A. V., “A method for autonomous collision-free navigation of a quadrotor UAV in unknown tunnel-like environments,” Robotica 40(4), 835861 (2022).CrossRefGoogle Scholar
Lin, T.-J. and Stol, K. A., “Faster navigation of semi-structured forest environments using multirotor UAVs,” Robotica 41(2), 735755 (2023).CrossRefGoogle Scholar
Guo, Y., Jiang, B. and Zhang, Y., “A novel robust attitude control for quadrotor aircraft subject to actuator faults and wind gusts,” IEEE/CAA J Autom Sin 5(1), 292300 (2018). doi: 10.1109/jas.2017.7510679.CrossRefGoogle Scholar
Hu, J., Bohn, C. and Wu, H. R., “Systematic H∞ weighting function selection and its application to the real-time control of a vertical take-off aircraft,” Control Eng Pract 8(3), 241252 (2000).CrossRefGoogle Scholar
Latif, Z., Shahzad, A., Bhatti, A. I., Whidborne, J. F. and Samar, R., “Autonomous landing of an UAV using H∞ based model predictive control,” Drones 6(12), 416 (2022).CrossRefGoogle Scholar
Rich, M., Elia, N. and Jones, P., “Design and Implementation of an H∞ Controller for a Quadrotor Helicopter,” In: 21st Mediterranean Conference on Control and Automation, Platanias, Greece, (2013) pp. 11891198.Google Scholar
Raffo, G. V., Ortega, M. G. and Rubio, F. R., “An integral predictive/nonlinear H∞ control structure for a quadrotor helicopter,” Automatica 46(1), 2939 (2010). doi: 10.1016/j.automatica.2009.10.018.CrossRefGoogle Scholar
Chen, M. and Huzmezan, M., “A combined MBPC/2 DOF H infinity controller for a quad rotor UAV,” AIAA Gui, Navi, Cont Conf Exhi 5520 (2003), 19. doi: 10.2514/6.2003-5520.Google Scholar
Massé, C., Gougeon, O., Nguyen, D.-T. and Saussié, D., “Modeling and Control of a Quadcopter Flying in a Wind Field: A Comparison Between LQR and Structured H∞ Control Techniques,” In: 2018 International Conference on Unmanned Aircraft Systems, Dallas Marriott City, USA (2018) pp. 14081417. doi: 10.1109/ICUAS.2018.8453402.CrossRefGoogle Scholar
Dai, B., He, Y., Zhang, G., Gu, F., Yang, L. and Xu, W., “Wind disturbance rejection for unmanned aerial vehicles using acceleration feedback enhanced H∞ method,” Auton Robot 44(7), 12711285 (2020).CrossRefGoogle Scholar
Zeng, J., Zhong, H., Wang, Y., Fan, S. and Zhang, H., “Autonomous control design of an unmanned aerial manipulator for contact inspection,” Robotica 41(4), 11451158 (2023).CrossRefGoogle Scholar
Zheng, P., Tan, X., Kocer, B. B., Yang, E. and Kovac, M., “TiltDrone: A fully-actuated tilting quadrotor platform,” IEEE Robot Auto Lett 5(4), 68456852 (2020). doi: 10.1109/lra.2020.3010460.CrossRefGoogle Scholar
Bhargavapuri, M., Patrikar, J., Sahoo, S. R. and Kothari, M., “A Low-Cost Tilt-Augmented Quadrotor Helicopter: Modeling and Control,” In: 2018 International Conference on Unmanned Aircraft Systems, Dallas Marriott City, USA (2018) pp. 186194. doi: 10.1109/ICUAS.2018.8453376.CrossRefGoogle Scholar
Anzai, T., Zhao, M., Murooka, M., Shi, F., Okada, K. and Inaba, M., “Modeling and Control of Fully Actuated 2D Transformable Aerial Robot with 1 DoF Thrust Vectorable Link Module,” In: 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems, Macau, Macau (2019) pp. 28202826. doi: 10.1109/IROS40897.2019.8967725.CrossRefGoogle Scholar
Panza, S., Lovera, M., Sato, M. and Muraoka, K., “Structured μ-synthesis of robust attitude control laws for quad-tilt-wing unmanned aerial vehicle,” J Guid Control Dyn 43(12), 22582274 (2020). doi: 10.2514/1.g005080.CrossRefGoogle Scholar
Brescianini, D. and D’Andrea, R., “An omni-directional multirotor vehicle,” Mechatron 55, 7693 (2018). doi: 10.1016/j.mechatronics.2018.08.005.CrossRefGoogle Scholar
Crowther, B., Lanzon, A., Maya-Gonzalez, M. and Langkamp, D., “Kinematic analysis and control design for a nonplanar multirotor vehicle,” J Guid Control Dyn 34(4), 11571171 (2011). doi: 10.2514/1.51186.CrossRefGoogle Scholar
Arizaga, J. M., Castaneda, H. and Castillo, P., “Adaptive Control for a Tilted-Motors Hexacopter UAS Flying on a Perturbed Environment,” In: 2019 International Conference on Unmanned Aircraft Systems, Atlanta, USA (2019) pp. 171177. doi: 10.1109/ICUAS.2019.8798048.CrossRefGoogle Scholar
Das, H., “A Comparative Study between a Cant Angle Hexacopter and a Conventional Hexacopter,” In: International Conference on Control, Instrumentation, Communication and Computational Technologies, Kumaracoil, India (2016) pp. 501506. doi: 10.1109/ICCICCT.2016.7988002.CrossRefGoogle Scholar
Kotarski, D., Piljek, P., Brezak, H. and Kasać, J., “Chattering-free tracking control of a fully actuated multirotor with passively tilted rotors,” Trans Famena 42(1), 114 (2018). doi: 10.21278/tof.42101.CrossRefGoogle Scholar
Lee, J. Y. S., Leang, K. K. and Yim, W., “Design and control of a fully-actuated hexrotor for aerial manipulation applications,” J. Mech. Robot 10(4), 110 (2018). doi: 10.1115/1.4039854.CrossRefGoogle Scholar
Sanchez-Cuevas, P. J., Gonzalez-Morgado, A., Cortes, N., Gayango, D. B., Jimenez-Cano, A. E., Ollero, A. and Heredia, G., “Fully-actuated aerial manipulator for infrastructure contact inspection: Design, modeling, localization, and control,” Sensors 20(17), 4708 (2020). doi: 10.3390/s20174708.CrossRefGoogle ScholarPubMed
Yao, C., Krieglstein, J. and Janschek, K., “Modeling and sliding mode control of a fully-actuated multirotor with tilted propellers,” IFAC-PapOnL 51(22), 115120 (2018). doi: 10.1016/j.ifacol.2018.11.527.CrossRefGoogle Scholar
Chen, Z. J., Stol, K. A. and Richards, P. J., “Preliminary design of multirotor UAVs with tilted-rotors for improved disturbance rejection capability,” Aerosp Sci Technol 92, 635643 (2018). doi: 10.1016/j.ast.2019.06.038.CrossRefGoogle Scholar
Chen, Z. J., Bannwarth, J. X. J., Stol, K. A. and Richards, P. J., “Analysis of a Multirotor UAV with Tilted-Rotors for the Purposes of Disturbance Rejection,” In: Proceedings of the 2018 International Conference on Unmanned Aircraft Systems, Dallas, TX, USA (2018) pp. 864873. doi: 10.1109/ICUAS.2018.8453383.CrossRefGoogle Scholar
Nekoo, S. R., Acosta, J. Á. and Ollero, A., “Quaternion-based state-dependent differential Riccati equation for quadrotor drones: Regulation control problem in aerobatic flight,” Robotica 40(9), 31203135 (2022).CrossRefGoogle Scholar
Bannwarth, J. X. J., Chen, Z. J., Stol, K. A., MacDonald, B. A. and Richards, P. J., “Aerodynamic force modeling of multirotor unmanned aerial vehicles,” AIAA J 57(3), 12501259 (2019). doi: 10.2514/1.j057165.CrossRefGoogle Scholar
Meier, L., Agar, D., Küng, B., Gubler, T., Sidrane, D., Oes, J., Babushkin, A., Charlebois, M., Bapst, R., Mannhart, D., Antener, A. D., Goppert, J., Tridgell, A., Riseborough, P., Grob, M., Whitehorn, M., Wilks, S., Mohammed, K., Smeets, S., Kirienko, P., Marques, N., Tobler, C., Jansen, J., Rivizzigno, M., Gagne, D., Siesta, B., de Souza, J. R., Achermann, F. and Lecoeur, J., “PX4 firmware: V1.8.2 stable release,” Zenodo, (2018). doi: 10.5281/zenodo.1493485.Google Scholar
Brescianini, D., Hehn, M. and D’Andrea, R., “Nonlinear quadrocopter attitude control: Technical report,” ETH Zürich, Zürich, Switzerland, (2013). doi: 10.3929/ETHZ-A-009970340.CrossRefGoogle Scholar
Gumussoy, S., Henrion, D., Millstone, M. and Overton, M. L., “Multiobjective robust control with HIFOO 2.0,” IFAC Proceed Vol 42(6), 144149 (2009). doi: 10.3182/20090616-3-il-2002.00025.CrossRefGoogle Scholar
Figure 0

Figure 1. (a) Photo of the tilted-rotor octocopter that is used in this work. (b) The front and back rotors (1, 4, 5, 8) are tilted about the body$x$-axis, while the left and right rotors (2, 3, 6, 7) are tilted around the body$y$-axis. The rotors of the UAV are equally distributed around the center of mass.

Figure 1

Table 1. Parameters of tilted-rotor octocopter.

Figure 2

Figure 2. Aerodynamic forces and moments acting on octocopter frame and the ith-rotor. (a) Side view of the frame when the sideslip angle${\beta }_{\textit{f}}$= 0. (b) Side view of the rotor when the sideslip angle${\beta }_{\textit{i}}$ = 0.

Figure 3

Figure 3. The control implementation architecture.

Figure 4

Figure 4. $\textit{H}_{{\infty }}$closed-loop control schematic with weighting matrices.

Figure 5

Figure 5. Fitting first-order transfer function to x-axis wind spectrum.

Figure 6

Figure 6. Upper half of the pole-zero map close to the imaginary axis for the linearized plant and closed-loop system.

Figure 7

Figure 7. Magnitude response of the transfer functions from the wind disturbance to the desired accelerations.

Figure 8

Figure 8. Wind disturbance rejection experiment. (a) Octocopter station-keeping in the boundary layer wind tunnel, University of Auckland. (b) RMS error of the position norm. (c) RMS rotation error. (d) Mean RMS of the motor PWM signals.

Figure 9

Figure 9. Tilted-rotor octocopter response to a step change in desired vectored-thrust acceleration in altitude hold mode. (a) Desired normalized horizontal accelerations, (b) Attitude, (c) Translational acceleration, (d) and motor PWM signals.