Next Article in Journal
Chemical Composition and Antimicrobial Activity of the Essential Oils of Three Closely Related Hypericum Species Growing Wild on the Island of Crete, Greece
Next Article in Special Issue
System Design and Monitoring Method of Robot Grinding for Friction Stir Weld Seam
Previous Article in Journal
Development of Equipment and Application of Machine Learning Techniques Using Frequency Response Data for Cap Damage Detection of Porcelain Insulators
Previous Article in Special Issue
Smooth Fractional Order Sliding Mode Controller for Spherical Robots with Input Saturation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Multiple Swarm Fruit Fly Optimization Algorithm Based Path Planning Method for Multi-UAVs

1
Faculty of Information Technology, Beijing University of Technology, Beijing 100124, China
2
Beijing Key Laboratory of Computational Intelligence and Intelligent System, Beijing 100124, China
3
Engineering Research Center of Digital Community, Ministry of Education, Beijing 100124, China
4
Beijing Laboratory for Urban Mass Transit, Beijing 100124, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2020, 10(8), 2822; https://doi.org/10.3390/app10082822
Submission received: 27 February 2020 / Revised: 30 March 2020 / Accepted: 15 April 2020 / Published: 19 April 2020
(This article belongs to the Special Issue Advances in Robotics-Based Automation Systems)

Abstract

:
The path planning of unmanned aerial vehicles (UAVs) in the threat and countermeasure region is a constrained nonlinear optimization problem with many static and dynamic constraints. The fruit fly optimization algorithm (FOA) is widely used to handle this kind of nonlinear optimization problem. In this paper, the multiple swarm fruit fly optimization algorithm (MSFOA) is proposed to overcome the drawback of the original FOA in terms of slow global convergence speed and local optimum, and then is applied to solve the coordinated path planning problem for multi-UAVs. In the proposed MSFOA, the whole fruit fly swarm is divided into several sub-swarms with multi-tasks in order to expand the searching space to improve the searching ability, while the offspring competition strategy is introduced to improve the utilization degree of each calculation result and realize the exchange of information among various fruit fly sub-swarms. To avoid the collision among multi-UAVs, the collision detection method is also proposed. Simulation results show that the proposed MSFOA is superior to the original FOA in terms of convergence and accuracy.

1. Introduction

Unmanned aerial vehicles (UAVs) have become an area of great concern to many governmental and military organizations around the world. The autonomy level of the UAVs depends on the methodology used to control the vehicle and plan its flight path [1]. Therefore, path planning, which is to generate a feasible path between two points that has an optimal or near-optimal performance satisfying constraint conditions, is one of the most important challenges in the autonomous navigation process of UAVs [2]. Typically, in increasingly complex mission environments, only one UAV usually cannot meet the mission requirements, so there are often multiple UAVs (multi-UAVs) on the same mission at the same time [3]. This paper mainly discusses the path planning of multi-UAVs cooperation. To solve the cooperative path planning problem of multi-UAVs, an approach is proposed: Priority is set to each UAV. The first priority UAV does not need a plan. Its sub-goal is the final goal. The UAV with second priority plans the path to avoid collision with the first priority UAV. The UAV with the third priority needs to plan its path to avoid collision with the former UAVs [4]. It is proven that finding the optimal path is an non-deterministic polynomial complete problem [2]. As the scale of the problem increases, the complexity of the problem increases rapidly. In many existing works, the optimal path is always considered as the shortest path, and the deterministic search algorithm is used to find the shortest path. However, the optimal path of the UAV should be considered to be related to the minimum distance path, average height, fuel consumption, radar exposure, and so on, which make the problem more complex [5]. In order to reduce the computational complexity, many approaches have been applied to the path planning problem, which can be classified into traditional methods and bionic inspired algorithms. The traditional path planning methods contain the A* search algorithm [6], the polynomial optimization method [7], and artificial potential field based methods [8], while the bionic inspired algorithms contain the simulated annealing algorithm (SAA) [9], genetic algorithm (GA) [5], differential evolution (DE) [10], artificial bee colony (ABC) [11], particle swarm optimization (PSO) algorithm [12,13], and ant colony optimization (ACO) [14]. Among these bionic inspired algorithms, ACO is usually applied to the combinational optimization problems [14,15], while the others are usually used to solve the continuous optimization problems. As a kind of population-based random search algorithm, PSO has been widely applied to UAV path planning [16]. The basic idea of PSO comes from the behavior of birds that randomly search for food within an area. To simulate this situation, the particle swarm was developed as a useful computational technique for solving the optimization problem [17].
As a novel bio-inspired technique, the fruit fly optimization algorithm (FOA) was first proposed by Pan in 2011 [18], inspired by the food finding behavior of fruit flies. FOA is well-known for its simple principle, few adjustable parameters, strong global optimization capability, and fast convergence speed [19]. So far, FOA has been used in a variety of applications, such as general regression neural network parameters optimization [20,21] and the tuning of controller parameters [22]. Several improved versions of FOA were proposed by researchers to enhance the search efficiency and global search ability of the basic FOA; these include the multi-swarm fruit fly optimization algorithm (MFOA) [23] and improved fruit fly optimization (IFFO) [24], to name a few.
In this paper, the new multiple swarm fruit fly optimization algorithm (MSFOA) is proposed. In the MSFOA, the whole fruit fly swarm are divided into several sub-swarms with multi-tasks. In the early searching stage, the sub-swarms are inclined to global searching, while at the end of the searching stage, they are inclined to local searching. The strategy can expand the searching space and improve the global and local searching ability. Then, the offspring competition strategy is introduced to improve the utilization degree of each calculation result and realize the exchange of information among various fruit fly sub-swarms. A path planner for multi-UAVs based on the proposed MSFOA is designed to find the optimal path for each UAV in complex three-dimensional environments. A collision detection method is proposed to avoid collision among multi-UAVs. The simulation results show that the proposed MSFOA-based path planner can effectively solve the coordinated path planning problem among multi-UAVs.
The rest of the paper is arranged as follows: The Section 2 introduces the basic FOA technique. In Section 3, the proposed MSFOA and its application to multi-UAV path planning are presented. Then, the comparison experiment results are listed and discussed in Section 4. Section 5 gives the conclusion.

2. Overview of Fruit Fly Optimization Algorithm

