Keywords

6.1 Introduction

In recent years the concept of autonomous helicopter controlling has gained a big acceleration, because of their vertical take-off/landing advantages and hovering. Although the coupled and nonlinear dynamics of the helicopter makes the attitude control difficult, numerous control techniques are applied to perform missions like hovering, aggressive manoeuvring, course keeping etc. But conventional techniques like PD or PID becomes insufficient to control such a platform. Even for an experienced engineer it is hard to regulate considerable amount of parameters of the 6 of freedom helicopter. In the literature, among the control methods that are applied to helicopters LQR is a very efficient and relatively easy way to utilize.

Despite the fact that many researchers applied optimal control techniques to small scale helicopters [1], there is relatively few studies about full envelope helicopter control. Though, in war/tactical simulators it is necessary for the full envelope platforms have middle/high fidelity relative to real helicopters. The helicopter members of the simulator must hover, take-off and follow a path, etc. So this study aims to clarify the main points of modelling, trajectory/attitude control of the helicopter by LQR and contribute the literature about this problem. In future researchers will easily be able to integrate this model to their simulators.

6.2 Manual Control of Helicopter

Due to the strong coupling between the longitudinal and lateral motion of the helicopter, the work of the pilot is harder than an aircraft pilot. Pilot should simultaneously control three controllers, collective, cyclic, and tail pedals. Basically with collective controller pilot can adjust the altitude. By cyclic controllers pilot can change the angle of blades of main rotor so longitudinal and lateral motion can be performed. By feet pedals angle of the blades of the tail rotor is changed so yaw motion is performed. Any mistake can cause the collapse of the platform. In this paper, owing to the optimal control methods, the controller gains will be hold at the optimum values. These inputs will be defined in this study as θ0mr , a 1b 1, θ0tr respectively.

6.3 Mathematical Modelling of Helicopter

6.3.1 Coordinate Frames and Transformations

Basically two frames are needed to demonstrate the motion of the helicopter, body fixed and earth fixed frames. Force, moment and other effects act on the body frame. The origin of body fixed frame is center of gravity of the platform, and it moves with the motion of the fuselage. In this frame, x shows longitudinal, y shows lateral, and z shows up/down movement. In the latter coordinate system, x points the north, y points east, and z points the center of the earth. Earth frame notation is necessary for the calculation of the displacements (Fig. 6.1).

Fig. 6.1
figure 1_6figure 1_6

Helicopter’s two main frames

To transform between body and earth frames, orthonormal rotation matrix R is used. Motion equations are multiplied with R, which is the result of the rotation by Euler angles. Yaw, pitch, roll rotation order is the standard in aircraft modelling [2]. As c\(\Theta \) shows cos(\(\Theta \)) and s\(\Theta \) shows sin(\(\Theta \)) two rotation matrices can be shown as follows:

Body frame to earth frame:

${ R}_{eb} = \left [\begin{array}{@{}c@{\quad }c@{\quad }c@{}} c\Theta c\Psi \quad &s\Phi s\Theta c\Psi - c\Phi s\Psi \quad &c\Phi s\Theta c\Psi + s\Phi s\Psi \\ c\Theta s\Psi \quad &s\Phi s\Theta s\Psi + c\Phi c\Psi \quad &c\Phi s\Theta s\Psi - s\Phi c\Psi \\ -s\Theta \quad & s\Phi c\Theta \quad & c\Phi c\Theta \\ \quad \end{array} \right ]$
(6.1)

6.3.2 Dynamic Equations of Motion

By assuming that the platform as a rigid body, any two points on the helicopter doesn’t change during the mission. The fuselage can make two types of movements: Translational and rotational. They define change in position and rotate around an axis respectively.

Translational motion, which is the motion of the center of gravity, can be defined by Newton’s second law and Coriolis Effect. Linear accelerations along x, y, and z axes can be defined as:

$\begin{array}{rcl} \left [\begin{array}{l} \dot{u} = vr - qw + \dfrac{{F}_{x}} {m} \\ \dot{v} = pw - ur + \dfrac{{F}_{y}} {m} \\ \dot{w} = uq - pv + \dfrac{{F}_{z}} {m}\\ \end{array} \right ]& &\end{array}$
(6.2)

