Next Article in Journal
Analysis and Prediction of Carsharing Demand Based on Data Mining Methods
Next Article in Special Issue
Optimal Coronavirus Optimization Algorithm Based PID Controller for High Performance Brushless DC Motor
Previous Article in Journal
Twenty-Four-Hour Ahead Probabilistic Global Horizontal Irradiance Forecasting Using Gaussian Process Regression
Previous Article in Special Issue
A PID Parameter Tuning Method Based on the Improved QUATRE Algorithm
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Optimised Tuning of a PID-Based Flight Controller for a Medium-Scale Rotorcraft

by
Lindokuhle J. Mpanza
*,† and
Jimoh Olarewaju Pedro
School of Mechanical, Industrial and Aeronautical Engineering, Faculty of Engineering and The Built Environment, University of the Witwatersrand, Johannesburg 2000, South Africa
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Submission received: 12 April 2021 / Revised: 8 May 2021 / Accepted: 9 May 2021 / Published: 3 June 2021
(This article belongs to the Special Issue Algorithms for PID Controller 2021)

Abstract

:
This paper presents the parameter optimisation of the flight control system of a singlerotor medium-scale rotorcraft. The six degrees-of-freedom (DOF) nonlinear mathematical model of the rotorcraft is developed. This model is then used to develop proportional–integral–derivative (PID)-based controllers. Since the majority of PID controllers installed in industry are poorly tuned, this paper presents a comparison of the optimised tuning of the flight controller parameters using particle swarm optimisation (PSO), genetic algorithm (GA), ant colony optimisation (ACO) and cuckoo search (CS) optimisation algorithms. The aim is to find the best PID parameters that minimise the specified objective function. Two trim conditions are investigated, i.e., hover and 10 m/s forward flight. The four algorithms performed better than manual tuning of the PID controllers. It was found, through numerical simulation, that the ACO algorithm converges the fastest and finds the best gains for the selected objective function in hover trim conditions. However, for 10 m/s forward flight trim, the GA algorithm was found to be the best. Both the tuned flight controllers managed to reject a gust wind of up to 5 m/s in the lateral axis in hover and in forward flight.

1. Introduction

One of the four fundamental principles of the Fourth Industrial Revolution (4IR) is the decentralisation of decisions for machines. This means increased autonomy of systems to make their own decisions in order to perform specific tasks without human intervention or supervision, especially in the presence of uncertainty and external disturbances [1]. Unmanned aerial vehicles (UAVs) have been at the forefront of autonomous systems, with specific applications already demonstrated in the military environment, such as surveillance, reconnaissance, evacuation and payload delivery, and civil applications such as filming, crop dusting, parcels and medical aid delivery [2]. These tasks require the employment of a rotorcraft UAV, because rotorcraft have the capacity for vertical takeoff and landing, hovering in place, flying backwards and side-slip. They are useful in situations where fixed-wing aircraft fail to perform, such as cluttered areas, overgrown fields and dangerous industrial areas including nuclear plants and offshore oil rigs [3].
However, a rotorcraft is a highly nonlinear, multi-input, multi-output system. It is also characterised by high coupling with a larger number of dynamics that cannot be modelled explicitly. This system is also inherently unstable, meaning that, once disturbed from equilibrium, it does not return unless an external force is introduced. This makes the achievement of the demanded autonomy a daunting challenge [4].
This performance specification for autonomy has resulted in high complexity in the rotorcraft flight control system. Significant effort has been devoted to improving the performance and reliability of flight control systems in the past two decades [1], and the increase in computational power and communication bandwidth has made possible some of the improvements that have eluded control engineers in recent years [5].
As such, a number of control strategies have been presented for the control of rotorcraft, including a proportional–integral–derivative (PID) controller and its gain scheduling counterpart [6,7]. This design methodology, also referred to as classical, requires linear approximation of the rotorcraft around a selected operating region. This is due to the fact that PID controllers are normally single-input single-output (SISO). However, these methods only work well under the simplifying assumptions of a linear system. Despite this, PID controllers have been successfully implemented in rotorcraft flight control systems.
Following the advances in the development of computer systems for flight control, there was a rise in the application of “modern control” systems such as the linear quadratic regulator (LQR) [8,9] and H [10]. These methods are difficult to implement practically [6]. Other methods, such as nonlinear inverse dynamics [9], including feedback linearisation [11], adaptive control [12] and sliding mode controllers [13], have also been applied with moderate success.
The problem with PID has been identified as poor tuning, which means that most of the controllers currently in operation have been poorly tuned. This results in biased judgment against the PID controllers themselves. The best known method for tuning PID controllers is Ziegler–Nichols, based on empirical rules. This method does not work well for multi-loop systems such as rotorcraft. Significant effort has recently been invested in optimal tuning of PID controllers [14,15,16] and other controllers in general [17].
Zhao et al. [18] applied cuckoo search to optimise PID parameters on a semi-active suspension system with the objective of operating at a desired damping force. For this, they conducted numerical simulations and experimental study on a quarter-car rig and found that the CS-PID does improve ride comfort. Hill et al. [19] investigated the application of GA to optimise a PID controller and a pseudo-derivative controller (PDF) to control a tall building elevator. The optimised controllers showed improved performance when compared to the manually tuned ones, which were not able to meet the settling time requirement.
In the aircraft industry, the selection of controller gains is conducted by a committee comprising the flight control designers and the test pilots making reference to the Cooper–Harper rating scale and/or the ADS-33E. This results in sub-optimal gains for the aircraft.
George et al. [20] presented an autopilot system based on optimised PID controllers to reduce the pilot workload. The performance criteria were derived from DEF-STAN 00-0970 and the ADS-33E version of settling time. Simulations were conducted on a linearised model and showed convergence back to trim condition in both roll and pitch. Yin et al. [21] also presented a linear model of a rotorcraft and applied a two-loop PID control system. The controller was tested on a test rotorcraft platform and was found to correctly stabilise the aircraft attitude, which is the function of the inner loop. No outer-loop test results were presented. Dai et al. [22] developed a three-loop PID control system containing the attitude, velocity and position loops. On a linearised model, the PID gains were optimised using PSO. The optimisation was only conducted on the outer loop and the other loops were tuned manually, thereby reducing the number of optimisation parameters. The methods for flight control of single-rotor helicopters presented in the literature do not include optimisation in general. If they do, they are based on linearised models. However, linearised models have explicit optimal points, which defeats the purpose of using optimisation algorithms.
Nonlinear optimisation has been applied to quadrotors. Noordin et al. [23] presented a nonlinear quadrotor model and used PSO to optimise PID controllers for roll, pitch, yaw and height. The PID controllers were then able to stabilise the quadrotor. Moreso, the investigation revealed that the SAE fitness function gave the best aircraft performance. Abduo et al. [24] investigated the PID control of a nonlinear quadrotor tuned with nature-inspired algorithms. These were then compared in numerical simulations to show the differences between the algorithms. This study used the ISE perfomance function, which was proven to give an acceptable rise time and overshoot. In another similar study, Cedro et al. [25] used an SAE performance function including the input signals scaled by a penalty factor ρ .
However, single-rotor helicopters are highly coupled and more dynamically complex than quadrotors. This could be the reason that this type of optimisation has not been attempted so far.
In this paper, we propose that the flying and control objectives of the aircraft be defined analytically in an objective function and then optimisation algorithms be used to minimise the cost to find the best PID controller parameters applied directly onto a nonlinear helicopter. Therefore, the contributions of this paper are: (1) to design a closed-loop flight control system for the rotorcraft that closely relates to the pilot control based on six concurrent PID controllers; (2) and to develop a comparative study of computational intelligence optimisation algorithms to find the best PID controller parameters for the given flight regimes, also showing robustness to external disturbances. Even though related work has been presented for other types of aircraft, to the best of the authors’ knowledge, this has not been investigated for a single-rotor helicopter.
The rest of the paper is arranged as follows: Section 2 provides an overview of the system and the development of the 6-DOF rotorcraft model. The proposed flight controller and the optimisation algorithms are presented in Section 3. Section 4 presents controller validation through simulations and monitoring of the model of the rotorcraft and comparison of the different optimisation algorithms. Section 5 concludes the paper and offers recommendations for possible future investigations.

