Next Article in Journal
Entitlement-Based Access Control for Smart Cities Using Blockchain
Previous Article in Journal
The Information Geometry of Sensor Configuration
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Fast Firefly Algorithm for Function Optimization: Application to the Control of BLDC Motor

1
Department of Science and Technology, University Center of Abdelhafid Bousouf Mila, Mila 43000, Algeria
2
Research Laboratory of Electromagnetic Induction and Propulsion Systems, Department of Electrical Engineering, University of Batna 2, Batna 05000, Algeria
3
Laboratoire d’Automatique Avancée et d’Analyse des Systèmes: LAAAS, Department of Electronics, University of Batna 2, Batna 05000, Algeria
4
Computer Engineering Department, College of Computer and Information Sciences, King Saud University, Riyadh 11543, Saudi Arabia
5
Applied Computer Science Department, College of Applied Computer Science, King Saud University, Riyadh 11543, Saudi Arabia
*
Author to whom correspondence should be addressed.
Sensors 2021, 21(16), 5267; https://doi.org/10.3390/s21165267
Submission received: 3 June 2021 / Revised: 30 July 2021 / Accepted: 1 August 2021 / Published: 4 August 2021
(This article belongs to the Section Intelligent Sensors)

Abstract

:
Firefly Algorithm (FA) is a recent swarm intelligence first introduced by X.S. Yang in 2008. It has been widely used to solve several optimization problems. Since then, many research works were elaborated presenting modified versions intending to improve performances of the standard one. Consequently, this article aims to present an accelerated variant compared to the original Algorithm. Through the resolving of some benchmark functions to reach optimal solution, obtained results demonstrate the superiority of the suggested alternative, so-called Fast Firefly Algorithm (FFA), when faced with those of the standard FA in term of convergence fastness to the global solution according to an almost similar precision. Additionally, a successful application for the control of a brushless direct current electric motor (BLDC) motor by optimization of the Proportional Integral (PI) regulator parameters is given. These parameters are optimized by the FFA, FA, GA, PSO and ABC algorithms using the IAE, ISE, ITAE and ISTE performance criteria.

1. Introduction

Optimization is one of the methods that seek to solve complex problems in engineering or other fields. The objective of optimization is to locate the optimal value of a cost function in a well-defined research space under different constraints [1]. Among the techniques used, in optimization, are those of swarm intelligence algorithms which are nature-inspired algorithms, these optimization techniques have spread over the past two decades [2]. Thus, the significant performance of swarm intelligence algorithms compared to other conventional optimization methods motivates researchers and are still to be attractive to exploit them in several complex optimization problems at different fields [3]. These algorithms operate on two different search properties: exploitation and exploration, where exploration scans the entire search space and prevents the algorithm from falling into the local optima, while exploitation ensures the efficiency of the search and the convergence of the algorithm towards the optimal solution [4]. Since the appearance of Genetic Algorithm [5], many optimization algorithms have been proposed such as Ant Colony Optimization [6,7], Artificial Bee Colony (ABC) [8,9], Particle Swarm Optimization (PSO) [10,11] Modified Particle Swarm Optimization [12] Cuckoo Search (CS) [13,14], Bat Algorithm (BA) [15,16], Gray Wolf Optimizer (GWO) [17,18], Firefly Algorithm [19,20] and so on.
Recently, Firefly Algorithm is one of the famous swarm intelligence algorithms for optimization problems that have been introduced in 2008. Due to its ease of design, implementation and flexibility in nature, it has become popular in the field of optimization and has been widely applied to diverse engineering optimization problems such as in [21,22]. Despite all these advantages, it has drawbacks such as the problem of local minima and it was unable to guarantee a balance between exploration and exploitation [2,23]. Therefore, several improvement algorithms have been proposed to overcome such drawbacks which make them more widely applied successfully in engineering like optimizing Proportional Integral Derivative (PID) parameters in machine control [24,25,26,27,28].
The PID controller and its variants are mainly used in control process to have a better dynamic performance of the controlled systems. Therefore, the optimal value of the corrector parameters is needed. In this context, the choice of controller gains has become an optimization problem [29]. FA and rival algorithms were successfully applied in the optimization of the parameters of PID mainly in electrical engineering and other fields [30]. One of the prominent applications in electrical engineering is the control of BLDC motor driven by a tuned and optimized PID. However, a BLDC motor is developed on the basis of Brushed DC motor and it is one of the special electrical synchronous motor. It is driven by DC voltage, but current commutation is obtained by solid-state switches. The commutation time is fixed by the rotor position which is detected by hall sensor position [31].
It is noticeable that BLDC motor has the advantages that are: high efficiency, long operating time, low noise, small size and well speed–torque features. In general, it has a great improvement in automotive, aerospace and industry of engineering and so on. Therefore, its use has been exposed to many types of load disturbances. Conventional control methods cannot resist these alterations and lose their precision. Thus, it was necessary to implement advanced control techniques to solve this problem, especially those based on the artificial intelligence, such as: fuzzy control [32,33], neural control [34,35], Genetic Algorithm (GA) control [36,37], PSO control [38], BAT control [31] and recently, FA control and Improved Firefly Algorithm (IFA) or Modified Firefly Algorithm (MFA) [24,25,26,27,28]. These methods are based essentially on the optimization of the PID corrector parameters and its derivatives to obtain optimal performance.
In this paper, we propose an improved version of the FA for function optimization by reducing the search space. We apply this method to several benchmark problems and also to the design of a controller for BLDC motor. The paper contains two experimental parts, the first concerns the search for the global optimum of several benchmark functions according to the FA and FFA algorithms and then a comparative study is carried out. In order to consolidate its efficiency, a second application of PI parameters’ optimization for the BLDC motor control is achieved through simulation in the MATLAB platform. This application used the FFA, FA, GA, PSO and ABC algorithms according to the IAE, ISE, ITAE and ISTE performance criteria, to test the competitiveness of the FFA algorithm. Finally, by comparison of the obtained results, it is found that the performances of the FFA are better than those of the other algorithms and it can be concluded that this new algorithm can be a valid concurrent meta-heuristic optimization method.
The paper is organized as follows. Section 2 introduces the mathematical background of the standard FA and the suggested FFA. In Section 3, the two algorithms are compared through optimum finding of several standard test functions. The mathematical model of BLDC motor and the PI controller with description of the experimental results are presented in Section 4. Finally, drawn conclusion summarizing the achieved work is given in Section 5.

2. Firefly Algorithm and Proposed Fast Firefly Algorithm

2.1. Standard Firefly Algorithm