Angular accelerations around x, y, and z axes can be defined as:

$\begin{array}{rcl} \left [\begin{array}{l} \dot{p} = qr\dfrac{{I}_{yy} - {I}_{zz}} {{I}_{xx}} + \dfrac{{M}_{x}} {{I}_{xx}} \\ \dot{q} = pr\dfrac{{I}_{zz} - {I}_{xx}} {{I}_{yy}} + \dfrac{{M}_{y}} {{I}_{yy}} \\ \dot{r} = pq\dfrac{{I}_{xx} - {I}_{yy}} {{I}_{zz}} + \dfrac{{M}_{z}} {{I}_{zz}}\\ \end{array} \right ]& &\end{array}$
(6.3)

6.3.3 Kinematic Equations

To represent the motion of the helicopter with respect to earth fixed frame, kinematic equations must be used. For translational kinematics, relation between body and earth fixed frame is as follows, where x E , y E , z E identifies position of the helicopter with respect to earth-fixed frame.

$\frac{dy} {dx}\left [\begin{array}{c} {x}_{E} \\ {y}_{E} \\ {z}_{E}\\ \end{array} \right ] = {R}_{eb}\left [\begin{array}{c} {u}_{B} \\ {v}_{B} \\ {w}_{B}\\ \end{array} \right ]$
(6.4)

Rotational kinematic equations of helicopter are as fallows, where ϕ, θ, ψ defines Euler angles of roll, pitch, and yaw respectively.

$\left [\begin{array}{c} \dot{\phi } = p +\tan (\theta )\left [q\sin (\phi ) + r\cos (\phi )\right ] \\ \dot{\theta } = q\cos (\phi ) - r\sin (\phi ) \\ \dot{\psi } = \left [q\sin (\phi ) + r\cos (\phi )\right ]\sec (\theta )\\ \end{array} \right ]$
(6.5)

6.3.4 Force and Moments Acting on Helicopter

In order to represent the motion of the helicopter, force and moment effects must be taken into account.

Helicopter can be modeled by combining five subsystems: main-rotor, fuselage, empennage (consist of horizontal stabilizer and vertical fin), tail rotor and engine [4]. To define the force and moment effects originated from main rotor, tail rotor, gravity and drag on main rotor; mr, tr, g, and d subscripts are used respectively.

$\begin{array}{l} \left [\begin{array}{c} {F}_{x} = {X}_{mr} + {X}_{tr} + {X}_{g} \\ {F}_{y} = {Y }_{mr} + {Y }_{tr} + {Y }_{g} \\ {F}_{z} = {Z}_{mr} + {Z}_{tr} + {Z}_{g} \\ L = {L}_{mr} + {L}_{tr} + {L}_{d} \\ M = {M}_{mr} + {M}_{tr} + {M}_{d} \\ N = {N}_{mr} + {N}_{tr} + {N}_{d}\\ \end{array} \right ] \\ \\ \end{array}$
(6.6)

As T mr and T tr shows main and tail rotor thrust, a1 and b1 shows longitudinal flapping angle and lateral flapping angle respectively, we obtain combined force equation matrix:

$\left [\begin{array}{c} {F}_{x} \\ {F}_{y} \\ {F}_{z}\\ \end{array} \right ] = \left [\begin{array}{c} -{T{}_{mr}}^{{_\ast}}\sin ({a}_{1}) -\sin {(\theta )}^{{_\ast}}mg \\ {T{}_{mr}}^{{_\ast}}\sin ({b}_{1}) + {T}_{tr} +\sin {(\phi )}^{{_\ast}}\cos {(\theta )}^{{_\ast}}mg \\ -{T{}_{mr}}^{{_\ast}}\cos {({b}_{1})}^{{_\ast}}\cos ({a}_{1}) +\cos {(\phi )}^{{_\ast}}\cos {(\theta )}^{{_\ast}}mg\\ \end{array} \right ]$
(6.7)

As h mr , h tr represents distance between cog and main/tail rotor along z axis, l mr , l tr represents distance between cog and main/tail rotor along x axis, Q mr defines counter torque that comes from the drag of main rotor, we can obtain combined torque equation matrix:

$\left [\begin{array}{c} {\tau }_{x} \\ {\tau }_{y} \\ {\tau }_{z}\\ \end{array} \right ] = \left [\begin{array}{*{20}c} {Y{ }_{mr}}^{{_\ast}}{h}_{mr} - {Z{}_{mr}}^{{_\ast}}{y}_{mr} + {Y{ }_{tr}}^{{_\ast}}{h}_{tr} + {Q{}_{mr}}^{{_\ast}}\sin ({a}_{1}) \\ -{X{}_{mr}}^{{_\ast}}{h}_{mr} - {Z{}_{mr}}^{{_\ast}}{l}_{mr} - {Q{}_{mr}}^{{_\ast}}\sin ({b}_{1}) \\ {X{}_{mr}}^{{_\ast}}{y}_{mr} + {Y{ }_{mr}}^{{_\ast}}{l}_{mr} - {Y{ }_{tr}}^{{_\ast}}{l}_{tr} + {Q{}_{mr}}^{{_\ast}}\cos {({a}_{1})}^{{_\ast}}\cos ({b}_{1})\\ \end{array} \right ]$
(6.8)

By using variables above nonlinear mathematical model can be build. To apply a linear controller the model must be linearized about certain operating points which will be covered in next section.

6.3.5 Trimming and Linearization

Nonlinear motion equations must be linearized about certain operating points. To increase the fidelity of the model eight trim points (0, 20, 40, 60, 80, 100, 120 and 140 knots) have been used. First assuming that linear and angular accelerations are zero; trimming conditions are obtained. This algorithm changes conditions until ϕ, θ, a 1 and b 1 reaches to steady state value in our desired flight condition.

By using Taylor’s series expansion, external forces acting on platform become linear functions of perturbed states. Total force along x axis, by the advantage of small perturbation theory (x = x e + Δx), can be written as follows:

$\begin{array}{rcl} & & \left [{F}_{x} = X = {X}_{e} + \frac{\partial x} {\partial u}\Delta u + \frac{\partial x} {\partial w}\Delta w + \frac{\partial x} {\partial q}\Delta q + \frac{\partial x} {\partial \theta }\Delta \theta + \cdots \right ] \\ & & \left [X = {X}_{e} + {X}_{u}\Delta u + {X}_{w}\Delta w + {X}_{q}\Delta q + {X}_{\theta }\Delta \theta + \cdots \right ] \end{array}$
(6.9)

If we consider that the motion can be described nonlinearly as \(\dot{x} = F(x,u,t)\), the linearized model can be defined as \(\dot{x} = Ax + Bu\), where \(x = \left [\begin{array}{cccccccc} u&w&q&\theta &v&p&\phi &r\\ \end{array} \right ]\) and \(u = \left [\begin{array}{cccc} {\theta }_{0mr}&{a}_{1} & {b}_{1} & {\theta }_{0tr}\\ \end{array} \right ]\).

The coefficients like X u , X w , are called stability derivatives in flight dynamics.

The result of these formulations can be found as A and B matrices.

6.3.6 Obtaining the Stability Derivatives

Stability derivatives can be calculated by using numerical or analytical methods. By using platform’s main characteristics [5, 6] all derivatives can be figured. For example X u can be found analytically by the equations below:

$\left [\begin{array}{l} \dfrac{\partial {X}_{mr}} {\partial u} = \dfrac{\partial (T{a}_{1})} {\partial u} = \dfrac{\partial T} {\partial u}{a}_{1} + T \dfrac{\partial {a}_{1}} {\partial u} \cdots \\ \dfrac{\partial T} {\partial u} = \rho {(\Omega R)}^{2}\pi {R}^{2}\dfrac{\partial {C}_{T}} {\partial u} \cdots \\ \end{array} \right ]$
(6.10)

Calculation of other derivatives was not mentioned in this paper. Further formulae can be found from [4]. For control study the stability derivatives of the PUMA type helicopter was used by author.

6.4 Controller Design

Helicopters which are open loop unstable must be stabilized and controlled carefully (Figs. 6.2 and 6.3).

Fig. 6.2
figure 2_6figure 2_6

Open loop step response

Fig. 6.3
figure 3_6figure 3_6

Block diagram of controllers