2. System Overview and Mathematical Modelling

An accurate mathematical model is required for the development of model-based controllers. Assumptions simplifying the model development processes are as follows:
  • The rotorcraft is considered as a six-DOF rigid body;
  • Variations in the properties of the air in which the rotorcraft is flying are negligible;
  • Variations in available rotor force due to air channel interaction are negligible;
  • Variations in inflow velocity across the rotorcraft rotor disc are negligible;
  • Locations for the rotorcraft centre of mass and centre of gravity are coincident.

2.1. Notation and Preliminaries

In order to understand the derivations that follow, it might be useful to recall the following symbols:
σ : rotor solidity; a: lift curve slope;
μ : advance ratio; λ : inflow ratio;
v: induced velocity; and ρ : air density.

2.2. Reference Frames

The rotorcraft dynamics are obtained using the Newton–Euler approach. To make this possible, two reference frames are essential. An Earth-fixed reference frame F E = { R O , x , y , z } is used to represent an inertial reference frame. The second frame of reference is a body-fixed reference frame F B = { R B O B , x B , y B , z B } . The centre of this reference frame O B is assigned to coincide with the rotorcraft’s centre of gravity (CG). In this case, ξ = [ x y z ] T is the position of the rotorcraft’s CG with respect to the Earth-fixed reference frame. The rotational angles (i.e., Euler angles) are η = [ ϕ θ ψ ] T of the body-fixed reference frame with respect to the Earth-fixed reference frame. The translational and rotational (angular) velocities of the moving body-fixed reference frame are given by v B = [ u v w ] T and ω B = [ p q r ] , respectively.

2.3. Kinematics

To transform from the body-fixed reference frame to the Earth-fixed reference frame and vice versa, we define R, the transformation matrix represented in Euler angles, as follows:
R ( η ) = R ψ ( ψ ) R θ ( θ ) R ϕ ( ϕ )
R ( η ) = cos ψ cos θ cos ψ sin θ sin ϕ sin ψ cos ϕ cos ψ sin θ cos ϕ + sin ψ sin ϕ sin ψ cos θ sin ψ sin θ sin ϕ + cos ψ cos ϕ sin ψ sin θ cos ϕ cos ψ sin ϕ sin θ cos θ sin ϕ cos θ cos ϕ
The position and the velocity in the body-fixed reference frame relate to the inertial reference frame in the following:
ξ ˙ = R v B
This is a special orthogonal group matrix S O 3 with interesting properties. For more about the S O 3 properties, consult [4]. For orientation, we define T , the differential transformation matrix, as follows:
T = 1 sin ϕ tan θ cos ϕ tan θ 0 cos ϕ sin ϕ 0 sin ϕ / cos θ cos ϕ / cos θ
The orientation velocity vector is transformed as follows:
η ˙ = T ω B
This transformation matrix exposes one of the drawbacks of using Euler angles: the fact that T has a singularity at ± 90 . This is not a problem in this investigation as the manoeuvres of interest are not too aggressive. For the design of aggressive and acrobatic rotorcraft, it is better to use Quaternions (see [26,27] for more information).

2.4. Dynamics

The force of gravity acting at the CG of the rotorcraft, F g = m g , does not act along the z-axis of the body-fixed reference frame and has to be transformed from the Earth-fixed reference frame F E = { R O , x , y , z } to the body-fixed reference frame using R in Equation (2). The total sum of forces acting on the rotorcraft within the body-fixed reference frame F B = { R B O B , x B , y B , z B } may thus be expressed in the Newton–Euler rigid-body equations of motions for a rotorcraft with mass m and the moment of inertia I as follows:
m d v B d t + m ( ω B × v B ) = F
I d ω B d t + ( ω B × I ω B ) = M
The sum of all external forces and moments that act on the rotorcraft is combined in the triple F = [ X Y Z ] and M = [ L M N ] , respectively. In the following, we discuss the contributions of the different rotorcraft subsystems to the force and the moment vectors. The contributing subsystems are the main rotor, tail rotor, fuselage, horizontal and vertical stabilisers. The force of gravity is transformed into the body-fixed reference frame using R T . These forces are illustrated in Figure 1.

2.5. Thrust Forces