Firefly Algorithm is inspired by the natural behavior of fireflies by using their self-luminosity to get closer to each other in the dark. Three assumptions have been suggested by Yang to clarify the behavior of fireflies [19,20]. Firstly, all fireflies are unisex. Thus, each firefly can be attracted to other fireflies regardless of gender. Secondly, the attractiveness is linked to the intensity which is a function of the distance between the firefly concerned and the other fireflies. The attractiveness decreases as the distance increases. Finally, the luminosity or the luminous intensity of a firefly is given by the value of the cost function of the problem posed. Mathematically, the FA algorithm can be given by the following equations [19].
The light intensity of a firefly is given by Equation (1).
I ( r ) = I 0 exp ( γ . r i j )
where: γ is the absorption coefficient and (I0) is the initial value at (r = 0).
The attractiveness is expressed by Equation (2) where β0 is the initial value at (r = 0):
β = β 0 exp ( γ . r i j m )   ,   m 1
Equation (3) evaluates the distance between two fireflies i and j, at positions xi and xj, respectively, and can be defined as Cartesian distance. Where xik is the kth element of the spatial coordinate xj of the ith firefly and D denotes the dimensionality of the problem [19].
r i j = | r i r j | = k = 1 D ( x i k x j k ) 2
The motion equation of the ith firefly to the jth one is determined by Equation (4).
x i ( t + 1 ) = x i ( t ) + β ( x j ( t ) x i ( t ) ) + α ( r a n d 0.5 )
where xi(t + 1) is the position of firefly i at iteration t +1 displacement. As it can be seen, the first part of the right side of Equation (4) is the position of firefly i at iteration t, the second term is relative to the attractiveness and the last one is randomization (blind flying if there is no light) where α is the random walk parameter α ∈ [0,1), [19].
The FA Algorithm 1 is given as follows [19]:
Algorithm 1. Firefly Algorithm
Initialization of the parameters of FA (Population size, α, βo, γ and the number of iterations).
The Light intensity is defined by the cost function f(xi) where xi(i = 1,…,n).
While (iter < Max Generation).
        for i = 1:n (all n fireflies)
          for j = 1:n (all n fireflies)
            if (f(xi) < f(xj)), move firefly i towards j,
            end if.
            Update attractiveness β with distance r.
            Evaluate new solution and update f(xi) in the same way as (4).
          end for j
        end for i
rank the solutions and find the best global optimal.
end while.
Show the results.

2.2. Fast Firefly Algorithm

It is worth noting that the original algorithm of Xin-She Yang performs (Max generation n.n) tests. However, in the proposed version, (K.n) tests only are performed, where K is an integer. It means that the conventional one is hugely time consuming when compared to the suggested one. The proposed Algorithm 2 is summarized as follows:
Algorithm 2. Fast Firefly Algorithm
While (iter < Max Generation)
        for k = 1:K.n (all n fireflies) // Here it is the first modification
                i = rand(n) // Here it is the second modification
                j = rand(n) // Here it is the third modification
                if (f(xi) < f(xj)), move firefly i towards j,
                end if.
                Update attractiveness β with distance r.
                Evaluate new solution and update f(xi) in the same way as Equation (4).
                Modify the new position obtained by Equation (4) according to Equation (5).
                end for k
rank the solutions and find the best global optimal.
end while.
Show the results.
As above mentioned, the new position obtained by Equation (4) is modified according to Equation (5):
x i ( t + 1 ) = α . x i ( t )
It should be noted that the values of α and γ are given empirically in the original version according to each test function, β0 is equal to unity. However, on the other hand, the α in FFA is taken equal to:
α = exp ( 10 . i t e r / ( i t e r + 100 ) )
where the convergence is reached easily and γ still chosen equal to 1. The randomization parameter α is reduced exponentially from a maximum value to a minimum value according to successive iterations instead of keeping it constant; with this injected artifice, we can maintain the research balance between the exploitation and the exploration of the proposed algorithm and it can give better results than its rival FA [4].
In the original version of the FA, the technique of updating the motion of fireflies can be improved to be more faster. Thus, it is beneficial for each firefly in the swarm to find a promising region by reorienting its motion in order to easily reach the overall optimum. Consequently, the updated term is redirected to have a better exploration and exploitation of the algorithm and the speed of its convergence is, thus, guaranteed [1,39].
The essence of the proposed method is the reduction of the search space (exploration) while keeping the search efficiency satisfactory to reach the optimal solution. It means that (K.n) evaluated tests were found clearly sufficient to obtain the optimal solution for the large number of benchmark functions and other applications [40].

3. Simulation Results and Analysis

3.1. Benchmark Functions

Standards’ functions are essential to prove and compare the characteristics of optimization algorithms. The most terms of evaluation are: The convergence speed and the precision. Hence, 12 different test functions are used to compare the performance of the original algorithm FA and the proposed one FFA according to the previously mentioned evaluation terms. The used test functions are listed in Table 1, highlighting the variables, ranges and values of the global optimum to reach [41,42].

3.2. Parameter Settings

The parameter settings of FA and FFA are showed in Table 2.

3.3. Functions’ Experimental Results

The two algorithms are applied to minimize a set of test functions of dimensions 2D, 10D, 20D and 30D, respectively. The experimental environment is the MATLAB R2017a software, the CPU is an [email protected] GHZ, the RAM is of size 6 GB. To compare their performance, minimum, mean, standard deviation and the computational time are taken over 10 runs. For each function, the two algorithms operate independently. The results of the optimization are summarized in Table 3.
In terms of precision of convergence towards the global optimum, by visualizing the results in Table 3, it can be seen that the mean and the standard deviation of the reached optimum, after 10 runs for each test function, of FFA in all dimensions are better than of FA.
Concerning the convergence fastness to the global optimum, it can be clearly remarked, from extensive simulation tests, that the proposed method outperforms the original one and it is significantly faster (see Table 3). Accordingly, the average speed up ratio, when applying the two algorithms on the 12 test functions, is 12:1, which confirms the effectiveness of the suggested technique.
It is worthy to note that the speed up ratio is defined by:
S R = t F A t F F A
where tFA is the execution time of the original algorithm FA, and the tFFA is the execution time of the proposed one FFA.
As is shown in Figure 1, Figure 2, Figure 3 and Figure 4 below, the proposed algorithm reaches all solutions of all test functions with high precision outperforming, accordingly, those obtained from the standard one.
As can be seen from Table 3, the proposed algorithm is more unbiased (the statistical expected value of obtained cost function of FFA is more tending to the theoretical value than FA) and more consistent (the standard deviation of obtained cost function when applying FFA is more tending to 0 than the FA). The reported remarks hold for the twelve test functions as previously shown in Table 3 for dimensions 2D, 10D, 20D and 30D, respectively. For more convincing, robustness and stability of FFA in higher dimensions are evaluated by using the test functions (F13, F14 and F15) for dimensions 50D, 100D, 150D and 200D, respectively. Table 4 gives the results of these tests with a 10 times run for each test function. Finally, it can be concluded that the stability of FFA is not affected by increasing significantly dimensions (high precision remains obtained). The graphs of Figure 5 reflect these results.

4. Application for the Control of Brushless DC Motor

4.1. Description