Open loop system’s inputs are deflected up to full angle and a step input is put in the first second. The speed responses of the system on each axis can be seen in Fig. 6.4.

Fig. 6.4
figure 4_6figure 4_6

Comparisons of u, w, and v

As seen in Fig. 6.5 proposed optimal controllers consist of three subsystems. State feedback controller, state integrator and PI controller. And gain scheduling is used to reflect the change in platform dynamics with respect to the forward velocity.

Fig. 6.5
figure 5_6figure 5_6

Resultant velocities on three axes

6.4.1 State Feedback Controller

Full-state feedback control algorithm tries to minimize the performance index (J), where “x” shows states, “u” inputs, Q and R are weighting matrices,

$J = \frac{1} {2} \int\limits_{0}^{\infty }(xQ{x}^{T} + uR{u}^{T})dt$
(6.11)

To decide appropriate weighting matrices, Bryson’s rule is used [8]. In this rule weights are calculated with the inverse of to the maximum available state/input value’s square.

By checking the set/rise time, overshoot and controlling effort; weights are tuned. By solving steady state Riccati equation, K gain matrix calculated offline. In the simulation input is calculated in each time step by u = − Kx.

6.4.2 State Integrator

Full state feedback control gives adequate results. But controller will regulate the dynamical system state values to zero. For tracking control of the helicopter, error between reference and actual states must be taken into account [7]. So the error term is defined as \(\dot{e} =\dot{ {x}}_{\mathit{desired}} -\dot{ {x}}_{\mathit{actual}}\). After integrating \(\dot{e}\), e is obtained. Then new control input becomes \(u = {K{}_{i}}^{{_\ast}}e - {K}^{{_\ast}}\dot{x}\).

Comparison of the reference and actual longitudinal, vertical and lateral speed can be seen from figure below respectively. Controller tracks reference speed values successfully.

6.4.3 PI Controller

After controlling the states and setting that values according to the reference states, for position control, which has slower dynamics than attitude control a proportional-integral feedback controller is used. Position error is calculated as e pos = [x, y, z] desired − [x, y, z] actual . By using classical \({K{}_{P}}^{{_\ast}}{e}_{\mathit{pos}} + {K}_{I} \int \nolimits \nolimits {e}_{\mathit{pos}}\,\mathit{dt}\) formula the trajectory control is realized.

6.5 Simulations

For testing the controllers following two scenarios are formed.

6.5.1 Movement to Point

  • Initial point = [x  z  y] = [0  0  0]

  • Target point = [500  − 200  100] m

  • Reference velocities = [30  − 10  5] m/s (Figs. 6.56.8)

    Fig. 6.6
    figure 6_6figure 6_6

    Resultant distances on three axes

    Fig. 6.7
    figure 7_6figure 7_6

    Control efforts

    Fig. 6.8
    figure 8_6figure 8_6

    3D view of the motion

6.5.2 Movement Through Waypoints

For testing the controllers a waypoint scenario is formed. Initial point is set as [x  z  y] = [0  0  0] m.

  • Four waypoints were selected as follows.

  • Waypoint 1 = [1000 400 0]

  • Waypoint 2 = [0 800 0]

  • Waypoint 3 = [ − 1000 400 0]

  • Waypoint 4 = [0 0 0]

  • Commanded composite velocity (of u and v) is 20 m/s.

In Fig. 6.9, squares show waypoints, lines show the actual way of the helicopter.

Fig. 6.9
figure 9_6figure 9_6

2D view of motion through waypoints

6.6 Conclusion

To control an unmanned air vehicle, kinematics, dynamics and mathematical modelling of the platform was examined in detail. Optimal and classical control techniques are applied to achieve the missions.

Basic results of the study and future work can be summarized as follows:

  • A platform which has strong coupling affects can effectively be controlled by LQR methods. Fast dynamics and control efforts can easily be optimized to reflect the real motion of the helicopter in simulators.

  • For full envelope platforms, PI control is sufficient to control slow dynamics like position control.

  • In future obstacle avoidance algorithms can be integrated to these works to use in tactic environment.

  • Disturbance scenarios can be added to the simulations to increase reality.

  • Intelligent and/or model based controller techniques can be applied to helicopter. These controllers can be compared with the optimal techniques.