The external forces acting on the rotorcraft can be summarised as the sum of combinations from different subsystems as follows:
X = X M + X T + X F
Y = Y M + Y T + Y F + Y V
Z = Z M + Z T + Z F + Z H
where the subscripts M, T, H, V and F are the main rotor, tail rotor, horizontal stabilizer, vertical stabiliser and fuselage, respectively. The simplified thrust produced by the main rotor is given by [28]:
T M = C T ρ A ( Ω R ) 2
C T = σ a 2 ( 1 3 + μ z 2 2 ) θ 0 μ λ 2
where T M , C T , A, R, Ω and θ 0 are the developed rotor thrust, the thrust coefficient, the area of the rotor disc, the radius of the rotors, the rotor speed and the collective pitch of the blades, respectively. The other symbols are as defined in Section 2.1. In a similar procedure used for main rotor, the tail rotor thrust, T T , is derived.
The total forces generated by the main rotor and the tail rotor are described as follows [4]:
X M = T M sin a l c
Y M = T M sin b l s
Z M = T M cos a l c cos b l s
Y T = T T
where a l c and b l c are the flapping angles in the horizontal and lateral direction, respectively.

2.6. Rolling and Pitching Moments

The external moments acting about the rotorcraft CG are summarised as follows:
L = L M + Y M h M + Z M y M + Y T h T + Y V h V + L F
M = M M X M h M + Z M l M + M T Z H l H X V h V + M F
N = N M Y M l M Y T l T Y V l V + N F
where the subscripts M, T, H, V and F are as described above. The main rotor torque is a result of the blade stiffness at the root. The equation for the main rotor torque is [28]:
C Q M = Q M ρ ( R Ω ) 2 π R 3
In a similar procedure used for main rotor thrust, the main rotor torque coefficient C Q M is found to be:
C Q M = C T ( λ 0 μ z ) + C D 0 σ 8 1 + 7 3 μ 2
where C D 0 is the drag zero-lift coefficient. The total moments generated by the main rotor and the tail rotor are described as follows [29]:
L M = L M b b l s Q M sin a l c
M M = M M a a l c Q M sin , M T = Q T b l s
N M = Q M cos a l c cos b l s
M T is the tail rotor contribution to the pitching moment.

2.7. System Performance Specifications

The goal of the present paper is focused on the development and investigation of an efficient controller for the rotorcraft. Five different controllers are developed, analysed and compared—that is, one manually tuned PID controller and four other PID controllers tuned using optimisation algorithms, as detailed in the next subsection. The manually tuned PID controller is used for benchmarking purposes. A successful controller must meet the following performance specifications [4]:
1.
The controller must exhibit general stability;
2.
Overshoot should be kept at less than 5%;
3.
Settling time should be less than 10 s;
4.
Steady-state error should be within ± 1 × 10 2 rad and ± 1 × 10 1 m.
In order to develop the best PID controller, the following objective function based on the integral of squared error (ISE) is used:
J = 1 T 0 T [ x d x x m a x 2 + y d y y m a x 2 + z d z z m a x 2 + θ d θ θ m a x 2 + ϕ d ϕ ϕ m a x 2 + ψ d ψ ψ m a x 2 + δ c o l δ c o l m a x 2 + δ l o n δ l o n m a x 2 + δ l a t δ l a t m a x 2 + δ p e d δ p e d m a x 2 ] d t ,
where x d , y d and z d are the desired positions of the rotorcraft with respect to the Earth-fixed reference frame, θ d , ϕ d and ψ d are the desired Euler angles of the rotorcraft, δ c o l , δ l o n , δ l a t and δ p e d are the collective, longitudinal cyclic, lateral cyclic and tail rotor collective inputs, respectively.

3. PID Control Development

The PID control of the rotorcraft is developed, coupling the roll and pitch angles with the horizontal translation of the rotorcraft. This involves developing an inner loop for the faster dynamics and an outer control loop for the slower dynamics. Preferably, the tuning process for the controller should start in the inner loop, in order to ensure that the rotorcraft is rotationally stable, before proceeding to the outer loop. The outer loop is responsible for the control of the position of the rotorcraft with respect to the Earth-fixed reference frame. The x d , y d and z d reference signals are passed into the outer loop transformation, R , which then passes these signals to the inner control loop. As such, these outer loop signals must be tuned to represent the desired roll and pitch angles in the body-fixed reference frame of the rotorcraft as shown in Figure 2.
The structure of the PID controller is described as follows:
u i ( t ) = K p i e 1 ( t ) + K i i e 1 ( t ) d t + K d i d e 1 ( t ) d t .
where the error signal, e 1 ( t ) = y d 1 y 1 , is the difference between the desired response, y d 1 , and the actual output, y 1 . The signal u i ( t ) is used to drive the corresponding actuators in the swashplate.
The first PID controller parameters are found using the manual tuning method. Although this method is effective and has been proven in applications, for the system with multiple loops and a larger number of gains, 18, it becomes tedious and time consuming [30]. The rest of the controllers are tuned using computational intelligence optimisation techniques. The simulation results based on these controllers are given in the next section. The controller optimisation algorithms are also discussed in the next section.

3.1. Controller Optimisation Strategies

In order to improve the tuning of controller parameters, computational intelligence techniques are employed. These techniques include particle swarm optimisation (PSO), genetic algorithm (GA), ant colony optimisation (ACO) and cuckoo search (CS), which are the focus of this paper. These techniques are used to find the parameters K p , K d , K i for each PID controller. Figure 3 shows the system architecture used for tuning the PID gains using optimisation techniques.
An optimisation problem is designed to satisfy the following equation:
P = ( S , f ) ,
where S n is the set of infinite solutions called the solution space and f is an n-dimensional real function [31] such that:
f : S .
The goal of each optimisation strategy is to find s S such that it minimises the objective function given in Equation (25). This is given mathematically as finding the solution s S : f ( s ´ ) f ( s ) in finite time.
Each optimisation technique is used to find s i = { K p , K d , K i , } and s = { s 1 s 2 s 3 s 4 s 5 s 6 } , called the candidate solution, iteratively. At each iteration, the candidate solution is evaluated with respect to the objective function in Equation (25). Since the optimisation is done after the initial tuning via trial and error, this solution is used to initialise the search algorithms, which means that even when optimisation tools outperform manual tuning, this result is still useful towards the final optimisation outcome.

3.2. Particle Swarm Optimisation