BLDC motor is a permanent magnet synchronous motor that has trapezoidal Back- EMF and an almost rectangular current. It uses position detectors and an inverter to control the armature currents. It becomes popular for industrial applications because of its high efficiency, reliability, noiseless operation, low maintenance and an optimized volume. BLDC motors are available in several different configurations, but three-phase is the most common type due to its high speed and low torque ripple [43].
The drive model of a BLDC motor is shown in Figure 6. It is divided into two blocks. The first one is the inverter and the second is the BLDC motor. Accordingly, the BLDC motor is powered by a six-switch inverter where, for each control step, two phases operate simultaneously while the third is eliminated. Note that the signals of the Hall Effect position sensor (Ha, Hb, Hc) shifted by 120°, electrically govern these switches by generation of the pulses (S1,…,S2) at every 60° electrical angle [43,44,45].

4.2. Mathematical Modeling of a BLDC Motor

By consideration of the symmetry of the phases, it is assumed that the three phases’ resistances are identical as well as the inductances. Consequently, the equations describing the model of the equivalent circuit of the motor are [43,44,45]:
v a = R i a + L d d t i a + e a
v b = R i b + L d d t i b + e b
v c = R i c + L d d t i c + e c
Then, the line voltage equation can be obtained by subtraction of the phase voltage equation as:
v a b = R ( i a i b ) + L d d t ( i a i b ) + e a e b
v b c = R ( i b i c ) + L d d t ( i b i c ) + e b e c
v c a = R ( i c i a ) + L d d t ( i c i a ) + e c e a
where:
  • R: resistance of a stator phase [Ω].
  • L: inductance of a stator phase [H].
  • va, vb and vc are the stator phase voltages [V].
  • vab, vbc and vca are the stator phase to phase voltages [V].
  • ia, ib and ic are stator phase currents [A]
  • ea, eb and ec are motor Back-EMFs [V].
The relationship between phase currents is given by the equation:
i a + i b + i c = 0
Since each voltage is a linear combination of the other two voltages, two equations are sufficient. Using relation 14, Equations (11) and (12) become [44]:
v a b = R ( i a i b ) + L d d t ( i a i b ) + e a e b
v b c = R ( i a + 2 i b ) + L d d t ( i a + 2 i b ) + e b e c
The equation of mechanical part represents as follows:
T e = k f ω m + J d ω m d t + T L
ω m = d θ m d t
where:
  • Te and TL are the electromagnetic torque and the load torque [Nm].
  • J is the rotor inertia, kf is a friction constant and ωm is the rotor speed [rad/s].
The Back-EMF and electromagnetic torque can be expressed as:
e a = k e ω m F ( θ e )
e b = k e ω m F ( ( θ e 2 π 3 ) )
e c = k e ω m F ( ( θ e 4 π 3 ) )
where:
  • ke is the Back-EMF’s constant.
  • θ e is equal to the rotor angle ( θ e = p.   θ m /2), θ m the mechanic angle and p the number of pole pairs. F( θ e ) is trapezoidal waveform of Back-EMFs.
Thus, the torque equation can be defined as:
T e = ( e a i a + e b i b + e c i c ) ω m = k t 2 [ F ( θ e ) i a + F ( θ e 2 π 3 ) i b + F ( θ e 4 π 3 ) i c ]
  • kt: the torque constant.
Therefore, the function F( θ e ) is a function of rotor position, which gives the trapezoidal waveform of Back-EMF. One period of function can be written as:
F ( θ e ) = 1 0 θ e < 2 π 3 1 6 π ( θ e 2 π 3 ) 2 π 3 θ e < π 1 π θ e < 5 π 3 1 + 6 π ( θ e 5 π 3 ) 5 π 3 θ e < 2 π
For illustration, Figure 7 shows Back-EMF, Hall Effect sensor signal and the current in the three phases. In the trapezoidal motor Back-EMF induced in the stator has a trapezoidal shape and its phases must be supplied with quasi square currents for ripple free torque operation [44,46].
Finally, Equations (15)–(18) can be converted to a state space form. The resulting complete model is given as:
[ d i a d t d i b d t d ω m d t d θ m d t ] = [ R L 0 0 0 0 R L 0 0 0 0 k f J 0 0 0 1 0 ] [ i a i b ω m θ m ] + [ 2 3 L 1 3 L 0 1 3 L 1 3 L 0 0 0 1 J 0 0 0 ] [ v a b e a b v b c e b c T e T L ]
i c = ( i a + i b )
where: e a b = e a e b and e b c = e b e c

4.3. Hall Effect Sensor and Transistor Switching Sequence

According to the angular position of the rotor evolution between 0° and 360°, the position produced by Hall Effect sensors is given which is described in Table 5 below.
Each Hall Effect sensor operates during the passage of the poles based on the rising and falling edges. Thus, the rising front for the north pole and falling for the south pole. Accordingly, the sensor indicates 1 or 0, respectively. Following this switching logic of Hall Effect sensors, the switching sequence of the inverter is expressed in Table 5, where the switching sequence for shaft rotation is clockwise [45,47].
According to the circuit in Figure 6, the three-phase voltages are calculated with the following formulas [45]:
v a = v d 2 ( S 1 S 2 )
v b = v d 2 ( S 3 S 4 )
v c = v d 2 ( S 5 S 6 )
where vd is the DC supply voltage.

4.4. Speed Control of Brushless DC Motor

The principle diagram for speed control of the three-phase BLDC motor is shown in Figure 8. At the regulator input, the reference speed is compared to the actual speed of the motor to generate a control voltage at its output.
The signals of the switching sequences are obtained from the position of the motor shaft. The motor stator is excited by the three-phase currents [45].

4.5. PI Controller

PI controller is a derivative of PID controller. It has been extensively used in industrial applications due to its simplicity, robustness, reliability and easy tuning gains in simple control [21].
The equation of the PI controller is specified by:
y ( t ) = k p ε ( t ) + k i 0 t ε ( τ ) d τ
The Laplace transfer function is:
C ( S ) = k p + k i s
where:
kp: proportional gain,
ki: integral gain,
s: Laplace operator.

4.6. Simulation Results and Discussion