Fruit flies have a superior sense of smell and vision [18]. In their search for food, fruit flies can not only use their sense of smell to detect smells in the air, but also can use their sense of sight to locate food and other flies. In the FOA, the flies first use their sense of smell to find the direction of the food source, and then fly toward the direction with the greatest smell concentration. After that, the fruit flies use their vision to find the location of the food and other flies and fly to the direction obtained by their vision.
Without loss of generality, the global optimization problem in the continuous domain can be summarized as
min F ( x ) s . t . x j [ X min , X m a x ] , j = 1 , 2 , , D
where F(x) is the objective function with the D-dimensional decision variable x = (x1, x2, …, xD) and Xmin and Xmax are the lower and upper bounds of the decision space, respectively.
The parameters of FOA are the population size Mpop and the maximum number of iterations NC. Firstly, the fruit fly swarm location (xbest, ybest) is randomly initialized in the decision space. The main process of the FOA contains two parts, namely olfactory search and visual search [1,18].
(1) Olfactory search
In the olfactory search process, the fruit fly swarm generates in total Mpop new locations of the food source that is randomly around its current location using random strategy, which is given by
{ x i = x best + random ( 1 , 1 ) y i = y best + random ( 1 , 1 )
where xi and yi, i = 1, 2, …, Mpop, denote the location coordinate of the i-th fruit fly and random(−1,1) is the random value in the range of (−1,1).
For each location produced in the olfactory search process, its smell concentration judgement Si is the reciprocal of the distance between the location and the origin, as follows
{   D i = x i 2 + y i 2 S i = 1 / D i
In the FOA framework, the smell concentration judgement Si corresponds to the candidate solution of the objective function F(.) in the decision space. The smell concentration of the food source can be calculated using the smell concentration judgement as follows
s m e l l i = F ( S i )
(2) Visual search
The visual search process of the fruit fly swarm can be regarded as a greedy selection procedure, where the fruit fly swarm observes all the locations generated via the above olfactory search and finds out the best location that has the minimum smell concentration, as follows
I n d e x = arg min i ( s m e l l i )
Then the best smell concentration smellindex generated via the olfactory search is compared with the smell concentration smellbest of the original fruit fly swarm location (xbest, ybest). If smellindex < smellbest, then the original location (xbest, ybest) will be replaced by the newly generated location (xindex, yindex) and the fly swarm will fly towards the new location by using the visual search. The visual search can be described as follows
{ x best = x I n d e x y best = y I n d e x if s m e l l I n d e x < s m e l l best s m e l l best = s m e l l I n d e x
The olfactory and visual search processes are repeated many times until a program termination condition is reached. The general process of the FOA in solving the minimum problem minF(x) is described in Algorithm 1.
Algorithm 1: Process of the FOA
/*Initialization*/
1Set the population size M pop and the max number of iterations N C .
Randomly initialize the fruit fly swarm’s location ( x best ,   y best ) in the search space.
/* Iterative search */
2forn = 1: N C
3 /* Olfactory search */
for i = 1: M pop
4   x i = x best + random(–1,1)
5 y i = y best + random(–1,1)
 /* Calculate the smell concentration */
6 D i = x i 2 + y i 2
7 S i = 1 / D i
8 s m e l l i = F ( S i )
9end for
 /* Visual search */
10 I n d e x = arg min i ( s m e l l i )
11if s m e l l I n d e x is smaller than s m e l l best of the fruit fly swarm’s location ( x best ,   y best ) then
12  Fruit flies move to the location ( x I n d e x ,   y I n d e x ) and update the smell concentration:
13 x best = x I n d e x
14 y best = y I n d e x
15 s m e l l best = s m e l l I n d e x
16end if
17end for

3. UAV Path Planning Method Based Modified Fruit Fly Optimization Algorithm

In this section, the MSFOA is proposed to enhance the searching ability of the original FOA and is applied to the path planning for multi-UAVs. The symbol description of the main variables appearing in the proposed MSFOA is listed in Abbreviations.

3.1. MSFOA

3.1.1. Motivation

The FOA converges quickly when applied to a single UAV path planning. Yet when it is applied to planning the path of multi-UAVs, it is easy to get lost in the local optimal solution. The original FOA is random when searching the solution, which means the convergence speed is fast in the early stage, but it is difficult to converge towards the optimal solution in the later stage. When the fruit fly’s path is near the optimal solution, the algorithm may ignore the path, because the path length and the threating level and other constraints are considered. The optimal path is often between the edge of the threating cylinder or the valley. When the fly finds a path near the optimal solution, the path usually falls into the threating cylinder or through the interior of the mountain. This path with a high smell concentration is easy to eliminate but near the optimal solution. When the algorithm is used to plan the path for a simple scenario, it can be repeated many times to get the optimal solution, but when the algorithm is applied to some complex scenarios, such as multi-UAVs path planning or path planning in complex scenarios, the convergence ability of FOA is obviously insufficient.
In FOA, there is no communication between fruit flies and the direction of the path depends only on the given random direction and the random distance, so the ability to converge in solving complex problems is insufficient. In order to overcome the shortfalls of the FOA, increasing the searching ability and communication between fruit flies can improve the convergence ability of the algorithm. At the same time, in order to avoid the problem of possible collision when planning multiple UAVs paths, this algorithm also adds the method of checking for collisions.

3.1.2. Multi-Swarm with Multi-Tasks Strategy

The searching process can be separated by global searching and local searching. Global searching occurs in the early stage of searching, while local searching occurs in the end stage of searching. In this paper, global searching and local searching are considered as different tasks, which should employ different searching strategies. This paper uses a threshold to confirm the two different stages. When the cost is larger than the threshold value, the algorithm is in the global searching period, when the cost is smaller than the threshold value, the algorithm is in the local searching period.
In the global searching period, it is important to enhance the searching space to improve global searching ability since the size of the searching space has a significant impact on the results. FOA only uses the single swarm approach to search for all fruit flies from a single location, thus when the searching space is small, the searching capacity is insufficient. In MSFOA, the searching space of the algorithm can be expanded linearly by using multi-swarm fruit fly at the same time and starting from many different positions. The fruit fly population Mpop is divided equally into G swarms. G is the total amount of swarms. Every fruit fly intends to have a big step in searching as shown in Equations (10) and (11). sin ( ( π / 2 ) * random ( 1 , 1 ) ) is introduced to map random ( 1 , 1 ) near −1 and 1.
X i ( g ) = x best ( g ) + sin ( ( π / 2 ) * random ( 1 , 1 ) )
Y i ( g ) = y best ( g ) + sin ( ( π / 2 ) * random ( 1 , 1 ) )
where X i ( g ) and Y i ( g ) , i = 1, 2, …, Mpop/G, g = 1, 2, …, G denote the position of the i-th fruit fly in the g-th swarm, while x best ( g ) and y best ( g ) are the concentration position of the g-th swarm.
In the local searching period when fruit fly swarms are near the global optimum, it is important to reduce searching space for further convergence; fruit flies should pay attention to the points near themselves to have a better result. The step of searching is dwindled.
X i ( g ) = x best ( g ) + R * random ( 1 , 1 )
Y i ( g ) = y best ( g ) + R * random ( 1 , 1 )
where R is the searching step dwindled parameter.

3.1.3. Competitive Strategies of Offspring

In order to avoid multi-swarm falling into local optimum, each swarm is independent in visual search and olfaction search, while the information exchange occurs in the competition of offspring, which is explained in detail below. In this way, not only can the multi-swarms not get into the local optimum at the same time, but also the information exchange between the species cannot be guaranteed.
The competition strategy of the offspring uses the optimal individual to cross with other flies at random to generate a new swarm at the same scale and select a new optimal individual. That is, the swarm in the same number has two optimal individuals, one comes from the old swarm, the other from the new swarm. The optimal solution of the swarm is obtained after competition between two optimal individuals.
The effect of this method is when fruit fly A is near the optimal solution but its smell concentration is high, but the individual from A hybridized with random fruit fly B has the path information of both fruit fly A and B; the path information of the fruit fly can be obtained by distributing the weight of the path data of the two flies. This strategy can increase the probability that the fruit fly near the optimal solution will be selected by the algorithm. The procedure for generating the i-th new individual of the g-th swarm is as follows:
{ S old ,   i ( g ) = ( X i ( g ) ) 2 + ( Y i ( g ) ) 2 s m e l l old ,   i ( g ) = F ( S old ,   i ( g ) )
I n d e x old ( g ) = arg min i ( s m e l l old ,   i ( g ) )
x oldbest ( g ) = X I n d e x old ( g ) ( g ) y oldbest ( g ) = Y I n d e x old ( g )   ( g )
X new ,   i ( g ) = c o e 1 * x oldbest random ( 1 , G ) + c o e 2 * X i ( g ) y new ,   i ( g ) = c o e 1 * y oldbest random ( 1 , G ) + c o e 2 * Y i ( g )
where random ( 1 ,   G ) produces random integers between 1 and G. X new ,   i ( g ) and Y new ,   i ( g ) mean the position of the i-th fly in the g-th new swarm. c o e 1 and c o e 2 are the weights of parental path data, satisfying:
c o e 1 + c o e 2 = 1
The calculation of best smell concentration is given by:
{ S new ,   i ( g ) = ( X new ,   i ( g ) ) 2 + ( Y new ,   i ( g ) ) 2 s m e l l new ,   i ( g ) = F ( S new ,   i ( g ) )
I n d e x new ( g ) = arg min i ( s m e l l new , i ( g ) )
Then all the fruit flies in every swarm fly to the point with the minimum smell concentration of each swarm. If the smell concentration of the offspring is less than the smell concentration of their parent ( s m e l l new ,   I n d e x new ( g ) ( g ) < s m e l l old ,   I n d e x old ( g ) ( g ) < s m e l l best ( g ) ), then:
{ x best ( g ) = X new ,   I n d e x new ( g )   ( g )   y best ( g ) = Y new ,   I n d e x new ( g ) ( g ) s m e l l best ( g ) = s m e l l new ,   I n d e x new ( g ) ( g )
Otherwise ( s m e l l old ,   I n d e x old ( g ) ( g ) < s m e l l new ,   I n d e x new ( g ) ( g ) < s m e l l best ( g ) ):
{ x best ( g ) = X I n d e x old ( g ) ( g )   y best ( g ) = Y I n d e x old ( g ) ( g ) s m e l l best ( g ) = s m e l l old ,   I n d e x old ( g ) ( g )
if s m e l l best ( g ) is smaller than s m e l l old ,   I n d e x old ( g ) ( g ) or s m e l l new ,   I n d e x new ( g ) ( g ) , x best ( g ) and y best ( g ) remain unchanged; where x best ( g ) and y best ( g ) are the location of the g-th fruit fly swarm.

3.1.4. The Process of MSFOA

The whole process of the MSFOA can be described by Algorithm 2.
Algorithm 2: MSFOA
/*Initialization*/
1Set the number of the fruit fly population Mpop, the max number of iterations NC, swarms’ initial position [xbest, ybest], swarm number g, the threshold, genetic coefficient of hybridization coe1 and coe2, the parameter R.
2fornc = 1: NC
3for g = 1: G
 /* Multi-swarm with multi-task searching strategy */
4  for i = 1: Mpop/G
5   if s m e l l best ( g ) is larger than threshold
6     X i ( g ) = x best ( g ) + sin ( ( π / 2 ) * random ( 1 , 1 ) )
7     Y i ( g ) = y best ( g ) + sin ( ( π / 2 ) * random ( 1 , 1 ) )
8   else
9     X i ( g ) = x best ( g ) + R * random ( 1 , 1 )
10     Y i ( g ) = y best ( g ) + R * random ( 1 , 1 )
11   end
   /* Calculate smell concentration */
12    S old ,   i ( g ) = ( X i ( g ) ) 2 + ( Y i ( g ) ) 2
13    s m e l l old ,   i ( g ) = F ( S old ,   i ( g ) )
   /*Vision searching in old swarms*/
14    I n d e x old ( g ) = arg min i ( s m e l l old , i ( g ) )
15  end for
16end for
 /*Competitive strategies of offspring*/
17for g = 1: G
18  for i = 1: Mpop/G
19    X new ,   i ( g ) = c o e 1 * x oldbest random ( 1 , G ) + c o e 2 * X i ( g )
20    Y new ,   i ( g ) = c o e 1 * y oldbest random ( 1 , G ) + c o e 2 * Y i ( g )
   /* Vision searching in new swarms */
21    S new ,   i ( g ) = ( X new ,   i ( g ) ) 2 + ( Y new ,   i ( g ) ) 2
22    s m e l l new ,   i ( g ) = F ( S new ,   i ( g ) )
23    I n d e x new ( g ) = arg min i ( s m e l l new , i ( g ) )
24  end for
25end for
 /* Competitive strategy of offspring */
26for g = 1: G
27  Competition of offspring and visual searching in each swarm by formulas (18) and (19)
28end for
29end for
/*Output*/
30Find the best individual from the G swarms and export it.

3.2. MSFOA-Based Path Planning

3.2.1. Problem Modeling

UAV path planning needs to adapt to current terrain and physical world constraints, such as terrain undulation, gravitational acceleration, etc. In addition, the path of the UAV cannot exceed the limits of the UAV itself, such as turning radius, glide angle, flying speed, minimum flying height, and so on. Within these limits, an optimal flight path is planned for the UAV, which can avoid a specific area and reach the target point with less energy consumption in a shorter time. The collision risk between UAVs needs to be considered in the three-dimensional (3D) cooperative path planning of multi-UAVs.
Path representation is a key problem in path planning, and the grid-based map [15] and spline curve [1,5] are two common methods. Zhang proves that by using the B-spline-based path representation strategy, the path can be constructed using a relatively smaller number of parameters than using a complete geometric description of the path [1]. Thus, in charting our course, the algorithm uses very few control points to record the path. When the algorithm needs to use the full path, it will use the control points to generate the whole path.
In this paper, the objective function divides the path constraints into the following categories: path length, threat cost, altitude cost, terrain constraint, corner constraint, and descent angle constraint. All the constraints constitute the objective function. The algorithm uses the objective function to express the quality of a path. Before calculating the objective function, it is necessary to generate a complete path with path points before calculating. The objective function is calculated as follows:
  J = J H + J L + J T + C H + C T + C G + J P
where the objective function includes the altitude cost JH, the length cost JL, the threat cost JT, the terrain constraint CH, the corner constraint CT, the climb down constraint CG, and the collision risk JP, which are described in detail as follows.
The altitude cost is determined by all points along the path, which reflects the flying altitude of the UAV above the ground. When flying at a low altitude, the UAV can benefit from terrain masking to avoid unknown radars [1]. Suppose the whole UAV path is represented by k points, if the variable z n is the height of the n-th point in the path, and hmin is the minimum flying height of the UAV, then the altitude cost JH adds up the height of all the points along the path on the ground as follows:
  J H = n = 1 k ( z n h m i n )
The path length cost JL reflects the flight length of the entire UAV path, which calculates and adds the distance between any two adjacent points to get the total length as follows:
J L = n = 1 k 1 l n with l n = ( x n + 1 x n ) 2 + ( y n + 1 y n ) 2 + ( z n + 1 z n ) 2
where the variable xn is the x coordinate of the n-th point in the path, yn is the y coordinate of the n-th point in the path, and zn is the z coordinate of the n-th point in the path.
The terrain constraints are determined by the length of the path in the underground section. This symbol is used to punish those paths that are not entirely on the ground. The variable p is the information of the map, and function H(p) means the height of the current point in map p.
C H = n = 1 k T n with T n = { H ( p ) z n , if   z n < H ( p ) 0 , if   z n > H ( p )
In this paper, the threat around the threat point is only related to the distance, so the threat area is approximated as a cylinder, within a certain range; the closer to the threat point, the greater the degree of threat. The variable n r is the amount of threaten points. T de ( i ) is the coordinate of the i-th threaten points.
  J T = n = 1 k 1 l n · i = 1 n R T de ( i )
The minimum angle of turning is determined by the maximum speed and gravitational acceleration. The turning angle of each point in the path is calculated. If current turning angle is greater than the max turning angle, and the turning angle constraint increases iteratively. Iterations are added to quickly filter out individuals who do not exceed the limit. The calculation is as follows:
C T = n = 1 k 1 g n with g n = { C T ,   if   φ n > φ m a x    0 ,   if   φ n < φ m a x
where φ k denotes the turning angle in the n-th point in the path and φ m a x denotes the maximum turning angle of the UAV.
CG is used to constrain the slope at the current point to meet the maximum climb slopes α and minimum climb slopes β .
C G = n = 1 k 1 g S n with g S n = { C   ,   if   β n S n α n   0 ,   if   β n S n   or   S n α n
where
  α n = 1 . 5377 × 10 10 z n 2 2 . 6997 × 10 5 z n + 0 . 4211 β n = 2 . 5063 × 10 9 z n 2 6.3014 × 10 6 z n 0.3257 S n = z n + 1 z k n ( x n + 1 x n ) 2 + ( y n + 1 y n ) 2
The cost JP is used to assess the risk of collisions between UAVs. The risk of collision between UAVs is determined by the time it takes to reach two points very close together. When planning the path of multi-UAVs, first, these UAVs are numbered according to the degree of importance and then the UAVs with the former number are given priority of passage on the map because each UAV has to avoid the UAV with greater priority.
J P n = k = 1 N 1 P C · Δ t i m e _ k
where PC is the penalty factor, N is the number of current UAV, and N is the number of points in the flight path generated by the B-spline curve. Δ t i m e _ k is the time difference between the two UAVs when they arrive at the point where a possible collision could occur.

3.2.2. Application of MSFOA to Multi-UAVs Path Planning

(1) Collision detection method
Collision avoidance is an important part of multi-UAVs path planning. Due to the huge space in the 3D map, this method only detects the possibility of collision after the path is generated. When the n-th UAV’s flight path is going to check for collision, this method will check it in pairs with the previous n − 1 UAV’s flight path. The n-th path is called the path to be detected, and the previous n − 1 is called the air_pathn−1. For each point on the detection path, the distance from each point between the detection path and air_pathn−1 is calculated. If the distance is less than the minimum safe distance, the two points will be called a possible collision point, and the path will be punished. The mathematical descriptions are as follows:
  J P = m = 1 n i = 1 n J P i with Δ t i m e _ k = { C * t c r a s h 3 , t c r a s h < 0 . 5 0 , t c r a s h 0 . 5
where J P i is the collision risk between the i-th UAVs and the m-th UAVs, the parameter C is the time penalty factor, and tcarsh is the time difference between the two UAVs at the point of possible collision, determined by the following formula:
tcarsh = v/(dis1dis2)
(2) MSFOA based multi-UAVs path planning
In order to further explain the MSFOA based path planning, the specific steps of multi-UAVs path planning for MSFOA is elaborated. The algorithm records the location of the d-th control point of the i-th individual fruit fly in swarm g with X i ( g ) ,   d and Y i ( g ) ,   d , d = 1, …, D, where D denotes the number of control points.
S i ( g ) ,   d = ( X i ( g ) , d ) 2 + ( Y i ( g ) , d ) 2
where S i ( g ) ,   j is the smell concentration judgment. The path is generated by
{ p a t h i ( x ) [ k ] = S i ( g ) ,   k P m a x ( x ) p a t h i ( y ) [ k ] = S i ( g ) ,   k + D P m a x ( y ) p a t h i ( z ) [ k ] = S i ( g ) ,   k + 2 D P m a x ( z )
where P m a x ( x ) , P m a x ( y ) , P m a x ( z ) is the boundary of the map in three dimensions. p a t h i ( x ) is the coordinate on the X axis of all the control points in the path,   p a t h i ( y ) is the coordinate on the Y axis of all the control points in the path, and p a t h i ( z ) is the coordinate on the Z axis of all the control points along this path. k represents the number of control points, where k values range from 2 to D–1. Then add the starting and ending points:
{ p a t h i ( x ) [ 1 ] = X S , N   p a t h i ( y ) [ 1 ] = Y S , N p a t h i ( z ) [ 1 ] = Z S , N p a t h i ( x ) [ D + 2 ] = X T p a t h i ( y ) [ D + 2 ] = Y T p a t h i ( z ) [ D + 2 ] = Z T
where X S , N   ,   Y S , N ,   Z S , N is the beginning of the path of the N-th UAV, and X T ,   Y T ,   Z T is the end of the path of the UAV. There is no essential difference between the multi-origin and multi-destination model in this paper. The MSFOA for multi-UAVs path planning is implemented as follows:
Step 1: Determine information of the UAVs mission, including starting coordinates ( X S ,   N , Y S ,   N , Z S ,   N ) and ending coordinates ( X T , Y T , Z T ). The number of UAVs required for the mission N u m , maximum velocity vmax, maximum turn overload nmax, and minimum altitude hmin. Mission map information p, boundary P m a x x ,   P m a x y ,   P m a x z , and the number D of control points that each UAV needs to plan out.
Step 2: Identify enemy ground weapons, including threat types such as radar, missiles, anti- aircraft guns, weapon positions (Xthreat, j, Ythreat, j), and their respective threat ranges.
Step 3: Set up the parameters of MSFOA, including maximum iteration number NC, the number of new swarms G, the fruit fly population size Mpop, the threshold, the searching step dwindled parameter R, and cross genetic coefficient coe1 and coe2.
Step 4: Let num = 1.
Step 5: Let nc = 1 and randomly generate the location for each swarm, ( x best ( 1 ) , 1 , y best ( 1 ) , 1 )…( x best ( 1 ) ,   D , y best ( 1 ) ,   D ) …( x best ( G ) , 1 , y best ( G ) , 1 )…( x best ( G ) ,   D , y best ( G ) ,   D ).
Step 6: Let g = 1, i = 1, d = 1.
Step 7: Generate the random locations for the food source using the olfactory according to Equation (34) if s m e l l best ( g ) is larger; otherwise, generate the new locations according to Equation (35), as follows
X i ( g ) ,   d = x best ( g ) ,   d + sin ( ( π / 2 ) * random ( 1 , 1 ) ) Y i ( g ) ,   d = y best ( g ) ,   d + sin ( ( π / 2 ) * random ( 1 , 1 ) )
X i ( g ) ,   d = x best ( g ) ,   d + R * random ( 1 , 1 ) Y i ( g ) ,   d = y best ( g ) ,   d + R * random ( 1 , 1 )
Step 8: Update the smell concentration judgement according to the formula below:
S old ,   i ( g ) ,   d = ( X i ( g ) ,   d ) 2 + ( Y i ( g ) ,   d ) 2
if S old ,   i ( g ) ,   d is bigger than 1, jump to step 7, otherwise jump to step 9.
Step 9: if d < D, let d = d + 1, jump to step 7, otherwise jump to step 10.
Step 10: Generate the path of this fruit fly pathi using Equations (31)–(33). Update smell concentration by the formula below
s m e l l old ,   i ( g ) = J ( p a t h i )
where J is described in Equation (20). If i < Mpop/G, then let i = i + 1, d = 1 and jump to step 7, otherwise jump to step 11.
Step 11: Find out the old best in the g-th swarm ( x oldbest ( g ) , 1 , y oldbest ( g ) , 1 ), …, ( x oldbest ( g ) ,   D , y oldbest ( g ) ,   D ) using Equations (12) and (13). If g < G, then let g = g + 1, d = 1, i = 1 and jump to step 7, otherwise jump to step 12.
Step 12: Let g = 1, i = 1, d = 1.
Step 13: Generate fruit fly in new swarms according to the equation below:
X new ,   i ( g ) ,   d = c o e 1 * x oldbest random ( 1 , G ) ,   d + c o e 2 * X i ( g ) ,   d Y new ,   i ( g ) ,   d = c o e 1 * y oldbest random ( 1 , G ) ,   d + c o e 2 * Y i ( g ) ,   d
Step 14: Update the smell concentration judgement according to the equation below:
S new ,   i ( g ) ,   d = ( X new ,   i ( g ) ,   d ) 2 + ( Y new ,   i ( g ) ,   d ) 2
if S new ,   i ( g ) ,   d is bigger than 1, jump to step 6, otherwise jump to step 8.
Step 15: if d < D, let d = d + 1, jump to step 13, otherwise jump to step 16.
Step 16: Generate the path of this fruit fly pathi by using Equations (31)–(33). Update smell concentration by the equation below:
s m e l l new ,   i ( g ) = J ( p a t h i )
If i < Mpop/G, then let i = i + 1, d = 1 and jump to step 13, otherwise jump to step 17.
Step 17: Find out the index of new best in the g-th new swarm I n d e x new ( g ) by Equation (17).
Step 18: All the fruit flies in the g-th swarm fly to the location with the minimum smell concentration according to Equations (18) and (19). If g < G, then let g = g + 1, d = 1, i = 1 and jump to step 13, otherwise jump to step 19.
Step 19: If nc < NC, let nc = nc + 1 and jump to step 5, otherwise jump to step 20.
Step 20: If num < Num, generate and output the path of the num-th UAV then let num = num + 1 and jump to step 5; otherwise, end and output the UAV paths.

4. Results and Discussion

This section discusses the simulations used to assess the performance of our proposed algorithm in solving the UAV path planning problem. Seven algorithms are tested under three scenarios, including MSFOA, FOA, PSO, DE, ABC, IFFO, and MFOA. The 3D stereo displays of three scenarios are shown in Figure 1. The algorithm is coded using Matlab-2018b. Owing to their stochastic nature, evolutionary algorithms may arrive at better or worse solutions than they previously reached during their search for new solutions. For this reason, every tested algorithm is run 40 times independently for each scenario and the statistical results are used for performance evaluation and comparison. We coded the above algorithms and set the parameters according to their references. The main parameters of the seven tested algorithms are detailed in Table 1. The best values of each scenario are highlighted using boldface. The parameter configurations are all based on the suggestions in the corresponding references; where these values have a fair comparison, the same maximum iteration number is used for all algorithms as the stopping criterion, while the population size is set as 100 for all algorithms.
The 3D stereo displays of the seven UAV paths in the three scenarios are shown in Figure 2, Figure 3 and Figure 4, where (a)–(g) correspond to MSFOA, FOA, PSO, DE, ABC, IFFO, and MFOA, respectively. The statistical results of MSFOA, FOA, PSO, DE, ABC, IFFO, and MFOA during 40 runs on the three different scenarios are listed in Table 2, where the best of the cost values of each UAV are recorded.
For the first scenario, all seven tested algorithms find the safe flight path for UAVs. It can be seen that the best path generated by MSFOA flies the smoothest. In comparing these results in the first scenario column in Table 2, it is observed that the MSFOA obtains the minimum best among the algorithms, which indicates that MSFOA has the most powerful optimization ability in the statistical sense. Figure 3 displays the experimental results of the second test scenario. For this test scenario, DE and IFFO come into the threat areas. From Table 2, it can be seen that MSFOA achieves the smallest mean cost value. Furthermore, the result of the third scenario is shown in Figure 4. It is obvious that MSFOA has the best path for UAVs. In the third scenario column of Table 2, the cost of MSFOA is significantly decreased in comparison to the other algorithms.
Above all, these experimental results demonstrate that the MSFOA still maintains a higher performance than the FOA, PSO, DE, ABC, and two other modified FOA versions.
The convergence curves of the average best cost values are displayed in Figure 5, Figure 6 and Figure 7. In the first scenario, it can be seen that DE, FOA, and IFFO show inferior convergence. MFOA achieves a faster convergence speed and smaller cost than MSFOA in the early stages. However, in the later iterations when most algorithms come to stagnation, MSFOA still shows the ability to search for better solutions. The searching range decreases as the cost value decreases below the threshold, which can improve the local searching ability near the optimal solution, and thus leads to the best global convergence of the algorithms.
In Table 3, the best, median, and average of the cost values of the sum for three UAVs are recorded. The best values are highlighted using boldface. From this table, it can be seen that MSFOA achieves the smallest cost value in the first and third scenario and the second smallest in the second scenario. MFOA obtains a smaller average and median in the second scenario, but the distributed interval of solutions obtained by MFOA in Figure 3 is evidently worse than that obtained by MSFOA. Comprehensively comparing the statistical data of all algorithms in the three scenarios, MSFOA still shows its superiority to other algorithms in terms of searching ability and stability.

5. Conclusions

This paper proposed an MSFOA for cooperative path planning of multi-UAVs over three-dimensional rugged terrain. In order to ensure the convergence speed and avoid local optimization, we have improved this in many ways. The multi-swarm strategy is used to increase the searching ability of the algorithm. In order to make use of any searching information effectively, we proposed the competition strategy of offspring, which ensures the efficient use of searching information and avoids falling into local optimum. In order to plan the flight path for multi-UAVs and avoid the collision between UAVs, we proposed a method to detect the collision between UAVs. Several simulations have shown the effective performance of the proposed approach. This paper proposed a method which can be used for multi-UAV path planning and can solve the high-dimensional function optimization problem. It can be widely used in the field of robotics. In addition, the parameters and sub-swarm amount usually affect the searching performance, and this may be improved in further work.

Author Contributions

K.S. and X.Z. proposed the algorithm and wrote the paper, as well as analyzed the data; K.S. and S.X. conceived and performed the experiments. All authors have read and agreed to the published version of the manuscript.

Funding

This work is supported by the Beijing Municipal Education Commission, the National Natural Science Foundation of China (No. 61703012), and the Beijing Natural Science Foundation (No. 4182010).

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

x best ( g ) The x coordinate of the location of the g-th old swarm.
y best ( g ) The y coordinate of the location of the g-th old swarm.
X i ( g ) The x coordinate of the i-th fruit fly in the g-th old swarm.
Y i ( g ) The y coordinate of the i-th fruit fly in the g-th old swarm.
S old ,   i ( g ) The smell concentration judgement of the i-th fruit fly in the g-th old swarm.
s m e l l old ,   i ( g ) The smell concentration of the i-th fruit fly in the g-th old swarm.
I n d e x old ( g ) The index of the fly with the best smell concentration in the g-th old swarm.
x oldbest ( g ) The x coordinate of the fly with the best smell concentration in the g-th old swarm.
y oldbest ( g ) The y coordinate of the fly with the best smell concentration in the g-th old swarm.
X new ,   i ( g ) The x coordinate of the i-th fruit fly in the g-th new swarm.
Y new ,   i ( g ) The y coordinate of the i-th fruit fly in the g-th new swarm.
S new ,   i ( g ) The smell concentration judgement of the i-th fruit fly in the g-th new swarm.
s m e l l new ,   i ( g ) The smell concentration of the i-th fruit fly in the g-th new swarm.
I n d e x new ( g ) The index of the fly with the best smell concentration in the g-th new swarm.
GThe number of swarms.

References

  1. Zhang, X.Y.; Lu, X.Y.; Jia, S.; Li, X.Z. A novel phase angle-encoded fruit fly optimization algorithm with mutation adaptation mechanism applied to UAV path planning. Appl. Soft Comput. 2018, 70, 371–388. [Google Scholar] [CrossRef]
  2. Zheng, C.W.; Li, L.; Xu, F.J.; Sun, F.C.; Ding, M.Y. Evolutionary route planner for unmanned air vehicles. IEEE Trans. Robot. 2005, 21, 609–620. [Google Scholar] [CrossRef]
  3. Zhu, M.N.; Zhang, X.H.; Luo, H.; Wang, G.Q.; Zhang, B.B. Optimization dubins path of multiple UAVs for post-earthquake rapid-assessment. Appl. Sci. 2020, 10, 1388. [Google Scholar] [CrossRef] [Green Version]
  4. Wang, X.D.; Luo, X.; Han, B.L.; Chen, Y.H.; Liang, G.H.; Zheng, K.L. Collision-free path planning method for robots based on an improved rapidly-exploring random tree algorithm. Appl. Sci. 2020, 10, 1381. [Google Scholar] [CrossRef] [Green Version]
  5. Roberge, V.; Tarbouchi, M.; Labonte, G. Comparison of parallel genetic algorithm and particle swarm optimization for real-time UAV path planning. IEEE Trans. Ind. Inform. 2013, 9, 132–141. [Google Scholar] [CrossRef]
  6. Sababha, M.; Zohdy, M.; Kafafy, M. The Eehanced firefly algorithm based on modified exploitation and exploration mechanism. Electronics 2018, 7, 132. [Google Scholar] [CrossRef] [Green Version]
  7. Richter, C.; Bry, A.; Roy, N. Polynomial trajectory planning for aggressive quadrotor flight in dense indoor environments. Springer Tracts Adv. Robot. 2016, 114, 649–666. [Google Scholar]
  8. Li, Z.H.; Yang, X.J.; Sun, X.D.; Liu, G.; Hu, C. Improved artificial potential field based lateral entry guidance for waypoints passage and no-fly zones avoidance. Aerosp. Sci. Technol. 2019, 86, 119–131. [Google Scholar] [CrossRef]
  9. Xue, Y.; Sun, J.Q. Solving the path planning problem in mobile robotics with the multi-objective evolutionary algorithm. Appl. Sci. 2018, 8, 1425. [Google Scholar] [CrossRef] [Green Version]
  10. Zhang, X.Y.; Duan, H.B. An improved constrained differential evolution algorithm for unmanned aerial vehicle global route planning. Appl. Soft Comput. 2015, 26, 270–284. [Google Scholar] [CrossRef]
  11. Xu, C.F.; Duan, H.B.; Liu, F. Chaotic artificial bee colony approach to uninhabited combat air vehicle (UCAV) path planning. Aerosp. Sci. Technol. 2010, 14, 535–541. [Google Scholar] [CrossRef]
  12. Zhang, X.Y.; Jia, S.M.; Li, X.Z.; Jian, M. Design of the fruit fly optimization algorithm based path planner for UAV in 3D environments. In Proceedings of the 2017 IEEE International Conference on Mechatronics and Automation, Takamatsu, Japan, 6–9 August 2017; pp. 381–386. [Google Scholar]
  13. Das, P.K.; Behera, H.S.; Das, S.; Tripathy, H.K.; Panigrahi, B.K.; Pradhan, S.K. A hybrid improved PSO-DV algorithm for multi-robot path planning in a clutter environment. Neurocomputing 2016, 207, 735–753. [Google Scholar] [CrossRef]
  14. Dorigo, M.; Maniezzo, V.; Colorni, A. Ant System: Optimization by a Colony of Cooperating Agents. IEEE Trans. Syst. 1996, 26, 29–41. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  15. Duan, H.B.; Zhang, X.Y.; Wu, J.; Ma, G.J. Max-min adaptive ant colony optimization approach to multi-UAVs coordinated trajectory replanning in dynamic and uncertain environments. J. Bionic Eng. 2009, 6, 161–173. [Google Scholar] [CrossRef]
  16. Masdari, M.; Salehi, F.; Jalali, M.; Bidaki, M. A survey of PSO-based scheduling algorithms in cloud computing. J. Netw. Syst. Manag. 2017, 25, 122–158. [Google Scholar] [CrossRef]
  17. Das, P.K.; Behera, H.S.; Panigrahi, B.K. A hybridization of an improved particle swarm optimization and gravitational search algorithm for multi-robot path planning. Swarm Evol. Comput. 2016, 28, 14–28. [Google Scholar] [CrossRef]
  18. Pan, W.T. A new fruit fly optimization algorithm: Taking the financial distress model as an example. Knowl. Based Syst. 2012, 26, 69–74. [Google Scholar] [CrossRef]
  19. Li, W.T.; Zhang, Y.D.; Shi, X.W. Advanced fruit fly optimization algorithm and its application to irregular subarray phased array antenna synthesis. IEEE Access 2019, 7, 165583–165596. [Google Scholar] [CrossRef]
  20. Li, H.Z.; Guo, S.; Li, C.J.; Sun, J.Q. A hybrid annual power load forecasting model based on generalized regression neural network with fruit fly optimization algorithm. Knowl. Based Syst. 2013, 37, 378–387. [Google Scholar] [CrossRef]
  21. Lin, S.M. Analysis of service satisfaction in web auction logistics service using a combination of fruit fly optimization algorithm and general regression neural network. Neural Comput. Appl. 2013, 22, 783–791. [Google Scholar] [CrossRef]
  22. Xing, Y.F. Design and optimization of key control characteristics based on improved fruit fly optimization algorithm. Kybernetes 2013, 42, 466–481. [Google Scholar] [CrossRef]
  23. Yuan, X.F.; Dai, X.S.; Zhao, J.Y.; He, Q. On a novel multi-swarm fruit fly optimization algorithm and its application. Appl. Math. Comput. 2014, 233, 260–271. [Google Scholar] [CrossRef]
  24. Pan, Q.K.; Sang, H.Y.; Duan, J.H.; Gao, L. An improved fruit fly optimization algorithm for continuous function optimization problem. Knowl. Based Syst. 2014, 62, 69–83. [Google Scholar] [CrossRef]
Figure 1. (a,c,e) are the three-dimensional (3D) displays of the three simulation scenarios, which show the terrain and threat sources in the mission map; (b,d,f) are the corresponding 2D views of the simulation scenarios.
Figure 1. (a,c,e) are the three-dimensional (3D) displays of the three simulation scenarios, which show the terrain and threat sources in the mission map; (b,d,f) are the corresponding 2D views of the simulation scenarios.
Applsci 10 02822 g001
Figure 2. Two-dimensional displays of the best unmanned aerial vehicle (UAV) paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the first scenario.
Figure 2. Two-dimensional displays of the best unmanned aerial vehicle (UAV) paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the first scenario.
Applsci 10 02822 g002aApplsci 10 02822 g002b
Figure 3. Two-dimensional displays of the best UAV paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the second scenario.
Figure 3. Two-dimensional displays of the best UAV paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the second scenario.
Applsci 10 02822 g003aApplsci 10 02822 g003b
Figure 4. Two-dimensional displays of the best UAV paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the third scenario.
Figure 4. Two-dimensional displays of the best UAV paths obtained by (a) MSFOA, (b) FOA, (c) PSO, (d) DE, (e) ABC, (f) IFFO, and (g) MFOA in the third scenario.
Applsci 10 02822 g004aApplsci 10 02822 g004b
Figure 5. Convergence curves of the average best values for the first scenario.
Figure 5. Convergence curves of the average best values for the first scenario.
Applsci 10 02822 g005
Figure 6. Convergence curves of the average best values for the second scenario.
Figure 6. Convergence curves of the average best values for the second scenario.
Applsci 10 02822 g006
Figure 7. Convergence curves of the average best values for the third scenario.
Figure 7. Convergence curves of the average best values for the third scenario.
Applsci 10 02822 g007
Table 1. The parameters used in experiments of different algorithms.
Table 1. The parameters used in experiments of different algorithms.
AlgorithmsPopulation SizeControl Parameters
MSFOAMpop = 100The swarm amount G = 5, the mutation parameters coe1 = 0.8, coe2 = 0.2.
FOA [18]Mpop = 100No more parameters.
PSO [13]Mpar = 100The inertial weight coefficient w varies from 0.9 to 0.4, the acceleration coefficients c1 = c2 = 2.
DE [10]Msol = 100The scaling factor F is set as a random value in [0.2, 0.9], the crossover factor cr = 0.9.
ABC [11]Ne = 50, Nu = 50The largest local searching times Limit = 20.
IFFO [24]Mpop = 100The maximum radius λ m a x = 0.5, the minimum radius λ min = 0.01.
MFOA [23]Mpop = 100The multi-swarm amount M = 5.
Abbreviations: MSFOA, multiple swarm fruit fly optimization algorithm; FOA, fruit fly optimization algorithm; PSO, particle swarm optimization; DE, differential evolution; ABC, artificial bee colony; IFFO, improved fruit fly optimization; MFOA, multi-swarm fruit fly optimization algorithm.
Table 2. The objective function of each UAV obtained by various algorithms in the three scenarios.
Table 2. The objective function of each UAV obtained by various algorithms in the three scenarios.
AlgorithmFirst Scenario Second Scenario Third Scenario
JUAV_1JUAV_2JUAV_3 n = 1 3 J UAV _ n   JUAV_1JUAV_2JUAV_3 n = 1 3 J UAV _ n   JUAV_1JUAV_2JUAV_3 n = 1 3 J UAV _ n  
MSFOA133.21 138.09 145.66 404.37128.79 125.52 149.90 382.95152.48 145.19 156.85 440.71
FOA165.22 168.24 173.69 507.15155.16 293.51 661.07 520.27307.26 244.29 178.91 730.46
PSO146.27 137.72 201.16 485.14123.72 112.26 171.77 520.27228.07 238.56 162.09 628.71
DE158.20 184.94 218.39 561.53232.28 235.97 187.56 655.81207.78 244.22 212.59 664.59
ABC113.07 142.89 155.21 411.16139.17 112.85 148.99 401.02165.08 125.62 166.76 457.45
IFFO181.34 146.80 169.14 497.29134.56 154.59 258.29 547.44229.20 165.71 194.94 589.85
MFOA116.54 155.41 145.11 417.07126.34 109.93 152.06 388.33167.12 146.68 152.06 465.87
Table 3. The statistical results of cost of the path in different scenarios.
Table 3. The statistical results of cost of the path in different scenarios.
AlgorithmFirst ScenarioSecond ScenarioThird Scenario
BestAverageMedianBestAverageMedianBestAverageMedian
MSFOA404.37490.23466.56382.95485.46505.18440.71504.20492.95
FOA507.15708.73698.53520.27755.35693.81730.461001.69993.81
PSO485.14797.76754.04520.27755.35693.81628.71953.93954.92
DE561.53674.52665.62655.81761.37768.37664.59809.74815.48
ABC411.16503.64497.22401.02516.94520.93457.45589.69591.39
IFFO497.29859.11860.97547.44928.37908.26589.85953.56934.38
MFOA417.07495.04493.33388.33482.81475.26465.87566.83564.83

Share and Cite

MDPI and ACS Style

Shi, K.; Zhang, X.; Xia, S. Multiple Swarm Fruit Fly Optimization Algorithm Based Path Planning Method for Multi-UAVs. Appl. Sci. 2020, 10, 2822. https://doi.org/10.3390/app10082822

AMA Style

Shi K, Zhang X, Xia S. Multiple Swarm Fruit Fly Optimization Algorithm Based Path Planning Method for Multi-UAVs. Applied Sciences. 2020; 10(8):2822. https://doi.org/10.3390/app10082822

Chicago/Turabian Style

Shi, Kunming, Xiangyin Zhang, and Shuang Xia. 2020. "Multiple Swarm Fruit Fly Optimization Algorithm Based Path Planning Method for Multi-UAVs" Applied Sciences 10, no. 8: 2822. https://doi.org/10.3390/app10082822

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