Particle swarm optimisation (PSO) is an optimisation algorithm that mimics the social behaviour of a group of animals as a unit system, such as a flock of birds, swarm of insects, school of fish, to name a few. The ideas of PSO was first propounded by Eberhart and Kennedy in 1995 and it has been very popular among evolutionary algorithms, only second to GA [15]. PSO uses a population of particles that are flying through the solution space at a given velocity. The best solution is found by following the optimal particle in the solution space. Following a particle is in the true sense, since each PSO particle has velocity and position. The velocity of each particle is defined as follows:
v i ( k + 1 ) = m v i ( k ) + c 1 . r 1 ( p b e s t i ( k ) p i ( k ) ) + c 2 . r 2 . ( g b e s t p i ( k ) )
where v i is the i-th particle velocity, p i is the current particle position, p b e s t is the best particle solution so far, g b e s t is the best solution in the global set of the particles. The parameter m is the velocity gain used for changing exploration into exploitation.
The velocity of the particle moves in the direction of p b e s t and eventually towards g b e s t . The particle moves to the next position according to the following equation:
p i ( k + 1 ) = p i ( k ) + v i ( k + 1 )
The iteration is completed after all particles have moved. The stopping criterion is when the optimal solution has been found or the maximum number of iterations has been reached.
Fan and Jen [32] compare the traditional PSO with a newly developed Enhanced Particle Search (EPS) PSO with co-swarms that are able to share information between particles. For this study, however, the PSO algorithm used can be found in [33]. In the setup of the PSO, the parameters that are used are shown in Table 1.

3.3. Genetic Algorithm

GA is a computational technique developed to mimic evolution in a natural environment by natural selection and is based on Darwin’s theory of “survival of the fittest.” GA is a heuristic optimisation tool used to find the most optimal solution in a solution space S of complex problems in a relatively short time. Candidate solutions s S are called chromosomes and are represented as binary-coded or real-coded strings. At each generation, new offspring chromosomes are created through the parent reproduction and mutation. The process is repeated until termination conditions are met.
Each of the GA processes is described as follows (Algorithm 1) [14,30]:
Algorithm 1: Genetic algorithm optimisation.
Algorithms 14 00178 i001
The best GA parameters for the present problem were found by numerical experimentation and are listed in Table 2.

3.4. Ant Colony Optimisation

ACO is a population-based meta-heuristic optimisation method falling into the swarm intelligence category [33]. It was first proposed by Dorigo [34], from observing the behaviour of real ants. Mathematically, in ACO, a number of concurrent artificial ants, m, is defined. The current state of the ant, i, is a partial solution of the problem of discourse. An ant evaluates its next state move, j, based on the pheromone trails to the adjacent solutions. Once an ant has completed each jth solution search, the solution is evaluated, and then the pheromone trails are updated based on the best solution so far. This process is repeated until the termination conditions are met.
We present ACO for parameter optimisation. Since the parameters cover a continuous space, the algorithm used to search this space must be continuous as well. In [31], an ACO for continuous domains called A C O is presented. The traditional ACO search space is given by v i D i = { v i 1 , . . . , v i D i } , while the A C O search space is v i D i . The basics of the algorithms are maintained, but the internal implementation differs. Instead of using a pheromone-based probability distribution function, a probability density function (PDF) is used by employing any P ( x ) 0 x such that: P ( x ) = 1 . For this paper, Gaussian functions were chosen due to the ease of sampling. For a multi-variable optimisation problem, a kernel G i ( x ) is defined as a sum of weighted Gaussian functions equal to the number of variables as follows:
G i ( x ) = l = 1 k ω l 1 σ l i 2 π e ( x μ l i ) 2 2 ( σ l i ) 2 .
where i = 1 , , n is the number of variables, and μ l i and σ l i are the l t h solution and its standard deviation for each variable. Instead of using a pheromone matrix τ i j , a pheromone archive table T i j is used such that, for each solution, μ and σ represent the chosen solution with its standard deviation. The subscript l = 1 , , k represents current index to the archived solutions and k is an optimisation parameter, i.e., the total number of archive solutions that can be stored at any iteration. The solution at an iteration in the archive is s l = μ l 1 , μ l n . To execute the algorithm, the following steps are followed [33].
Algorithm 2: Ant colony optimisation.
Algorithms 14 00178 i002
The ACO performance is based on the selection of the number of ants m, the size k of the archive, the number of iterations to run the algorithm and the ACO parameters, where q and ζ are algorithm parameters. If q is too small, the ranking is focused on the best solution, while a larger value results in a flat, more uniform search for alternative solutions. The ζ parameter on the other end will have an equivalent effect as the ρ , the pheromone evaporation rate. The higher value of ζ will promote the forgetting of the current solution and exploration of new areas in the solution space, meaning that the convergence rate will be slower. The Algorithm 2 is said to have short-term memory [31].
The best ACO parameters for the present problem were found by numerical experimentation and are listed in Table 3. Similar to GA, ACO is a stochastic algorithm in that it converges to a different solution each time it is executed.

3.5. Cuckoo Search Algorithm

The cuckoo search algorithm was developed by Yang and Deb [35]. This search algorithm (Algorithm 3) was inspired by the breeding behaviour of cuckoo birds. Cuckoo birds are opportunistic agents that try to maximise the chance of their offspring’s survival without doing anything in terms of incubating eggs and feeding the hatchings.
The cuckoo lays its eggs in other birds’ nests. The eggs are hidden among the original eggs in the nest. Sometimes, to increase the chance of its chicks’ survival, the cuckoo might dispose of the other bird’s eggs. The cuckoo that hatches first also maximises its own chance of survival by disposing of the other eggs in the nest. The algorithm used for optimisation using cuckoo search is as follows [35].
Algorithm 3: Cuckoo search optimisation.
Algorithms 14 00178 i003
The best CS parameters for the present problem were found by numerical experimentation and are listed in Table 4.
Each egg in the nest represents a solution and a cuckoo dropping an egg in the nest represents a new solution.

4. Simulation Results and Discussion

A validation exercise based on numerical simulations was conducted in the Matlab/Simulink environment. The ODE optimisation algorithm was selected to be the Bogacki–Shampire solver with a sampling time of 1 kHz. The simulations were conducted on a Windows 10 computer with a i5 processor and 8 Gb of RAM.
The rotorcraft model was first trimmed at hover, 10 m above the ground and at low forward speed, i.e., 10 m/s. Once a steady state was achieved, the system was driven to track a sinusoidal height and step input for the x and y directions, while regulating other states and rejecting disturbances.

4.1. Trimming Results