To ensure efficient performance of the system to be monitored, the performance criteria defined by Equations (31)–(34) are used. The objective functions are chosen for minimizing the time response characteristics due to the dependency of error on time [27]:
J 1 = I A E = 0 T ε ( t ) d t = 0 T ( ω r e f ω m ) d t
J 2 = I S E = 0 T ε 2 ( t ) d t d t = 0 T ( ω r e f ω m ) 2 d t
J 3 = I T A E = 0 T t . ε ( t ) d t = 0 T t . ( ω r e f ω m ) d t
J 4 = I T S E = 0 T t . ε 2 ( t ) d t = 0 T t . ( ω r e f ω m ) 2 d t
The problem can be represented as:
Minimize J subjected to:
kpminkpkpmax
kiminkikimax
where ωref is the reference speed and ωm is the actual one. Figure 9 shows PI controller block of the control. In this problem, the values of overshoot, rise time and stabilization time are controlled indirectly. These parameters are directly linked to the objective function so they are optimized implicitly [27].
The model of BLDC motor drive is simulated in MATLAB. The parameters of the BLDC motor are reported in Table 6.
To control the BLDC motor, a conventional PI controller is used. However, it is not easy to adjust its parameters in order to have an efficient control. Therefore, the FFA_PI controller is used and it is compared to other algorithms to evaluate its competitiveness. The simulation is performed by considering the well-known algorithms GA, PSO, ABC and the standard FA. The simulation is run with 100 iterations and a population size of 10.
Figure 10 shows the evolution of the different performance criteria with the different algorithms. The results of FFA, with the different criteria, are all the better than those presented by the other algorithms. Figure 11, also, presents the cost functions IAE, ISE, ITAE and ISTE obtained by FFA algorithm.
The values of the PI controller, obtained by different simulations, are shown in Table 7. The values are obtained by the five algorithms used, with different criteria.
In the chosen cost functions, the values of the overshoot, the rise time and the settling time can be controlled indirectly. Based on their optimization, the cost functions force the values of the other parameters to be optimum [27]. Table 8 shows the values of the different correctors used in this simulation. The values of the rise time, settling time, peak time, peak and overshoot are reported in Table 8. Accordingly, the results concerning the time are better for the FFA algorithm as well as for the peaks and the overshoots which are alternated with the other algorithms.
Moreover, the execution simulation time comparison is given between the different correctors and shown in Table 9. It can be reported that the calculation time using the FFA_PI is faster than those obtained with the FA_PI, GA_PI, PSO_PI and ABC_PI when using 50 or 100 iterations.
According to the used criterions, Figure 12, Figure 13, Figure 14 and Figure 15 represent the BLDC motor speeds obtained with the different corrector optimized. Consequently, the figures are given for comparison and they justify the values in Table 8.
The graphs are zoomed in the area of the overshoot and the rejection of the disturbance for better visualization of signals.
From the previous numerical results and the figures’ responses, it can be concluded that the optimized PI controller-based FFA showed a better capacity to compete with its FA counterpart, and its rivals GA, PSO and ABC. Thus, it provided the fastest rise and response times in addition to the minimum peak time.
Figure 16 show the simulation results of the various variables of the BLDC motor using the FFA_PI using (ki = 2468, kp = 18.19). Accordingly, Figure 16a presents the speed of the BLDC motor where the reference speed ωref is chosen as a ramp in order to dampen the current at start-up and to avoid peaks as well as for the electromagnetic torque on the Figure 16b. At 0.125 s, a torque load TL = 4 Nm is applied and a good rejection by the control is observed. The effect of the load is very apparent on the figure of the speed, the torque, the voltages and the current.
On each figure presented, there are three phases, where the first phase is zoomed-in to clearly visualize the behavior of the signals. Thus, Figure 16c,d show the phase voltages and the phase to phase voltage simultaneously. The trapezoidal Back-EMF shape is well illustrated on the Figure 16e. Finally, the shape of the currents of the three phases of the stator is given by the Figure 16f. As can be seen, there is a distortion in the torque signals which is due to the trapezoidal shape of the Back-EMF and the nature of the currents containing harmonics. Finally, Figure 17 gives the evolution, until the convergence, of the parameters of the FFA_PI and FA_PI on the control technique.

5. Conclusions

A fast FA algorithm so-called FFA is presented and compared with the standard FA through searching the global optimum by using different standard benchmark functions in a first application. The simulation results were compared, taking in consideration the precision and the speed of convergence criteria for the two algorithms. The reached results prove that those obtained by FFA are better than those of FA. A second application concerning the optimization of the gains of a PI controlling a BLDC motor is carried out through the ITSE performance criterion. The results obtained show the robustness of the two algorithms with superiority for FFA. The acceleration of the proposed algorithm is due to the search space reduction by a random election of a significantly small set of moving fireflies while the whole search space stills covered. It should be noted that the acceleration, in the optimization function, is in the average 12:1, with respect to FA. Additionally, for the complex problem (BLDC motor control), the acceleration is clearly remarked for the modified algorithm FFA than FA, GA, PSO and ABC algorithms. Globally, the suggested FFA algorithm can be considered as most state of the art metaheuristic algorithms such as FA, GA, PSO and ABC, and presents superior fastness against all reported optimizers.
Furthermore, a modification on the α parameter is given and this guarantees the robustness and precision through the enhancement of search directions toward the global optimal solution.

Author Contributions

Conceptualization, methodology, software, writing—original draft preparation, validation S.B. and R.B.; Supervision, R.B. formal analysis, writing—review and editing, funding acquisition, Y.B. and M.M.A.R. All authors have read and agreed to the published version of the manuscript.

Funding

The authors extend their appreciation to the Deanship of Scientific Research at King Saud University for funding this work through research group No. RG-1441-502.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Acknowledgments

The authors extend their appreciation to the Deanship of Scientific Research at King Saud University for funding this work through research group No. RG-1441-502.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

Symbols used in this paper
ABCArtificial Bee Colony
PSOParticle Swarm Optimization
CSCuckoo Search
BABat Algorithm
GWOGray Wolf Optimizer
FAFirefly Algorithm
FFAFast Firefly Algorithm
GAGenetic Algorithms
PIProportional Integral
PIDProportional Integral & Derivative
kp, kiProportional and Integral gains of the PI controller
IFAImproved Firefly Algorithm
MFAModified Firefly Algorithm
tFAExecution time of the original algorithm FA
tFFAExecution time of the proposed algorithm FFA
RResistance of a stator phase, [Ω]
LInductance of a stator phase, [H]
va, vc, vcStator phase voltages, [V]
vab, vbc, vcaStator phase to phase voltages, [V]
ia, ib, icStator phase currents, [A]
ea, eb, ecMotor Back-EMFs, [V]
Te, TLElectromagnetic and load torques, [Nm]
JRotor inertia, [kgm2]
kfFriction constant, [Nms/rad]
ktTorque coefficient, [Nm/A]
ωmRotor speed, [rad/s]
NrRated speed, [rpm]
θeElectric angle of rotor, [rad]
θmMechanic angle of rotor, [rad]
F(θe)Back-EMF reference function
ε(t)Error input signal
y(t)Output signal
Ha, Hb, HcHall Effect Sensors for the three phases
IAEIntegral Absolute Error
ISEIntegral Square Error
ITAEIntegral Time Absolute Error
ISTEIntegral Square Time Error