To apply PID control on the rotorcraft, it must be trimmed. The trim states are found by solving the rotorcraft dynamic equation:
f ( x , u ) = 0
In this simulation, the trim is specified by zero translation velocities and angular rates, v I = [ 0 0 0 ] T and ω B = [ 0 0 0 ] , respectively.. This requires a set of inputs in cyclic and collective to achieve this state. The steady-state values for hover trim are shown in Table 5.
The behaviour of the rotorcraft in response to the tabulated trim values is shown in Figure 4 and Figure 5. As expected, the model is not entirely stable (rotorcraft require constant closed-loop control for stability); however, it does maintain the rotorcraft in the vicinity of the trim point. To make sure that the aircraft is stable at hover and can recover from disturbances such as wind gust and stabilise to an upright position when it is initially tilted, an active controller is used.

4.2. Controller Implementation Results

As discussed previously, tuning an inherently unstable rotorcraft is a tedious task. The prevailing methodology for designing PID-controlled rotorcraft is by linearising the model of interest and then using the available wealth of analytical tools to find the gains that meet performance specifications [36]. The other method is empirical in nature and relies on the ability to excite the system and measure the output and use the Ziegler–Nichols method to find the gains. The following, however, presents the results of PID controller gains achieved through the optimisation techniques based on computational intelligence as presented in the previous section. These are compared to the results found by manual tuning.

4.2.1. Hover

The four controllers are then tuned to minimise the objective function in Equation (25). For each optimisation algorithm, ten trials were executed. The convergence graphs of each of the four optimisation techniques are shown in Figure 6.
The best gains returned the following values of the objective function and the running times as given in Table 6. The ACO-PID completed the optimisation the fastest and had the lowest average ISE score. The gains found for the four PID controllers’ optimisation methods are given in Table 7.
The performance of these controllers is evaluated for tracking elevation around the trim height, i.e., z d = 10 ± 1 metres and unit steps wind gust for y at t = 7 s. Figure 7 and Figure 8 show a visual comparison of the controllers. The ACO-PID is superior to others, although the others are also within the performance specifications.
PID controllers tend to have better regulation than tracking due to the limited region of effectiveness. Next is the tracking of sudden changes in longitudinal displacement. The controllers are able to track a small forward speed up to 2 m/s (Figure 9 and Figure 10). However, the ACO-PID seems to perform better. It also has less overshoot, which is very desirable if the rotorcraft is performing in confined spaces. The PSO-PID is the worst-performing, with a velocity overshoot of 68%. Figure 11 shows the inputs into the rotorcraft commanded by each controller. An attempt to move the rotorcraft from trim with a velocity higher than 2 m/s results in instability.

4.2.2. Forward Speed

A well-known effect of the PID-controlled system is its loss of performance away from the trimmed condition. The tuned system was tested on how well it withstands the translation from hover to 10 m/s forward speed. Because the optimally tuned PID controllers can give performance of up to 2 m/s, after which the rotorcraft becomes unstable, a new trim position is required for forward speed. The four controllers were retuned for the 10 m/s forward flight to be the new trim condition. This trim condition is also based on Equation (32), with the exception that the v I = [ 10 0 0 ] .
The best gains returned the values of the objective function and the running times given in Table 8.
The PID controllers’ gains obtained using the proposed optimisation algorithms for 10 m/s forward flight conditions are given in Table 9.
The newly tuned PID controllers are able to keep the flight path by following the reference signal. Figure 12 and Figure 13 show the position and the velocity time history of the rotorcraft. The velocity is kept constant and the x translation increases steadily. In this experiment, the GA-PID proved to track the velocity better than the other controllers. Even though it is the best, the velocity overshoots by 11% and settles quicker than others, in less than 4 s. The rest of the controllers also traced the ramp displacement, but this was at the expense of the height of the rotorcraft. Also noteworthy is that the GA-PID did have worse performance for y direction regulation. The multi-axis and underactuation problem becomes prominent in this part of the numerical experiment as optimising one output variable comes at the expense of the other variable.

4.2.3. Robustness

Finally, the rotorcraft was perturbed with a constant gust wind to verify the robustness of the tuned PID controllers. The wind was introduced at time t = 7 s, to see if the rotorcraft would be able to return to equilibrium. Figure 14 and Figure 15 show the position and orientation of the rotorcraft when it is subjected to a 10 m/s gust wind from the starboard side. All hover PID controllers are able to recover from the gust with 5 s as shown in Figure 14. It is noted, however, that the steady-state error in height is increased. The velocity graph, in Figure 15, shows that the total lateral rotorcraft speed does change at 7 s and recovers asymptotically.
For gust perturbation in forward speed, the rotorcraft, even though it still tracks the forward speed correctly, drifts and does not recover the desired position, as shown in Figure 16. The ACO-PID seems to be more effective in its response, while the GA-PID responds the worst to gust. The hypothesis is that, due to its strict adherence to the objective function during tuning, it struggles with any effect outside the norm.
Nguyen [37] has covered, extensively, the shortcomings and perils of adaptive control on aircraft systems and their lack of amicable proofs, leading to the large number of documented experimental aircraft incidents. However, the PID gains derived in this paper are offline in nature and the computational intelligence optimisation algorithms only assist in the selection of these gains. The algorithms themselves do not form part of the final aircraft flight control system.
This also clarifies what might appear as a contradictory conclusion from the presented numerical simulations: that ACO-PID performs better for hover while the GA-PID performs better for forward flight. This does not mean that the rotorcraft flight control system will fly ACO and then change to GA, but that the results of the optimisations (i.e., the gains) are programmed to the flight controller. These gains are subjected to similar scrutiny for any PID-based flight controller gains determined through other documented and popular methods that are, albeit, not optimal.

5. Conclusions

A mathematical model of a rotorcraft was developed. Assumptions were made to simplify the calculations of thrust and torque generated by the rotors of the rotorcraft, as well as to limit the effects of surface drag on the system. Two trim conditions were investigated: hover and 10 m/s forward flight. The paper presented the use of computational intelligence optimisation techniques for tuning the PID controllers’ gains that were developed for a rotorcraft system.
It was observed through numerical simulation that the optimised PID controllers are effective around the trim point for which they were developed, with ACO-PID performing better for hover and GA-PID for forward flight. However, this conclusion is not universal and is only valid for the hover and forward flight cases investigated in this paper. The controllers are able to tolerate some deviation from this operating point, such as an increase in forward speed and when subjected to gust winds. However, they cannot be employed to control the rotorcraft through its entire flight envelope as they started to lose stability. Since the PID controller can only affect one input for every reference input, the cross-coupling effects can be noticeable when translating, for example. These effects become more pronounced as the rotorcraft moves away from the designed trim condition. Hence, different controllers need to be designed for different operating regions and gain scheduling employed to transition from one controller to the next as the region changes. However, the ACO-optimised controller seems to outperform the other optimisation algorithms both in holding the trim state and recovering from external disturbance.
A follow-up to the proposed optimised PID controller for the rotorcraft is to employ a robust nonlinear controller that not only operates in the entire flight envelope of the aircraft but is able to handle disturbance and is also tolerant to bounded uncertainties and actuator loss of effectiveness, such as a sliding mode controller.

Author Contributions

Conceptualization, L.J.M. and J.O.P.; Data curation, L.J.M.; Formal analysis, L.J.M. and J.O.P.; Methodology, L.J.M.; Software, L.J.M.; Supervision, J.O.P.; Validation, J.O.P.; Writing—original draft, L.J.M.; Writing—review & editing, J.O.P. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Huang, Y.; Zhu, M.; Zheng, Z.; Feroskhan, M. Fixed-time autonomous shipboard landing control of a helicopter with external disturbances. Aerosp. Sci. Technol. 2019, 84, 18–30. [Google Scholar] [CrossRef]
  2. Mohiuddin, A.; Tarek, T.; Zweiri, Y.; Gan, D. A survey of single and multi-UAV aerial manipulation. Unmanned Syst. 2020, 8, 119–147. [Google Scholar] [CrossRef]
  3. Marconi, L.; Naldi, R. Aggressive control of helicopters in presence of parametric and dynamical uncertainties. Mechatronics 2008, 18, 381–389. [Google Scholar] [CrossRef]
  4. Raptis, I.A.; Valavanis, K.P. Linear and Nonlinear Control of Small-Scale Unmanned Helicopters; Springer Science & Business Media: Berlin/Heidelberg, Germany, 2010; Volume 45. [Google Scholar]
  5. Chi, C.; Yan, X.; Chen, R.; Li, P. Analysis of low-speed height-velocity diagram of a variable-speed-rotor helicopter in one-engine-failure. Aerosp. Sci. Technol. 2019, 91, 310–320. [Google Scholar] [CrossRef]
  6. Budiyono, A. Advances in Unmanned Aerial Vehicles Technologies. Available online: https://www.researchgate.net/profile/Agus-Budiyono-2/publication/234119875_Advances_in_unmanned_aerial_vehicles_technologies/links/00b4952cea51940af2000000/Advances-in-unmanned-aerial-vehicles-technologies.pdf (accessed on 11 April 2021).
  7. Mo, H.; Naigang, C. A gain scheduling controller for small-scaled unmanned helicopters. In Proceedings of the 2018 Chinese Control And Decision Conference (CCDC), Shenyang, China, 9–11 June 2018; pp. 6309–6313. [Google Scholar] [CrossRef]
  8. Budiyono, A.; Wibowo, S.S. Optimal tracking controller design for a small scale helicopter. J. Bionic Eng. 2007, 4, 271–280. [Google Scholar] [CrossRef] [Green Version]
  9. Scholz, G.; Trommer, G. Model based control of a quadrotor with tiltable rotors. Gyroscopy Navig. 2016, 7, 72–81. [Google Scholar] [CrossRef]
  10. Khalesi, M.H.; Salarieh, H.; Saadat Foumani, M. System identification and robust attitude control of an unmanned helicopter using novel low-cost flight control system. Proc. Inst. Mech. Eng. Part I J. Syst. Control Eng. 2020, 234, 634–645. [Google Scholar]
  11. Nemati, A.; Kumar, M. Non-linear control of tilting-quadcopter using feedback linearization based motion Control. In Dynamic Systems and Control Conference; American Society of Mechanical Engineers: New York, NY, USA, 2014; Volume 46209, p. V003T48A005. [Google Scholar]
  12. Chikasha, P.N.; Dube, C. Adaptive model predictive control of a quadrotor. IFAC-PapersOnLine 2017, 50, 157–162. [Google Scholar]
  13. Halbe, O.; Hajek, M. Robust Helicopter Sliding Mode Control for Enhanced Handling and Trajectory Following. J. Guid. Control Dyn. 2020, 43, 1805–1821. [Google Scholar] [CrossRef]
  14. Sheng, L.; Li, W. Optimization Design by Genetic Algorithm Controller for Trajectory Control of a 3-RRR Parallel Robot. Algorithms 2018, 11, 7. [Google Scholar] [CrossRef] [Green Version]
  15. Abdalla, M.; Al-Baradie, S. Real Time Optimal Tuning of Quadcopter Attitude Controller Using Particle Swarm Optimization. J. Eng. Technol. Sci. 2020, 52, 745–764. [Google Scholar]
  16. Gomez, V.; Gomez, N.; Rodas, J.; Paiva, E.; Saad, M.; Gregor, R. Pareto Optimal PID Tuning for Px4-Based Unmanned Aerial Vehicles by Using a Multi-Objective Particle Swarm Optimization Algorithm. Aerospace 2020, 7, 71. [Google Scholar] [CrossRef]
  17. Mpanza, L.J.; Pedro, J.O. Nature-Inspired Optimization Algorithms for Sliding Mode Control Parameters Tuning for Autonomous Quadrotor. In Proceedings of the 2019 IEEE Conference on Control Technology and Applications (CCTA), Hong Kong, China, 19–21 August 2019; pp. 1087–1092. [Google Scholar]
  18. Zhao, J.; Wong, P.K.; Xie, Z.; Ma, X.; Hua, X. Design and control of an automotive variable hydraulic damper using cuckoo search optimized PID method. Int. J. Automot. Technol. 2019, 20, 51–63. [Google Scholar]
  19. Hill, I.L.R.; Mangera, M.; Parshotam, D.S.; Panday, A.; Pedro, J.O. Genetic algorithm based design of PID and PDF controllers for velocity tracking of a high-rise building elevator. In Proceedings of the 2018 SICE International Symposium on Control Systems (SICE ISCS), Tokyo, Japan, 9–11 March 2018; pp. 136–143. [Google Scholar]
  20. George, T.; Verma, V.S.; Jaiprakash, N.; Harigopal, A.; Raj, S.P.; Sampath, P. Estimation of PID Gains of Autopilot System for 5.5 Ton Class Helicopter. IFAC-PapersOnLine 2018, 51, 148–153. [Google Scholar] [CrossRef]
  21. Yin, X.; Zhang, D.; Fang, Q.; Shen, L. Research on modeling and stability control of micro unmanned helicopter. In Proceedings of the 2017 29th Chinese Control And Decision Conference (CCDC), Chongqing, China, 28–30 May 2017; pp. 6618–6622. [Google Scholar]
  22. Dai, J.; Nie, H.; Ying, J.; Zhao, Y.; Sun, Y. Modeling and Tracking Control of Unmanned Helicopter. In Proceedings of the 2020 IEEE 6th International Conference on Control Science and Systems Engineering (ICCSSE), Beijing, China, 17–19 July 2020; pp. 149–155. [Google Scholar]
  23. Noordin, A.; Basri, M.M.; Mohamed, Z.; Abidin, A.Z. Modelling and PSO fine-tuned PID control of quadrotor UAV. Int. J. Adv. Sci. Eng. Inf. Technol. 2017, 7, 1367–1373. [Google Scholar]
  24. Abdou, L.; Glida, H.E. Parameters tuning of a quadrotor PID controllers by using nature-inspired algorithms. Evol. Intell. 2019, 1–13. [Google Scholar]
  25. Cedro, L.; Wieczorkowski, K. Optimizing PID controller gains to model the performance of a quadcopter. Transp. Res. Procedia 2019, 40, 156–169. [Google Scholar]
  26. Cai, G.; Chen, B.M.; Lee, T.H. Unmanned Rotorcraft Systems; Springer: London, UK, 2011. [Google Scholar]
  27. Chen, R.; Yuan, Y.; Thomson, D. A review of mathematical modelling techniques for advanced rotorcraft configurations. Prog. Aerosp. Sci. 2021, 120, 100681. [Google Scholar]
  28. Gavrilets, V. Autonomous Aerobatic Maneuvering of Miniature Helicopters. Ph.D. Thesis, Massachusetts Institute of Technology, Massachusetts, CA, USA, 2003. [Google Scholar]
  29. Yang, B.; He, Y.; Han, J.; Liu, G. Rotor-flying manipulator: Modeling, analysis, and Control. Math. Probl. Eng. 2014, 2014, 492965. [Google Scholar] [CrossRef]
  30. Bindu, R.; Namboothiripad, M.K. Tuning of PID controller for DC servo motor using genetic algorithm. Int. J. Emerg. Technol. Adv. Eng. 2012, 2, 310–314. [Google Scholar]
  31. Socha, K.; Dorigo, M. Ant colony optimization for continuous domains. Eur. J. Oper. Res. 2008, 185, 1155–1173. [Google Scholar] [CrossRef] [Green Version]
  32. Fan, S.K.S.; Jen, C.H. An enhanced partial search to particle swarm optimization for unconstrained optimization. Mathematics 2019, 7, 357. [Google Scholar] [CrossRef] [Green Version]
  33. Engelbrecht, A.P. Computational Intelligence: An Introduction; John Wiley & Son, Ltd.: West Sussex, UK, 2007. [Google Scholar]
  34. Dorigo, M. Optimization, Learning and Natural Algorithms. Ph.D. Thesis, Politecnico di Milano, Milan, Italy, 1992. [Google Scholar]
  35. Yang, X.S.; Deb, S. Cuckoo search via Lévy flights. In Proceedings of the World Congress on Nature & Biologically Inspired Computing, 2009 (NaBIC 2009), Coimbatore, India, 9–11 December 2009; pp. 210–214. [Google Scholar]
  36. Ogata, K. Modern Control Engineering; Prentice Hall: Hoboken, NJ, USA, 2010. [Google Scholar]
  37. Nguyen, N.T. Model-reference adaptive Control. In Model-Reference Adaptive Control: A Primer; Springer: Cham, Switzerland, 2018; pp. 83–123. [Google Scholar]