References

  1. Sarangi, S.K.; Panda, R.; Priyadarshini, S.; Sarangi, A. A New Modified Firefly Algorithm for Function Optimization. In Proceedings of the 2016 International Conference on Electrical, Electronics, and Optimization Techniques (ICEEOT), Chennai, India, 3–5 March 2016; pp. 2944–2949. [Google Scholar]
  2. Yelghi, A.; Köse, C. A Modified Firefly Algorithm for Global Minimum Optimization. Appl. Soft Comput. 2018, 62, 29–44. [Google Scholar] [CrossRef]
  3. Ariyaratne, M.K.A.; Fernando, T.G.I.; Weerakoon, S. A Modified Firefly Algorithm to Solve Univariate Nonlinear Equations with Complex Roots. In Proceedings of the 2015 Fifteenth International Conference on Advances in ICT for Emerging Regions (ICTer), Colombo, Sri Lanka, 24–26 August 2015; pp. 160–167. [Google Scholar]
  4. Ariyaratne, M.K.A.; Fernando, T.G.I.; Weerakoon, S. Solving systems of nonlinear equations using a modified firefly algorithm (MODFA). Swarm Evol. Comput. 2019, 48, 72–92. [Google Scholar] [CrossRef]
  5. Goldberg, D.E. Genetic Algorithms in Search, Optimization and Machine Learning, 1st ed.; Addison-Wesley Longman Publishing Co., Inc.: Boston, MA, USA, 1989; ISBN 978-0-201-15767-3. [Google Scholar]
  6. Dorigo, M.; Birattari, M.; Stutzle, T. Ant Colony Optimization. IEEE Comput. Intell. Mag. 2006, 1, 28–39. [Google Scholar] [CrossRef] [Green Version]
  7. Zeng, Q.; Tan, G. Optimal Design of PID Controller Using Modified Ant Colony System Algorithm. In Proceedings of the Third International Conference on Natural Computation (ICNC 2007), Haikou, China, 24–27 August 2007; Volume 5, pp. 436–440. [Google Scholar]
  8. Karaboga, D.; Akay, B.; Ozturk, C. Artificial Bee Colony (ABC) Optimization Algorithm for Training Feed-Forward Neural Networks. In Proceedings of the Modeling Decisions for Artificial Intelligence, Haikou, China, 24–27 August 2007; Torra, V., Narukawa, Y., Yoshida, Y., Eds.; Springer: Berlin/Heidelberg, Germany, 2007; pp. 318–329. [Google Scholar]
  9. Singh, K.; Sundar, S. Artifical Bee Colony Algorithm Using Problem-Specific Neighborhood Strategies for the Tree t-Spanner Problem. Appl. Soft Comput. 2018, 62, 110–118. [Google Scholar] [CrossRef]
  10. Kennedy, J.; Eberhart, R. Particle Swarm Optimization. In Proceedings of the ICNN’95—International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar]
  11. Nema, S.; Padhy, P.K. PI-PD Controller for Stable and Unstable Processes. Int. J. Syst. Control Commun. 2013, 5, 156–165. [Google Scholar] [CrossRef]
  12. Nangru, D.; Bairwa, D.K.; Singh, K.; Nema, S.; Padhy, P.K. Modified PSO Based PID Controller for Stable Processes. In Proceedings of the 2013 International Conference on Control, Automation, Robotics and Embedded Systems (CARE), Jabalpur, India, 16–18 December 2013; pp. 1–5. [Google Scholar]
  13. Yang, X.-S.; Deb, S. Cuckoo Search via Lévy Flights. In Proceedings of the 2009 World Congress on Nature Biologically Inspired Computing (NaBIC), Coimbatore, India, 9–11 December 2009; pp. 210–214. [Google Scholar]
  14. Yang, X.-S.; Deb, S. Engineering Optimisation by Cuckoo Search. Int. J. Math. Model. Numer. Optim. 2010, 1, 330–343. [Google Scholar] [CrossRef]
  15. Yang, X.; He, X. Bat Algorithm: Literature Review and Applications. Int. J. Bio-Inspired Comput. 2013, 5, 141–149. [Google Scholar] [CrossRef] [Green Version]
  16. Yang, X.-S. A New Metaheuristic Bat-Inspired Algorithm. In Nature Inspired Cooperative Strategies for Optimization (NICSO 2010); González, J.R., Pelta, D.A., Cruz, C., Terrazas, G., Krasnogor, N., Eds.; Studies in Computational Intelligence; Springer: Berlin/Heidelberg, Germany, 2010; pp. 65–74. ISBN 978-3-642-12538-6. [Google Scholar]
  17. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey Wolf Optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef] [Green Version]
  18. Pallav, D.; Santanu, K.N. Grey Wolf Optimizer Based PID Controller for Speed Control of BLDC Motor. J. Electr. Eng. Technol. 2021, 16, 955–961. [Google Scholar] [CrossRef]
  19. Yang, X.-S. Firefly Algorithms for Multimodal Optimization. In Proceedings of the Stochastic Algorithms: Foundations and Applications; 5th International Symposium, SAGA 2009, Sapporo, Japan, 26–28 October, 2009; pp. 169–178. [Google Scholar]
  20. Yang, X.-S. Nature-Inspired Metaheuristic Algorithms; Luniver Press: Beckington, UK, 2010; ISBN-13: 978-1-905986-28-6. [Google Scholar]
  21. Bazi, S.; Benzid, R.; Said, M.S.N. Optimum PI Controller Design in PMSM Using Firefly Algorithm and Genetic Algorithm. In Proceedings of the 2017 6th International Conference on Systems and Control (ICSC), Batna, Algeria, 7–9 May 2017; pp. 85–89. [Google Scholar]
  22. Pradhan, P.C.; Sahu, R.K.; Panda, S. Firefly Algorithm Optimized Fuzzy PID Controller for AGC of Multi-Area Multi-Source Power Systems with UPFC and SMES. Eng. Sci. Technol. Int. J. 2016, 19, 338–354. [Google Scholar] [CrossRef] [Green Version]
  23. Jinran, W.; You-Gan, W.; Kevin, B.; Yu-Chu, T.; Brodie, L.; Zhe, D. An improved firefly algorithm for global continuous optimization problems. Expert Syst. Appl. 2020, 149, 113340. [Google Scholar] [CrossRef]
  24. Boris, J.; Paolo, L.; Guido, M. Control of double-loop permanent magnet synchronous motor drives by optimized fractional and distributed-order PID controllers. Eur. J. Control 2021, 58, 232–244. [Google Scholar] [CrossRef]
  25. Mat Hussin, A.T.; Intan Zaurah, M.D.; Pakharuddin, M.S.; Hanim, M.Y.; Mohd Ibthisham, A.; Nik Mohd, R.S.; Muhamad, S.H. Vibration control of semi-active suspension system using PID controller with advanced firefly algorithm and particle swarm optimization. J. Ambient. Intell. Humaniz. Comput. 2021, 12, 1119–1137. [Google Scholar]
  26. He, S.; Chen, Z.; Gao, X. Parameter Solving of DC Servo Motor PID Controller Based on Improved Firefly Algorithm. In Proceedings of the 2018 3rd International Conference on Robotics and Automation Engineering (ICRAE), Guangzhou, China, 17–19 November 2018; pp. 136–140. [Google Scholar]
  27. Rosy, P.; Santosh, K.M.; Jatin, K.P.; Bibhuti, B.P. Optimal fractional order PID controller design using Ant Lion Optimizer. Ain Shams Eng. J. 2020, 11, 281–291. [Google Scholar] [CrossRef]
  28. Devarapalli, R.; Naga Lakshmi, N.J.; Prasad, U. Application of a Novel Political Optimization in Optimal Parameter Design of PI Controller for the BLDC Motor Speed Control. In Proceedings of the 2020 International Conference on Emerging Frontiers in Electrical and Electronic Technologies (ICEFEET), Patna, India, 10–11 July 2020; pp. 1–6. [Google Scholar]
  29. BARAN, H. Optimal Tuning of Fractional Order PID Controller for DC Motor Speed Control via Chaotic Atom Search Optimization Algorithm. IEEE Access 2019, 7, 38100–38114. [Google Scholar]
  30. Jagatheesan, K.; Anand, B.; Samanta, S.; Dey, N.; Ashour, A.S.; Balas, V.E. Design of a Proportional-Integral-Derivative Controller for an Automatic Generation Control of Multi-Area Power Thermal Systems Using Firefly Algorithm. IEEE/CAA J. Autom. Sin. 2019, 6, 503–515. [Google Scholar] [CrossRef]
  31. Chaib, L.; Choucha, A.; Arif, S. Optimal Design and Tuning of Novel Fractional Order PID Power System Stabilizer Using a New Metaheuristic Bat Algorithm. Ain Shams Eng. J. 2017, 8, 113–125. [Google Scholar] [CrossRef] [Green Version]
  32. Xiaoyan, P.; Mingfei, J.; Lei, H.; Xiang, Y.; Yibin, L. Fuzzy sliding mode control based on longitudinal force estimation for electro-mechanical braking systems using BLDC motor. CES Trans. Electr. Mach. Syst. 2018, 2, 142–151. [Google Scholar]
  33. Walekar, V.R.; Murkute, S.V. Speed Control of BLDC Motor Using PI Fuzzy Approach: A Comparative Study. In Proceedings of the 2018 International Conference on Information, Communication, Engineering and Technology (ICICET), Pune, India, 29–31 August 2018; pp. 1–4. [Google Scholar]
  34. Ahmed, R.; Paul, Y. Hardware/Software Implementation of Fuzzy-Neural-Network Self-Learning Control Methods for Brushless DC Motor Drives. IEEE Trans. Ind. Appl. 2016, 52, 414–424. [Google Scholar]
  35. Xiong, S.; Junguo, G.; Jian, C.; Biao, J. Research on Speed Control System of Brushless DC Motor Based on Neural Network. In Proceedings of the 2015 8th International Conference on Intelligent Computation Technology and Automation (ICICTA), Nanchang, China, 14–15 June 2015; pp. 761–764. [Google Scholar]
  36. Putra, E.H.; Zulfatman, Z.; Effendy, M. Robust Adaptive Sliding Mode Control Design with Genetic Algorithm for Brushless DC Motor. In Proceedings of the International Conference on Electrical Engineering, Computer Science and Informatics (EECSI), Malang, Indonesia, 16–18 October 2018; Volume 5, pp. 330–335, ISBN 978-1-5386-8402-3. [Google Scholar]
  37. Li, J.; Li, W. On-Line PID Parameters Optimization Control for Wind Power Generation System Based on Genetic Algorithm. IEEE Access 2020, 8, 137094–137100. [Google Scholar] [CrossRef]
  38. Merugumalla, M.K.; Navuri, P.K. PSO and Firefly Algorithms Based Control of BLDC Motor Drive. In Proceedings of the 2018 2nd International Conference on Inventive Systems and Control (ICISC), Coimbatore, India, 19–20 January 2018; pp. 994–999. [Google Scholar]
  39. Ho, S.L.; Yang, S.; Ni, G.; Lo, E.W.C.; Wong, H.C. A Particle Swarm Optimization-Based Method for Multiobjective Design Optimizations. IEEE Trans. Magn. 2005, 41, 1756–1759. [Google Scholar] [CrossRef] [Green Version]
  40. Fateen, S.-E.K.; Bonilla-Petriciolet, A. Intelligent firefly algorithm for global optimization. In Cuckoo Search and Firefly algorithm; Springer: Berlin/Heidelberg, Germany, 2014; pp. 315–330. [Google Scholar]
  41. Ardeh, M.A. Benchmark Functions. Available online: Benchmarkfcns.xyz/fcns.html (accessed on 26 May 2021).
  42. Jamil, M.; Yang, X.-S. A Literature Survey of Benchmark Functions for Global Optimisation Problems. Int. J. Math. Model. Numer. Optim. 2013, 4, 150–194. [Google Scholar] [CrossRef] [Green Version]
  43. Permanent Magnet Brushless DC Motor Drives and Controls|Wiley. Available online: https://www.wiley.com/en-ar/Permanent+Magnet+Brushless+DC+Motor+Drives+and+Controls-p-9781118188330 (accessed on 27 May 2021).
  44. Mondal, S.; Mitra, A.; Chattopadhyay, M. Mathematical Modeling and Simulation of Brushless DC Motor with Ideal Back EMF for a Precision Speed Control. In Proceedings of the 2015 IEEE International Conference on Electrical, Computer and Communication Technologies (ICECCT), Coimbatore, India, 5–7 March 2015; pp. 1–5. [Google Scholar]
  45. Prasad, G.; Ramya, N.S.; Prasad, P.V.N.; Das, G.T.R. Modeling and Simulation Analysis of the Brushless DC Motor by Using MATLAB. Int. J. Innov. Technol. Explor. Eng. (IJITEE) 2012, 1, 27–31. [Google Scholar]
  46. Kumar, D.; Gupta, R.A.; Gupta, N. Modeling and Simulation of Four Switch Three-Phase BLDC Motor Using Anti-Windup PI Controller. In Proceedings of the 2017 Innovations in Power and Advanced Computing Technologies (i-PACT), Vellore, India, 21–22 April 2017; pp. 1–6. [Google Scholar]
  47. Jaromír, J.; Miloslav, Č. Position Measurement with Hall Effect Sensors. Am. J. Mech. Eng. 2013, 1, 231–235. [Google Scholar] [CrossRef]
Figure 1. Convergence curves of FFA and FA for the functions: (a) F1; (b) F2 and (c) F3 (2D).
Figure 1. Convergence curves of FFA and FA for the functions: (a) F1; (b) F2 and (c) F3 (2D).
Sensors 21 05267 g001
Figure 2. Convergence curves of FFA and FA for the functions: (a) F4; (b) F5 and (c) F6 (10D).
Figure 2. Convergence curves of FFA and FA for the functions: (a) F4; (b) F5 and (c) F6 (10D).
Sensors 21 05267 g002
Figure 3. Convergence curves of FFA and FA for the functions: (a) F7; (b) F8 and (c) F9 (20D).
Figure 3. Convergence curves of FFA and FA for the functions: (a) F7; (b) F8 and (c) F9 (20D).
Sensors 21 05267 g003
Figure 4. Convergence curves of FFA and FA for the functions: (a) F10; (b) F11 and (c) F12 (30D).
Figure 4. Convergence curves of FFA and FA for the functions: (a) F10; (b) F11 and (c) F12 (30D).
Sensors 21 05267 g004
Figure 5. Convergence curves of FFA for the functions: (a) F13; (b) F14 and (c) F15 on 50D, 100D, 150D and 200D.
Figure 5. Convergence curves of FFA for the functions: (a) F13; (b) F14 and (c) F15 on 50D, 100D, 150D and 200D.
Sensors 21 05267 g005
Figure 6. Drive model of a BLDC motor [43,44,45,46,47].
Figure 6. Drive model of a BLDC motor [43,44,45,46,47].
Sensors 21 05267 g006
Figure 7. State of Hall sensor signals, Back-EMF and currents [47].
Figure 7. State of Hall sensor signals, Back-EMF and currents [47].
Sensors 21 05267 g007
Figure 8. Speed control principle of BLDC motor.
Figure 8. Speed control principle of BLDC motor.
Sensors 21 05267 g008
Figure 9. Scheme of PI controller parameters’ optimization based on a nature-inspired algorithm.
Figure 9. Scheme of PI controller parameters’ optimization based on a nature-inspired algorithm.
Sensors 21 05267 g009
Figure 10. Convergence curves for different algorithms with several criteria.
Figure 10. Convergence curves for different algorithms with several criteria.
Sensors 21 05267 g010aSensors 21 05267 g010b
Figure 11. Convergence curves for different criteria with FFA algorithms.
Figure 11. Convergence curves for different criteria with FFA algorithms.
Sensors 21 05267 g011
Figure 12. Comparison of speed responses with different algorithms using IAE criterion: (a) original; (b) and (c) zoomed version.
Figure 12. Comparison of speed responses with different algorithms using IAE criterion: (a) original; (b) and (c) zoomed version.
Sensors 21 05267 g012
Figure 13. Comparison of speed responses with different algorithms using ISE criterion: (a) original; (b) and (c) zoomed version.
Figure 13. Comparison of speed responses with different algorithms using ISE criterion: (a) original; (b) and (c) zoomed version.
Sensors 21 05267 g013
Figure 14. Comparison of speed responses with different algorithms using ITAE criterion: (a) original; (b) and (c) zoomed version.
Figure 14. Comparison of speed responses with different algorithms using ITAE criterion: (a) original; (b) and (c) zoomed version.
Sensors 21 05267 g014
Figure 15. Comparison of speed responses with different algorithms using ISTE criterion: (a) original; (b) and (c) zoomed version.
Figure 15. Comparison of speed responses with different algorithms using ISTE criterion: (a) original; (b) and (c) zoomed version.
Sensors 21 05267 g015
Figure 16. Results of simulation by using FFA_PI controller.
Figure 16. Results of simulation by using FFA_PI controller.
Sensors 21 05267 g016aSensors 21 05267 g016b
Figure 17. Evolution of parameters of FFA_PI until convergence.
Figure 17. Evolution of parameters of FFA_PI until convergence.
Sensors 21 05267 g017
Table 1. Benchmark functions.
Table 1. Benchmark functions.
FunctionNameExpressionRangef(x*)
F1Schaffer N.1 F 1 ( x , y ) = sin 2 ( x 2 + y 2 ) 2 0.5 ( 1 + 0.001 ( x 2 + y 2 ) ) 2 [−100,100]0 for x* = (0,0)
F2Matyas F 2 ( x , y ) = 0.26 ( x 2 + y 2 ) 0.48 x y [−10,10]0 for x* = (0,0)
F3BohachevskyN1 F 3 ( x , y ) = x 2 + 2 y 2 0.3 cos ( 3 π x ) 0.4 cos ( 4 π y ) + 0.7 [−100,100]0 for x* = (0,0)
F4Xin-SheYang N.2 F 4 ( x ) = i = 1 D | x i | exp ( i D sin ( x i 2 ) ) [−2π,2π]0 for x* = (0,……,0)
F5Zakharov F 5 ( x ) = i = 1 D x i 2 + ( i = 1 D 0.5 i x i ) 2 + ( i = 1 D 0.5 i x i ) 4 [−5,10]0 for x* = (0,……,0)
F6Ackley F 6 ( x ) = 20 exp ( 0.2 1 D i = 1 D x i 2 )
      exp ( 1 D i = 1 D cos ( 2 π x i ) + 20 + exp ( 1 )
[−32,32]0 for x* = (0,……,0)
F7Powell F 7 ( x ) = i = 1 D | x i | i + 1 [−1,1]0 for x* = (0,……,0)
F8Rastrigin F 8 ( x ) = 10 D + i = 1 D [ x i 2 10 cos ( 2 π x i ) ] [−5.12,5.12]0 for x* = (0,……,0)
F9Schewel223 F 9 ( x ) = i = 1 D x i 10 [−10,10]0 for x* = (0,0)
F10Alpinen1 F 10 ( x ) = i = 1 D | x i sin ( x i ) + 0.1 x i | [0,10]0 for x* = (0,0)
F11Grienwak F 11 ( x ) = 1 + i = 1 D x i 2 4000 i = 1 D cos ( x i i ) [−600,600]0 for x* = (0,……,0)
F12Brown F 12 ( x ) = i = 1 D 1 ( x i 2 ) ( x i + 1 2 + 1 ) + ( x i + 1 2 ) ( x i 2 + 1 ) [−1,4]0 for x* = (0,……,0)
F13Sphere F 13 ( x ) = i = 1 D x i 2 [−5.12,5.12]0 for x* = (0,……,0)
F14Salomon F 14 ( x ) = 1 cos ( 2 π i = 1 D x i 2 ) + 0.1 i = 1 D x i 2 [−100,100]0 for x* = (0,……,0)
F15Three Hump Camel F 15 ( x ) = 2 x 1 2 1.05 x 1 4 + x 1 6 6 + x 1 x 2 + x 2 2 [−5,5]0 for x* = (0,……,0)
Table 2. Parameter settings of FA and FFA.
Table 2. Parameter settings of FA and FFA.
SymbolQuantityValue
NPopulation size30
IterNumber of iterations1000
αRandomization parameter[0,1]
β0Attractiveness1
γAbsorption coefficient[0,1]
Table 3. Comparative simulation results of FA and FFA for the 12 benchmark test functions.
Table 3. Comparative simulation results of FA and FFA for the 12 benchmark test functions.
FunctionAlgorithmDim. DTheoretical
Optimal Value
Minimum
Value
Computational
Time (s)
Average Speed up
Ratio of 10 Runs
StdMean
F1FA201.6542 × 10−1386.48388712.0295:12.9426 × 10−123.4053 × 10−12
FFA2.2204 × 10−167.1893271.1466 × 10−163.5527 × 10−16
F2FA205.8618 × 10−15110.61790111.7869:12.2829 × 10−154.2810 × 10−15
FFA1.1794 × 10−229.3847925.2167 × 10−223.4229 × 10−22
F3FA208.0766 × 10−10114.39939711.9121:12.2452 × 10−92.2950 × 10−9
FFA1.1102 × 10−169.6036421.0320 × 10−151.4211 × 10−15
F4FA1005.6623 × 10−4165.31833213.0661:11.3542 × 10−85.6625 × 10−8
FFA3.4134 × 10−1112.6525102.4298 × 10−113.6237 × 10−11
F5FA1001.9635 × 10−7102.11122412.0521:11.1191 × 10−73.1165 × 10−7
FFA5.0686 × 10−228.4724789.9126 × 10−385.0686 × 10−22
F6FA1000.0252174.64512112.6941:10.00610.0357
FFA7.5286 × 10−1113.7580155.5179 × 10−118.6060 × 10−11
F7FA2005.4225 × 10−8254.09081611.9330:14.4293 × 10−86.0622 × 10−8
FFA6.0701 × 10−2721.2930911.6065 × 10−252.1326 × 10−25
F8FA2001.7397 × 10−986.13528611.9768:12.2366 × 10−92.5533 × 10−9
FFA7.1054 × 10−157.1918341.1235 × 10−141.0658 × 10−14
F9FA2005.4774 × 10−26199.92338512.2129:16.8916 × 10−267.4821 × 10−26
FFA2.9153 × 10−8416.3698034.8193 × 10−1002.9153 × 10−84
F10FA3001.7988 × 10−4139.50760612.2676:11.5871 × 10−52.1766 × 10−4
FFA5.6687 × 10−911.3720183.6465 × 10−106.0921 × 10−9
F11FA3008.0295 × 10−6130.42922317.9004:12.0834 × 10−71.2770 × 10−6
FFA3.3304 × 10−167.2864052.0572 × 10−166.5503 × 10−16
F12FA3002.0832 × 10−4312.02158216.2503:12.1256 × 10−51.7312 × 10−4
FFA3.5141 × 10−1619.2009452.1964 × 10−173.5897 × 10−16
Table 4. Stability of FFA in higher dimensions.
Table 4. Stability of FFA in higher dimensions.
FunctionAlgorithmDim. DTheoretical Optimal ValueMinimum ValueStdMeanComputational Time
of 10 Runs (Seconds)
Iterations
F13FFA5003.7950 × 10−162.9222 × 10−173.9330 × 10−1611.7435431000
1008.9766 × 10−165.3287 × 10−179.2937 × 10−1612.630883
1501.5083 × 10−154.4389 × 10−171.5223 × 10−1513.399011
2002.1964 × 10−158.7426 × 10−202.1966 × 10−1514.696007
F14FFA5001.9615 × 10−95.8730 × 10−112.0092 × 10−912.6191301000
1003.0618 × 10−96.2137 × 10−113.1208 × 10−913.483702
1503.9315 × 10−91.7846 × 10−113.9107 × 10−914.451983
2004.6921 × 10−91.1344 × 10−114.6959 × 10−915.718014
F15FFA5001.1834 × 10−217.7571 × 10−222.0847 × 10−218.6761271000
1001.3134 × 10−219.5957 × 10−221.7686 × 10−219.238064
1501.6926 × 10−214.3289 × 10−213.9281 × 10−2110.033184
2002.8146 × 10−213.7922 × 10−215.1335 × 10−2111.103394
Table 5. Switching sequence by using Hall Effect sensor signals.
Table 5. Switching sequence by using Hall Effect sensor signals.
Electrical Angle (°)Sequence NumberHall SensorsPhase CurrentSwitch Closed
HaHbHciaibic
0–601101+offS1S4
60–1202100+offS1S6
120–1803110off+S3S6
180–2404010+offS3S2
240–3005011off+S5S2
300–3606001off+S5S4
Table 6. Parameters of BLDC motor.
Table 6. Parameters of BLDC motor.
ParametersValues
Number of pole4
Nominal voltage vd114 V
Stator resistance R1.2 Ω
Stator inductance L1.2 mH
Torque coefficient kt0.3262 Nm/A
Back-EMF coefficient ke0.3262 Vs/rad
Rotor inertia J0.00085 kgm2
Rated speed Nr3000 rpm
Friction coefficient kf0.0001 Nms/rad
Table 7. kp, ki parameters obtained by various objective functions and various algorithms.
Table 7. kp, ki parameters obtained by various objective functions and various algorithms.
AlgorithmParameters/CriterionIAEISEITAEITSE
FFAkp_FFA18.1924.524.5624.06
ki_FFA4468.84435.24132.24002.32
FAkp_FA26.5420.2124.0824.08
ki_FA2207.23615.83451.22996.2
GAkp_GA19.4523.1419.1124.76
ki_GA1685.12474.53220.22896.1
PSOkp_PSO25.817.6822.0621.72
ki_PSO2081.53440.83451.23601.66
ABCkp_ABC24.5119.5320.1624.17
ki_ABC3140.93796.63650.82901.12
Table 8. Performance of the different controllers.
Table 8. Performance of the different controllers.
ControllerCriterionRise Time(s)Settling Time(s)PeakPeak Time(s)% Overshoot
FFA_PIIAE0.02170.4133067.30.02642.2497
FA_PI0.02190.07223041.10.02891.3708
GA_PI0.02190.07313038.80.02931.2922
PSO_PI0.02190.07303039.90.02891.3299
ABC_PI0.02190.05793046.50.02891.5486
FFA_PIISE0.02170.04783058.20.02631.7516
FA_PI0.02180.04883060.70.02642.0226
GA_PI0.02190.06463044.30.02901.4769
PSO_PI0.02170.04883062.40.02652.0804
ABC_PI0.02170.04883062.10.02642.0713
FFA_PIITAE0.02180.04883051.50.02631.7163
FA_PI0.02190.05463049.70.02631.6554
GA_PI0.02180.04883058.90.02641.9620
PSO_PI0.02190.06123055.20.02631.8398
ABC_PI0.02180.04883061.20.02642.0393
FFA_PIISTE0.02180.05133051.00.02631.7013
FA_PI0.02190.06133046.40.02901.5480
GA_PI0.02190.06133046.40.02901.5473
PSO_PI0.02180.05133058.90.02631.9625
ABC_PI0.02190.05963045.80.02901.5269
Table 9. Simulation time of the five algorithms.
Table 9. Simulation time of the five algorithms.
Simulation Time (s)
IterationFFAFAGAPSOABC
50108.53284.15119.55242.23135.95
100216.57570.06239.77486.82268.20
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Bazi, S.; Benzid, R.; Bazi, Y.; Rahhal, M.M.A. A Fast Firefly Algorithm for Function Optimization: Application to the Control of BLDC Motor. Sensors 2021, 21, 5267. https://doi.org/10.3390/s21165267

AMA Style

Bazi S, Benzid R, Bazi Y, Rahhal MMA. A Fast Firefly Algorithm for Function Optimization: Application to the Control of BLDC Motor. Sensors. 2021; 21(16):5267. https://doi.org/10.3390/s21165267

Chicago/Turabian Style

Bazi, Smail, Redha Benzid, Yakoub Bazi, and Mohamd Mahmoud Al Rahhal. 2021. "A Fast Firefly Algorithm for Function Optimization: Application to the Control of BLDC Motor" Sensors 21, no. 16: 5267. https://doi.org/10.3390/s21165267

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