Figure 1. Forces and moments acting on the rotorcraft with reference to the body-fixed reference frame.
Figure 1. Forces and moments acting on the rotorcraft with reference to the body-fixed reference frame.
Algorithms 14 00178 g001
Figure 2. PID closed-loop system showing the inner loop for pitch( θ ) and roll( ϕ ), and the outer loop of x , y , z and yaw( ψ ).
Figure 2. PID closed-loop system showing the inner loop for pitch( θ ) and roll( ϕ ), and the outer loop of x , y , z and yaw( ψ ).
Algorithms 14 00178 g002
Figure 3. PID closed-loop system showing the objective function and the optimisation algorithm used to update the PID controller gains.
Figure 3. PID closed-loop system showing the objective function and the optimisation algorithm used to update the PID controller gains.
Algorithms 14 00178 g003
Figure 4. The nonlinear rotorcraft model response to selected trim control input.
Figure 4. The nonlinear rotorcraft model response to selected trim control input.
Algorithms 14 00178 g004
Figure 5. The nonlinear rotorcraft model response to selected trim control input.
Figure 5. The nonlinear rotorcraft model response to selected trim control input.
Algorithms 14 00178 g005
Figure 6. The change in fitness over the number of iterations (generations).
Figure 6. The change in fitness over the number of iterations (generations).
Algorithms 14 00178 g006
Figure 7. The controlled nonlinear rotorcraft position response to selected desired inputs.
Figure 7. The controlled nonlinear rotorcraft position response to selected desired inputs.
Algorithms 14 00178 g007
Figure 8. The controlled nonlinear rotorcraft orientation response to selected desired input.
Figure 8. The controlled nonlinear rotorcraft orientation response to selected desired input.
Algorithms 14 00178 g008
Figure 9. The controlled rotorcraft positions with the forward translation at 1 m/s.
Figure 9. The controlled rotorcraft positions with the forward translation at 1 m/s.
Algorithms 14 00178 g009
Figure 10. The controlled rotorcraft forward velocity tracking of 1 m/s.
Figure 10. The controlled rotorcraft forward velocity tracking of 1 m/s.
Algorithms 14 00178 g010
Figure 11. The four rotorcraft inputs to maintain trim hover flight.
Figure 11. The four rotorcraft inputs to maintain trim hover flight.
Algorithms 14 00178 g011
Figure 12. The nonlinear rotorcraft position time history 10 m/s.
Figure 12. The nonlinear rotorcraft position time history 10 m/s.
Algorithms 14 00178 g012
Figure 13. The nonlinear rotorcraft velocity time history 10 m/s.
Figure 13. The nonlinear rotorcraft velocity time history 10 m/s.
Algorithms 14 00178 g013
Figure 14. The position history of the rotorcraft subjected to starboard gust disturbance at hover.
Figure 14. The position history of the rotorcraft subjected to starboard gust disturbance at hover.
Algorithms 14 00178 g014
Figure 15. The speed of the rotorcraft in response to starboard gust disturbance at hover.
Figure 15. The speed of the rotorcraft in response to starboard gust disturbance at hover.
Algorithms 14 00178 g015
Figure 16. The position of the rotorcraft in response to starboard gust disturbance at 10 m/s.
Figure 16. The position of the rotorcraft in response to starboard gust disturbance at 10 m/s.
Algorithms 14 00178 g016
Table 1. PSO setup parameters for optimisation.
Table 1. PSO setup parameters for optimisation.
ParametersValue
Number of particles, N250
Crossover factor, F 0.5
Crossover probability, C R 0.5
Maximum iteration, i100
Table 2. GA setup parameters.
Table 2. GA setup parameters.
ParametersValue
Population size, N500
Maximum generation, G e n m a x 100
Crossover point, P c 0.8
Mutation probability, P m 0.05
Table 3. ACO setup parameters.
Table 3. ACO setup parameters.
ParametersValue
Number of ants, m20
Number of archives, k30
Maximum iteration, i100
Forgetting constant, ζ 0.8
Pheromone constant, q 0.05
Table 4. CS setup parameters.
Table 4. CS setup parameters.
ParametersValue
Number of nests, m20
Number of birds, k30
Maximum iteration, i100
Table 5. The system parameters used for the trim numerical simulations.
Table 5. The system parameters used for the trim numerical simulations.
ParametersValueParametersValue
T M =5494.6 N C T M =0.0083
λ e =0.0645 v i e =8.87 m/s
Q T e =431.26 N.m C Q M e =0.00067
θ 0 M e =0.139 rad
T T =106 N C T t =0.0040
λ e =0.0446 v i e = 7.55 m/s
Q T e =11.59 N.m C Q e =0.00035
θ 0 T e =0.229 rad
a 1 c =0.00 rad b 1 s =0.0019 rad
Table 6. The fitness, the running times of the four PID controllers’ gains optimisation algorithms and the mean and standard deviation of the ten experiments conducted.
Table 6. The fitness, the running times of the four PID controllers’ gains optimisation algorithms and the mean and standard deviation of the ten experiments conducted.
PID GainsPSOGAACOCS
Best fitness1.499 × 10 −7 2.563 × 10 −7 1.340 × 10 −7 1.566 × 10 −7
Running time (min)94.7091.2177.59119.68
Mean1.521 × 10 −7 2.608 × 10 −7 1.434 × 10 −7 1.763 × 10 −7
Standard deviation0.0200.0650.1190.240
Table 7. The four PID controllers’ gains found using optimisation for hover conditions.
Table 7. The four PID controllers’ gains found using optimisation for hover conditions.
PID GainsRollPitchYawAltitudeLongLat
PSO K p −12.56436.446−20.986−37.17210.99849.8666
K i 0036.9852.460−45.44419.936
K d −12.54616.29648.7257.10841.892−47.418
GA K p 21.0000−10.0000−14.0000−17.750019.755236.0000
K i 0018.0000−10.000011.000033.2500
K d 0031.00000.9319−19.0000−8.0000
ACO K p 20.0000−9.7567−19.9999−19.99700.974619.9999
K i 008.6687−1.751010.912619.9970
K d 0019.98600.8009−17.1235−6.5332
CS K p 20.0000−8.8618−19.6234−20.000017.650320.0000
K i 0020.0000−14.914219.589820.0000
K d −4.3698−11.986920.00001.0630−18.6291−8.6031
Table 8. The fitness, the running times of the four PID controllers’ gains optimisation algorithms and the mean and standard deviation of the ten experiments conducted for forward speed.
Table 8. The fitness, the running times of the four PID controllers’ gains optimisation algorithms and the mean and standard deviation of the ten experiments conducted for forward speed.
PID GainsPSOGAACOCS
Best fitness1.334 × 10 3 2.772 × 10 6 1.221 × 10 6 1.372 × 10 6
Running time (min)92.1190.7281.39130.02
Mean1.676 × 10 3 2.776 × 10 6 1.234 × 10 6 1.382 × 10 6
Standard deviation3083.336 × 10 3 1.707 × 10 4 8.590 × 10 3
Table 9. The four PID controllers’ gains found using optimisation for the 10 m/s forward flight conditions.
Table 9. The four PID controllers’ gains found using optimisation for the 10 m/s forward flight conditions.
PID GainsRollPitchYawAltitudeLongLat
PSO K p 37.1538−11.79044.4863−36.616211.93728.4715
K i 0038.24705.92181.89560.6122
K d 17.5394−2.72732.35727.1495−7.96460.1276
GA K p 37.1538−11.79044.4863−36.616211.93728.4715
K i 0038.24705.92181.89560.6122
K d 17.5394−2.72732.35727.1495−7.96460.1276
ACO K p 37.1538−11.79044.4863−36.616211.93728.4715
K i 0038.46975.92181.89560.6122
K d 17.5394−2.72732.35727.1495−7.96460.1276
CS K p 37.1538−11.79044.4863−36.616211.93728.4715
K i 0038.24705.92181.89560.6122
K d 17.5394−2.72732.35727.1495−7.96460.1276
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Mpanza, L.J.; Pedro, J.O. Optimised Tuning of a PID-Based Flight Controller for a Medium-Scale Rotorcraft. Algorithms 2021, 14, 178. https://0-doi-org.brum.beds.ac.uk/10.3390/a14060178

AMA Style

Mpanza LJ, Pedro JO. Optimised Tuning of a PID-Based Flight Controller for a Medium-Scale Rotorcraft. Algorithms. 2021; 14(6):178. https://0-doi-org.brum.beds.ac.uk/10.3390/a14060178

Chicago/Turabian Style

Mpanza, Lindokuhle J., and Jimoh Olarewaju Pedro. 2021. "Optimised Tuning of a PID-Based Flight Controller for a Medium-Scale Rotorcraft" Algorithms 14, no. 6: 178. https://0-doi-org.brum.beds.ac.uk/10.3390/a14060178

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop