Next Article in Journal
Joint Beamforming and Trajectory Design for Aerial Intelligent Reflecting Surface-Aided Secure Transmission
Next Article in Special Issue
A Novel Deep Learning Technique for Detecting Emotional Impact in Online Education
Previous Article in Journal
Operator-Based Fractional-Order Nonlinear Robust Control for the Spiral Heat Exchanger Identified by Particle Swarm Optimization
Previous Article in Special Issue
Evolution of Machine Learning in Tuberculosis Diagnosis: A Review of Deep Learning-Based Medical Applications
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Survey of Trajectory Planning Techniques for Autonomous Systems

1
School of Avionics & Electrical Engineering, College of Aeronautical Engineering, National University of Sciences and Technology (NUST), Islamabad 44000, Pakistan
2
Department of Avionics Engineering, Air University, Aerospace & Aviation Campus Kamra, Islamabad 43570, Pakistan
3
Department of Electrical Engineering, Air University, Aerospace & Aviation Campus Kamra, Islamabad 43600, Pakistan
4
Electrical Department, Fast-National University of Computer & Emerging Sciences, Peshawar 25124, Pakistan
5
Department of Electrical and Communication Engineering, United Arab Emirates University (UAEU), Al Ain 15551, United Arab Emirates
6
Hourani Center for Applied Scientific Research, Al-Ahliyya Amman University, Amman 11831, Jordan
7
Faculty of Information Technology, Middle East University, Amman 11831, Jordan
8
Department of Computer Science, Wenzhou-Kean University, Wenzhou 325015, China
9
Faculty of Engineering and Information Technology, University of Technology Sydney, Ultimo, NSW 2007, Australia
*
Authors to whom correspondence should be addressed.
Electronics 2022, 11(18), 2801; https://doi.org/10.3390/electronics11182801
Submission received: 28 June 2022 / Revised: 19 August 2022 / Accepted: 29 August 2022 / Published: 6 September 2022
(This article belongs to the Special Issue Big Data Analytics Using Artificial Intelligence)

Abstract

:
This work offers an overview of the effective communication techniques for space exploration of ground, aerial, and underwater vehicles. We not only comprehensively summarize the trajectory planning, space exploration, optimization, and other challenges encountered but also present the possible directions for future work. Because a detailed study like this is uncommon in the literature, an attempt has been made to fill the gap for readers interested in path planning. This paper also includes optimization strategies that can be used to implement terrestrial, underwater, and airborne applications. This study addresses numerical, bio-inspired, and hybrid methodologies for each dimension described. Throughout this study, we endeavored to establish a centralized platform in which a wealth of research on autonomous vehicles (on the land and their trajectory optimizations), airborne vehicles, and underwater vehicles, is published.

1. Introduction

The significance of ground autonomous vehicles began with the DARPA (Defense Advanced Research Projects Agency) urban challenge in 2007 [1,2]; this concept later extended to the development of aerial vehicles. Different concepts were also applied to flight dynamics techniques to improve flight stability. Optimization algorithms for the path findings of ground robotics [3,4,5,6,7] and aerial vehicles [8,9,10,11,12] include numerous applications. Since the 1970s, path planning has received a lot of attention, and it has been used to address issues in a variety of sectors, from simple geographical route planning to selecting an acceptable action sequence to achieve a certain objective. Path planning can be employed in fully-known or partially-known surroundings, as well as in completely new situations, where data from system-mounted sensors are used to update environmental maps and instruct the robot/planned AV’s movements.
To keep the robot moving from the start state to the goal location through various intermediate stages, a proper trajectory is constructed as a series of actions. Every choice made by path planning algorithms is determined by the information that is currently accessible, as well as by other factors, such as the Euclidean distance computation’s calculation of the shortest distance to the target point (i.e., certain objectives are required to be fulfilled). In terms of optimization, the best path must travel the fewest distances, be free of obstacles and collisions, and take the least amount of time to arrive at the desired state.
In the last decade, multiple path planning methods have been formulated for land and aerial vehicles using the trajectory optimization problem. These trajectory optimization problems are distinguished into two groups: (i) heuristics and, (ii) non-heuristic methods. The former uses the trade-off in producing optimal solutions but gives computationally effective results and the latter uses mathematical derivations, which are computationally expensive [13].
For mobile robots or aerial vehicles, autonomous navigation is a crucial tool. It aids in reducing their reliance on human assistance. However, it does involve several jobs or difficulties to accomplish, such as path planning. This assignment entails determining the optimal course of action for obtaining a robot from its current condition to the target state. Both states may, for example, represent the objective and the starting positions, respectively. This plan of action takes the shape of a path, which is also known as a route in other works. In general, path planning algorithms aim to find the optimal path or at least a close approximation to it. The optimal route refers to the best path, in the sense that it is the outcome of minimizing one or more objective optimization functions. This path, for example, may be the one that takes the least amount of time. This is crucial in operations such as search-and-rescue [14], for example, catastrophe victims may request assistance in life-or-death circumstances. Another optimization function to consider could be the energy of the robot. In the case of planetary exploration, this is critical since rovers have limited energy resources available.
For collision avoidance of a mobile robot in a dynamic scenario, Rath et al. [15] considered a virtual disc in front of the mobile robot that was centered at the mobile robot’s heading angle. According to some specified regulations, the crossing angle between the disc and the obstacles was computed and continually modified in the direction of the mobile robot. To tackle the motion-planning problem, ANNs and radial basis neural networks are utilized to forecast the movements of dynamic barriers.
An efficient path planning algorithm must meet four requirements. First, in actual static situations, the motion planning approach must always be capable of identifying the best path. Second, it must be adaptable to changing conditions. Third, it must be consistent with and strengthen the self-referencing strategy selected. Fourth, it must keep the complexity, data storage, and computing time to a minimum. A survey article on land/aerial and underwater has been given by a number of scholars. However, these surveys are insufficient to offer information on their navigation [16]. A detailed examination of individual navigational strategies has been presented in this research. The purpose of the suggested survey articles on vehicle navigation is to discover the research gaps and potential for innovation in a certain field.
The route generation and optimization problem can be tackled using deterministic (numerical) approaches, nature-inspired algorithms, or a combination of these techniques. To calculate the precise solution, there are several numerical techniques available, including the iterative method [17], Runge Kutta [18], Newton–Raphson method [19], and  the bisection method [20]. These techniques can be utilized to locate any type of answer. These algorithms are used to tackle path planning, trajectory optimization, and a variety of other vehicle versions for autonomous vehicles. Nature-inspired approaches are based on the social hierarchy of animals and birds such as ants, bees, and flies [21,22,23,24]. There are a great number of different algorithms, which are inspired by the Grey Wolf Optimizer, Whale Optimization, the Deer Hunting Algorithm, the Slap Swarm Algorithm, the Grasshopper Algorithm, the Ant Lion Optimizer, the Moth Flame Optimizer, simulated annealing, the Arithmetic Algorithm, the Harmony Search Algorithm, the Aquila Optimizer, and the Owl Search Algorithm [25,26,27,28,29,30,31,32,33].
Path planning for autonomous vehicles is also known as a multi-objective optimization since it involves achieving many goals, such as generating optimal routes while avoiding obstacles that evade the capability [34]. Route planning for agents can be divided into different categories based on how they complete a task in a given environment, namely: (i) reactive computing, (ii) soft computing, (iii) optimal control, and (iv) C-space search, refer to Figure 1.
The first idea is defined as: if the vehicle has access to or knowledge of the surrounding region prior to the start of its voyage, it is inferred as a priori information. The latter, on the other hand, involves the vehicle lacking information about the surrounding region [35,36,37]. The surrounding space can also be divided as dynamic or static; when the obstacles are in motion, it is called dynamic motion and when the objects are not in motion, it is known as a static motion [35,38,39,40,41]. Therefore, it is evident the optimization of path planning and space exploration techniques have gained significant importance in the research community (due to their vast applicability and diversity). Several authors have used different industrial robots to implement the algorithms and validate their effectiveness and robustness. Table 1 depicts such few robotic parameters mentioned in the different studies.

1.1. Objective and Contents

This research examines numerical approaches along with nature-inspired techniques, and their integration with each other (or individually), for navigation and obstacle avoidance utilized for land, aerial, and underwater vehicles. This research is aimed at providing academics with the most up-to-date knowledge for path optimization and environment modeling. This paper compares several algorithms and shows how they can be implemented in various contexts. The following is a list of this review’s contributions:
  • Consolidation of relevant work: Human drivers have an amazing ability to simultaneously perceive a vehicle’s environment while steadily performing the essential motion movements. Globally, researchers are working on replicating the maneuverable capabilities of human drivers in designing autonomous guided vehicles that are simple in design, provide safety, and are efficient) [47,48,49,50,51]. Therefore, this study strives to provide valuable insight into the land, aerial, and underwater vehicles for readers in-order to understand their utilities in the industry and research.
  • Limitations and the way forward: Another major contribution of this research involved identifying the impediments associated with path optimization and obstacle avoidance using numerical and nature-inspired methods. Characteristics that do not contribute toward finding the optimal trajectory optimization for ground and aerial vehicles are identified and categorized into two categories: (i) numerical methods and nature-inspired techniques: limitations; (ii) numerical methods and nature-inspired techniques: restrictions. A complete way forward is also suggested.

1.2. Paper Organization

The paper is organized in the following manner. Section 2 elaborates on the fundamentals regarding the trajectory planning. Section 3 presents detailed information regarding the numerical methods, bio-inspired algorithms, and hybrid algorithms involved in land, aerial, and underwater vehicles. Section 4 contains an elaborated description of the challenges involved in land, aerial, and underwater vehicles. The paper ends with our conclusion in Section 5.

2. Trajectory Planning Fundamentals

To formulate the desired trajectories, the trajectory planning problem is treated as an optimization problem. With the exception of simple problems (such as the infinite horizon linear quadratic problem [52]), these optimization problems must be solved numerically. Such techniques can be divided into three major methods—dynamic programming, direct methods, and indirect methods [53].
In the 1970s, there was interest in path planning [54]; in the following years, it has been used to solve problems in a variety of sectors, from straightforward geographical route planning to the choice of an appropriate action sequence that is necessary to achieve a specific goal. When information is obtained from system-mounted sensors and updated environmental maps, path planning can be employed in fully or partially known surroundings as well as in completely new environments to guide the desired motion of the robot [46,55]. Finding a single solution to this NP-hard problem is not the goal; rather, it is to find the best possible answer, one that travels the shortest distance, makes the fewest maneuvers, and avoids all known obstacles. The global planner often divides this module into two parts: the local planner, which recalculates the initial plan to account for potential dynamic impediments, and the global planner, which employs a priori knowledge of the environment to produce the best path, if any.
The created plan consists of a set of waypoints for both the global P i = ( x i , y i ) T and the local P i = ( x i , y i , θ i ) T , ϵ R 2 × S 1 , where S is the navigation plane on which the vehicle can drive. Learning-based approaches have begun to demonstrate their effectiveness in resolving motion planning issues. They either use human-designed incentive functions or learn workable solutions from previous successful planning experiences to direct the robot’s movement. In general, supervised/unsupervised learning and reinforcement learning can be used to categorize learning-based approaches to robot motion planning. Four requirements are critical for effective path planning; Algorithm 1. First, in realistic static situations, the motion planning technique must always be able to identify the best path. Second, it needs to be scalable to dynamic contexts. Third, it must continue to be beneficial to (and compatible with) the selected self-referencing strategy. The complexity, data storage, and computing time must all be kept to a minimum [56]. Realizing the importance of path planning, this research introduces a wide range of path planning algorithms for all three domains of ground, aerial, and underwater applications.
Algorithm 1 Integrated CME-Adaptive Aquila Optimizer.
1:
Set nRbt, iteration, agent start position
2:
Define utility of unknown space = 1
3:
while iter = iter + 1 do
4:
    for all nRbt do
5:
        Initialize coordinates of V c
6:
        Determine the cost of V c
7:
        Subtract R U c i & V c
8:
        Utilize X1, X2, X3, and X4
9:
        Update the X(iter + 1) position
10:
      Re-select the agent position
11:
      Reduce R U j g c on X(t + 1)
12:
    end for
13:
    Determine G1, G2 & QF
14:
end while
15:
return the solution

Trajectory Planning: Mathematical Framework

Essentially, all numerical methods for solving the trajectory planning problem involve iterative mechanisms with a finite number of unknowns and known variables, subject to static, dynamic, and linkage constraints. This functionality is demonstrated through Figure 2. The flow chart elaborates the fundamental steps adopted in the trajectory planning algorithm beginning with user-defined input data for the stated problem to the computation of the final trajectory.
Conventionally the problem is configured as a multiple-domain optimal control problem [57]. In this, v [ 1 , . . . , V ] is the phase number, V is the total number of phases, M y is the output dimension, M u is the input dimension, M q is the integral dimension, and M s is the dimension of the static parameters. The optimal control problem then tries to determine the state, z ( v ) ( t ) R M y ( v ) , control, u ( v ) ( t ) R M u ( v ) , integrals q ( v ) R M q ( v ) , start time, t 0 ( p ) R , phase terminal time, t f ( p ) R , in all phases p [ 1 , . . . , P ] , along with the static parameters s R M s , which minimize the objective function in Equation (1)
T = v = 1 v [ Φ ( v p ) ( x ( v ) ( t o ) , t o ( v ) , x ( v ) ( t f ) , t f ( v ) , q ( v ) ) + t o ( v ) t f ( v ) L ( v ) ( x ( v ) ( t ) , u ( v ) ( t ) , q ( v ) d t ) ]
subject to constraints in Equation (2), inequality path constraints in Estimates (3), boundary constraints in Estimates (4), and linkage constraints in Estimates (5).
z ˙ ( v ) = f ( v ) ( z ( v ) u ( z ) t ; a ( v ) ) , v = 1 , . . . . V
C m i n ( v ) C ( v ) ( z ( v ) , u ( v ) , t ; q ( v ) ) C m a x ) , v = 1 , . . . . V
ϕ m i n ( v ) ϕ ( v ) ( x ( V ) ( t 0 ) , t 0 o , z ( v ) ( t f ) , t f , ; q ( v ) ) ϕ m a x ) , v = 1 , . . . . V
K m i n ( r ) K ( r ) ( z ( v 1 r ) ( t f ) , t f ( v 1 r ) ; q ( v 1 r ) , x ( v r r ) ( t 0 ) , t 0 ( v r r ) ; q ( v r r ) L m a x ( r ) ) w h e r e [ v 1 , v r [ v = 1 , . . . V ] ] , r = [ 1 , . . . K ]
The required state and control variables are then calculated using polynomial interpolation as elaborated in Equation (6)
z ( τ ) Z ( τ ) = i = 1 N Z i · K i ( τ ) , τ [ 1 , 1 ]
where L i ( τ ) = j = 0 , j i N τ τ j τ i τ j , i = 0 , 1 . . . . N .
The control is then determined using Equation (7)
u ( τ ) U ( τ ) = i = 1 N Z i · K i * ( τ ) , τ [ 1 , 1 ]
where L i * ( τ ) = j = 1 , j i N τ τ j τ i τ j , i = 1 . . . . N . From Equation (6), x ˙ ( τ ) is approximated by X ˙ ( τ ) (see Equation (8))
z ˙ ( τ ) Z ˙ ( τ )
The continuous cost function of Equation (1) is approximated using a quadrature given by Equation (9)
J = Φ ( Z 0 , t 0 , Z f , t f ) + t f t o 2 b = 1 N w k · g ( X b , U b , τ b ; t 0 , t f )
where w b are the weights. The boundary constraint of Estimates. (4) is expressed as in Equation (10)
ϕ ( X 0 , t 0 , X f , t f ) = 0
The cost function and algebraic constraints in Equation (9) define the transformed problem, whose solution is an approximate solution to the original trajectory planning problem from the time t 0 to t f .
This fundamental framework has been utilized by various research studies for numerous applications and is now considered a pretty robust and widely acceptable technique for ground, aerial, space, and underwater trajectory optimization problems [58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75].

3. Relevant Studies

In this section, we will present an in-depth analysis and review of major studies performed for space exploration for autonomous systems. As elaborated earlier, path planning, space exploration, and trajectory optimization problems can be solved utilizing numerical techniques, bio-inspired algorithms, and the hybridization of these techniques with each other. In the beginning, deterministic methods or numerical methods were employed for path planning and other jobs. However, due to their inability to generate random solutions and computationally expensive nature, they were replaced by other algorithms. With growing interest, research areas have expanded and introduced bio-inspired techniques based on swarm, ant, reptile, etc., to solve trajectory planning, obstacle avoidance, and trajectory optimization. It is often seen that no single algorithm or technique can guarantee the desired results; therefore, it is common practice to integrate techniques to achieve higher accuracy and design a system more efficiently. This whole process is called the hybridization of algorithms/techniques [76].
The analysis will comprehensively cover the numerical, bio-inspired, and hybrid optimization techniques utilized for aerial, surface, and subsurface purposes.

3.1. Numerical Techniques

The implementation of algorithms for obtaining numerical solutions is a part of numerical analysis. It entails mathematical analysis on a theoretical level. The numerical methodologies, and their utilities found in land, aerial, and undersea vehicles, are presented in this section.

3.1.1. Applications to Aerial Vehicles

The most predominant feature involved in any aerial vehicle system is the sensor performance. Numerous sensors, such as radar, LiDAR, and sonar, are linked with the efficiency of aerial vehicles and their dynamics. In [77,78,79], the authors efficiently utilized radar to detect fast-moving targets, whereas the authors of [80,81] employed LiDAR for airborne purpose. Moreover, the authors of [82] utilized sonar for similar purposes. Important scholarly contributions in this aspect are summarized in Table 2. Various algorithms [83,84,85] have been developed to control the flight mechanics of UAVs. Few have presented and implemented the leader–follower strategy for accurate outcomes. The following is a list of works that are related to this one: Hasircioglu et al. [86] implemented the GA algorithm for 3D UAV flights for multiple missions. Nikolos et al. [87] used the evolutionary algorithm to increase the robustness and efficiency. Similarly, many researchers have worked on the obstacle avoidance of UAVs. One way is to add a penalty function in the objective function to catch the error [88]. Mansury et al. [89] came up with the penalty function in a planned path when a collision occurred.
One method added a penalty to its objective function as the planned path neared an obstacle, while another approach imposed a penalty only when the planned path resulted in a collision. Obstacles can also be treated as flight-restricted areas in lieu of a single point. Zhao et al. [90,91] converted an optimal control problem into parameter optimization via a collocation approach (numerically-solved with the software, Nonlinear Programming Solver (NPSOL)) [92]. NPSOL is a suite of Fortran 77 subroutines designed to solve a non-linear programming problem. NPSOL uses sequential quadratic programming (SQP) algorithm, in which the search direction is the solution of a quadratic programming sub-problem. The step size at each iteration is iteratively selected to produce a sufficient decrease in an augmented Lagrangian merit function. After successful convergence, solutions of the NPSOL program represent a locally optimal solution to the non-linear programming problem. Zhang et al. [93] followed the nature-inspired technique that birds follow and developed an algorithm for a target using the Tau theory.

3.1.2. Applications to Ground Vehicles

Curve interpolation planners, such as clothoid, polynomial, spline, and Bézier curves, are common in online route planning. Because the behavior of the curve is specified by a few control points or parameters, these planners are comparable to graph search techniques and have minimal computing costs. However, the resultant path’s optimality cannot be guaranteed, and the dynamic restrictions of a robot are not taken into account during the planning phase (because the sizes of the curves in obstacles vary), necessitating a smoothing step. The clothoid curve introduces a novel way to reduce the route length and curvature change [98]. The suggested technique produces a closed-form solution to link two clothoid sets for the position of a waypoint in this approach, which considers two points on the plane. This method lowers the robot’s rapid changes in curvature and sideslip and improves movement performance. Zhang et al. [99] measured unmanageable divergence. This statistic was used to build a system to transition between numerous predictive controllers, reducing the controller’s return time while maintaining predictive accuracy. The authors of [100] created a smooth route by combining RRT* (rapidly-exploring random trees) and spline approaches. The suggested bidirectional Spline-RRT* method is based on the cubic curve and meets both start and target position direction restrictions. This approach is unlike any previous route planning algorithm, and the robot’s solution is sub-optimal yet workable.

3.1.3. Application to Underwater Vehicle (AUV)

The navigation and controls of autonomous underwater vehicle systems have reached the same level of importance as ground and aerial vehicles. Ocean vehicle navigation is another name for them. It is also crucial to discuss the AUV system’s connected literature. Autonomous underwater vehicles, such as ground and aerial vehicles, require path planning to navigate in the best possible way. However, in comparison to ground and airborne vehicles, the water environment has several problems because of data transmission, sensing range, and power limits.
Because of the constantly shifting bandwidth channel, communicating successfully underwater is difficult. As a result, deciding which path to follow for autonomous underwater vehicles is a difficult task. Path planning and trajectory planning are two types of motion planning. The first one is described as the numerous waypoints in which a vehicle must travel to reach the destination point, while the latter is defined as the time required to complete the journey. Underwater, the GPS system is not available and with weak communication power, it is extremely hard to set the routes for AUVs. Soylu et al. [101] presented an algorithm with an adaptive term; it works on the concept of control, although it is only concerned with maritime vehicles. An underwater vehicle uncertainty estimator (limited to 4 DOF systems defined by a diagonal inertia matrix) is proposed. The authors of [102] suggested a unique technique that consisted of two steps: (i) the creation of a velocity control algorithm in terms of the normalized generalized velocity components (NGVC) as a tool for analysis, and, (ii) its application to the vehicle dynamics inquiry. The algorithm is defined in terms of the altered equations of motion resulting from the decomposition of the inertia matrix. The author proposed approach is appropriate for fully-operated underwater vehicles and may be used to conduct numerical testing of the assumed model before conducting an actual experiment. The simulation on a 6 DOF underwater vehicle demonstrates the usefulness of the suggested technique.
A nonlinear MPC (model predictive control) is proposed in [103] for an autonomous underwater vehicle. A receding horizon optimization framework with a spline template was used to address the path planning issue. Once the current local optimal path is created, it is used as the vehicle’s reference trajectory. A nonlinear model predictive control (MPC) system is used to simultaneously manage the depth of the AUV and to interact amicably with the dynamic route planning method. For tracking control, a combination of the path planning result and MPC is employed. A path planning approach using MPC is suggested to select the maneuvers mode for autonomous cars in dynamic conditions [104].

3.2. Bio-Inspired Techniques

This section provides information about trajectory planning for land, airborne, and undersea vehicles, as well as different nature-inspired techniques. The primary idea behind path optimization approaches is to define route planning as an optimization problem that takes into account the robot’s intended performance and restrictions. This method can determine the best path between the start and target points.
Siddique et al. [105] investigated meta-heuristic and nature-inspired algorithms that mimic natural events in natural sciences. Many academics have tackled the challenge of ground and aerial vehicle trajectory planning and obstacle avoidance using an optimization algorithm that replicates the behavior of live organisms, such as fish, ants, bees, whales, wolves, and bats. [106,107,108,109,110,111] They are referred to as unconventional approaches. These algorithms are known as bio-inspired approaches, and they have been used in engineering to solve challenging mathematical issues [112]. A few bio-inspired algorithms and their summaries are presented in Table 3.

3.2.1. Application to Aerial Vehicles

Zhang et al. [128] focused on obtaining an ideal flying route while avoiding hazards in a battle area. They exhibited Grey Wolf Optimizer (GWO) performance on an unmanned combat aerial vehicle (UCAV; also known as a combat drone, colloquially shortened as drone or battlefield UAV) in a 2D environment. The safest path is determined by connecting nodes while avoiding risks. The simulation results were astounding, demonstrating that an unmanned combat aerial vehicle (UCAV) is more capable than a contemporary algorithm. Similarly, Qu et al. [132] blended the methods to accomplish successful route planning in UAVs. They merged the Grey Wolf Optimizer (GWO) with the Symbiotic Organisms Search (SOS) to present another variant optimizer—the Grey Wolf Optimizer (SGWO) and the Modified Symbiotic Organisms Search (MSOS), called HSGWO-MSOS. The stochastic parameters involved in the algorithm were intelligently adjusted to further enhance the convergence rate. For analysis, a linear difference equation was utilized, and the cubic B-spline curve approach was used to smooth the flight trajectory. The experimental findings show that the proposed algorithm HSGWO-MSOS delivers more viable outputs and is more efficient in conducting the flight trajectory.
Lewis et al. [133] presented a particle swarm optimization path-finding (PSOP) for UAV navigation purposes. The method was employed to control the flock of drones; based on this, a model known as drone flock control (DFC) was constructed. The model is combined with Reynolds flocking and the AI method for obstacle avoidance for UAVs in an unknown space. Majd Saied et al. [134] looked at a variety of unmanned aerial vehicles. The suggested concept uses the Artificial Bee Colony (ABC; inspired by the intelligent foraging behavior of honey bees) method to calculate velocity to avoid obstacles and maintain track of flight data. The simulations were run in MATLAB using various case situations.

3.2.2. Application to Ground Vehicles

In situations with dynamic impediments, Han et al. [126] employed genetic algorithms to identify the shortest pathways. Marco Cruz et al. [39] generated an ideal path by using the ABC method to perform local searches, which progressively created a path without colliding by correlating the mobile robot’s start and end points, and then using evolutionary programming to optimize the practical path. GWO has an atypical condition of local optima avoidance, according to Sen Zhang et al. [128], which increases the likelihood of discovering reasonable approximations of the optimal weighted total cost of this path. Furthermore, due to the strong utilization of the GWO, the accuracy of the generated optimal values for weighted sum cost is quite high. Janglova et al. [135] demonstrated the use of a NN to navigate a wheeled mobile robot in a mostly unknown area. To build a collision-free route, they employed two NN-based techniques. The first neural mechanism used sensory input to discover clear space, while another NN avoided the nearest impediment to find a safe path (to prevent human guidance during the navigation procedure). Gasparri et al. [136] offered real-time navigation in a hallway, lobby, and built floor environments using a single mobile robot system. Abbas et al. [137] developed an upgraded BFO algorithm to improve the path planning performance of a wheeled robot.

3.2.3. Application to Underwater Vehicles

Shen et al. [103] designed a multi-AUV target search with a bio-inspired neural network that could successfully design search trajectories. A fuzzy algorithm was added to the bio-inspired neural network to smooth out the AUV obstacle avoidance trajectory. Unlike existing algorithms that require repeat training to obtain the essential parameters, the suggested technique obtains all of the required parameters without the requirement for learning or training.
Kahlil et al. [138] presented an enhanced cooperative route planning model. This research focused on the search and tracking of an underwater object. To obtain the best results, the mission was separated into search and tracing stages, with the goal of increasing the search space and decreasing the terminal error. The improvement was conducted utilizing the improved whale algorithm. The simulated results show that the suggested technique provides superior outcomes for the search and tracing phase, an improved computing performance, and well-achieved optimization for cooperative path planning of large-scale complicated issues. Daqi Zhu et al. [139] proposed a new rapid marching-based method to extract a continuous route from an environment while taking into consideration the underwater current. Yilmaz et al. [140] proposed the path planning issue as an optimization framework and mixed it with an integer linear programming-based technique. All of the approaches described above were evaluated in two-dimensional (2D) settings, which did not fulfill the actual requirements for AUV route planning. Hu et al. [141], by utilizing a control rule with an attractive force toward a target and a repulsive force against obstacles, produced a vision-based autonomous robotic fish capable of 3D mobility.
An improved self-organizing map and a velocity synthesis approach were presented for multi-AUV route planning in a 3D underwater workspace [142]. Those approaches have their own benefits, but there are certain flaws that need to be investigated further. For example, vision-based approaches perform poorly in an underwater environment; certain evolution-based methods are difficult to compute; and methods based on the premise that underwater habitats are totally known are unsuitable for the real world. Yuan and Qu [143] devised an optimum real-time collision-free AUV route in an unknown 3D underwater environment. The 3D motion planning issue was reduced to a 2D problem in their technique, resulting in a significant reduction in processing costs.

3.3. Hybrid Techniques

After elaborating on numerical and nature-inspired techniques, this section presents detailed information on hybridized algorithms and their related path optimization for land, aerial, and underwater applications.

3.3.1. Application to Aerial Vehicles

Hassan et al. [144] used the traveling salesman method for maximum UAV area coverage. The authors integrated PSO with the GA algorithm to suggest multiple paths for multiple UAVs and to further propose the parallel version of both algorithms. The authors intelligently exploited PSO and GA to avoid local minima and to pick up the quality of the output in a minimum amount of time. Statistical data obtained from the simulated results prove that the proposed method provides promising results. Arantes et al. [145] presented the integration of the genetic algorithm with the visibility graph method to decode the path in an uncertain environment under convex-shaped obstacles. The path was further decoded by linear programming methods to solve each individual path separately. Under the set, 50 different maps that proposed heuristic approaches were tested and the obtained outputs depicted promising results.
Dhargupta et al. [146] presented the integration of RL with the GWO algorithm for a smoother and more efficient flight path for UAVs. Furthermore, the authors in [132] presented a novel algorithm for UAV path planning by combining RL with the GWO optimizer. The algorithm helps in generating a refined clean trajectory for UAVs. The adjustment of stochastic parameters for GWO helps in generating a smoother path. Similarly, a number of authors have also worked on obstacle avoidance. Bouhamed et al. [147] came up with an efficient UAV that glided and, at the same time, avoided static and dynamic objects. The authors utilized the deep deterministic policy gradient (DDPG) learning algorithm, which used a reward function to help detect the target and avoid obstacles. The reward function also helped to diminish the distance between the UAV’s initial step to its final step. A penalty function was added to catch the anomaly in the algorithm. Another method was presented by Challita et al. [148], which depicts numerous sub-challenges for UAVs. The authors discussed the intervention cause during path planning from the ground.

3.3.2. Application to Ground Vehicles

Pengchao Zhang et al. [149] argued that combining classical algorithms with heuristic programming algorithms based on AI yields beneficial outcomes. To modify the functions of path smoothness and path planning, the classic quickly exploring random tree approach was combined with a neural network. The simulations were run in real-time to test the viability of the modified method, which produced better outcomes when dealing with navigation challenges. Faiza et al. [150] presented a novel approach for space surfing by combining the deterministic method with an up-to-date bio-inspired method. The coordinated multi-agent exploration combined with the Arithmetic Algorithm helped to achieve a rate of exploration much higher when compared to contemporary methods. The rates of the failed simulation runs were also lesser than the compared algorithms. Bakdi et al. [151] demonstrated a robot with a camera for trajectory planning. All data obtained from the environment was processed using IM techniques, and GA was utilized to generate the best trajectory to connect the starting point with the destination point. GA was also used with a piecewise cubic Hermite interpolating polynomial to smoothen the route. Finally, an adaptive fuzzy logic controller was used to maintain track of the vehicle’s left and right wheel velocities.

3.3.3. Underwater Vehicles

Wenjie Chen et al. [152] offered a technique to obtain quality photos of underwater localization since previously-reported algorithms, such as simultaneous localization and mapping (SLAM), lacked feature-based extraction qualities, resulting in fuzzy images. To address this issue, a novel technology called visual SLAM employs generative adversarial networks to improve picture quality using assessment criteria. This increases the SLAM efficiency and delivers improved localization and accuracy. The suggested approach was tested on many photos with various amounts of turbidity in the water. For fault resilience challenges in autonomous underwater vehicles, the authors of [153] developed a moth flame optimization algorithm for AUVs. AUVs have a difficult time communicating; hence, a fast network is required to send data packets back to the station. To tackle the failure problem, MFO develops a unique fitness function. The suggested methods for AUVs have been evaluated and were found to be successful.

4. Challenges, Recommendations, and Future Directions

In this section, based on the survey of the literature work, we present a summary of the challenges encountered in the space exploration process. We then propose solutions and future directions.

4.1. Challenges Involved in Path Planning

Below are the challenges involved in path planning for vehicles.

4.1.1. Inaccurate Results

No single method guarantees 100% results, despite the number of research studies conducted on land, aerial, and underwater vehicles. In robotics, the system accuracy depends on whether the robot can reach a known place without becoming stuck to the local/global minima/maxima. If the robot evades without becoming stuck, then the accuracy of that algorithm is higher. However, for space exploration, the areas being explored by the robot(s) are measured in terms of percentages, e.g., 80%, 90%, etc. [154,155]. Further, the intrinsic limitation of nature-inspired algorithms being stuck in local/global maxima/minima is the main drawback of all bio-inspired algorithms. Aspects such as oscillations, sensor, and measurement noises, and overshooting/undershooting make the design architecture more susceptible to errors. These disadvantages have substantial impacts on the workings of algorithms, which ultimately affect the performances of autonomous vehicles.

4.1.2. Sensor Dependence

The placement of onboard sensors is the most commonly used strategy for path identification [156,157]. However, the readings obtained from such sensors are greatly impacted by noise and system oscillations; therefore, such readings are neither accurate nor precise, resulting in an uncertainty in the system output and accidental inaccuracy in the algorithm output [158].

4.1.3. Dependent on Environmental Observation

Certain algorithms rely on the surrounding information for their navigational decisions. This causes unwanted halts in the vehicle’s motion. Baldoni et al. [159] addressed the same difficulty with the aid of simulations. He presented that generating an optimal efficient trajectory for any kind of mobile vehicle is hard; even so, if that vehicle is able to arrive at its intended point, no algorithm can claim to generate a smooth path for its navigation.

4.1.4. Computational Cost

Algorithm proofs are easy in a simulated world; however, the onboard implementations of algorithms are computationally expensive. Furthermore, it is necessary to consider the robot’s orientation and utilize the robot’s real footprint for non-circular robots working in crowded environments with small pathways (such as entrances and parking places) [160]. The cost of such planning increases for a number of reasons. First, it must be completed in at least three dimensions (x, y, and orientation). Second, it is quite expensive to estimate an action’s cost. Since it entails convolution (the set of all the cells visited by the robot during execution), this cost evaluation approach typically ends up taking the longest amount of time in the planning process. For instance, a basic turn-in-place movement using a 1 by 1 m square robot operating in a 2.5 cm grid covers over 500 cells.

4.1.5. Insufficient Literature on Space Exploration

The literature depicts the number of authors that have worked on path planning for ground and aerial vehicles. The literature offers a wide range of algorithm implementations for path planning but fewer for space exploration. Even the review papers are written on path planning but not for any other type of research [161,162,163,164].

4.1.6. Simulated Work

The work was conducted using simulation methods; this served as a ’drawback’ pertaining to how the developed algorithm could work in real-time [165,166,167].
Other challenges involved in vehicle maneuverability and algorithms are depicted in Table 4 in the form of highlights.

4.2. Proposed Solutions

Path planning is the most investigated topic in control engineering for land, aerial, and underwater vehicles; it has been further extended to path optimization. Different algorithms [173] involving probabilistic and non-probabilistic techniques, such as A-star; (A-star is designed as a graph traversal problem to help build a robot that can find its own course); the bug algorithm (this robot moves in the direction of the goal until an obstacle is encountered. A canonical direction is followed (clockwise) until the location of the initial encounter is reached); the bug2 algorithm (the robot always attempts to move along the line of sight toward the goal. If an obstacle is encountered, a canonical direction is followed until the line of sight is encountered); artificial potential field (a robot path planning method used to reach the goal point and avoid obstacles by using the magnetic force method, which is the attractive force to reach the goal point and the repulsive force to avoid obstacles in an unknown environment); the rolling window algorithm (this takes full advantage of local, real-time environmental data that the robot has collected; path planning is carried out online in a rolling fashion through efficient scenario prediction); PRM (probabilistic roadmap; an algorithm that builds a graph to perform motion planning), etc., have been utilized to solve optimization problems in all three domains.
These methods were further improved and the authors came up with a number of variants, namely, A*, D*, and various improvements to PRM and APF. No single method can fulfill all objectives, so the integration/hybridization of methods has become a common practice. The nature-inspired algorithms mimic social behaviors for how they appear in nature; therefore, they are modeled as complete optimization algorithms. Nature-inspired algorithms, such as the Grey Wolf Optimizer, Arithmetic Optimizer, Aquila Optimizer, Snake Optimizer, Reptile Search Optimizer, etc., are widely used in this regard. Researchers are also working on controllers, known as sliding mode controllers, adaptive controllers, and linear quadratic controllers, with a combination of nature-inspired methods. Keeping in mind the trends involved in the implementation of different algorithms, the best approach is the hybridization of methods, so that instead of benefiting from a single objective, multiple objectives can be achieved [43,150,174,175,176]. The important aspect to remember is that hybridization may result in increased oscillation in the system performance, additional noise, or an increase in computational complexity. Nonetheless, the added advantages after integration are not comparable to other deficiencies. The trade-off is always observed under such circumstances.
Table 5 describes each path planning category’s key characteristics using the suggested categorization scheme in this study. A detailed discussion of the algorithm along with its merits and demerits is presented in the Table 5.

4.3. Potential Future Directions

For insight into trajectory generation, the utilization of the newly developed Aquila Optimizer with widespread potential utilization is a potential direction to look into. The Aquila Optimizer (AO) is a nature-inspired algorithm [32]. This nature-inspired Aquila Optimizer—with minor modifications—was merged with multi-coordinated robot exploration. Readers may be interested in using these strategies for trajectory optimization and area surfing. Instead of employing a single robot, multiple robots can be coordinated. Another alternative route (with the same notion but a different optimization strategy) may be found in [186].
We present insight into the Aquila Optimizer (as a tentative future direction). In AO, there are two hyperparameters: quality function (QF) and G2. QF is used to bring equilibrium in the search strategies and G2 is a stochastic parameter that linearly decreases during the course of iteration; it represents the flight slope of AO, which it follows for prey during the elope movement. The findings demonstrate that when G2 < 1, G2 is a convex function, which allows for a more thorough exploration of the method in the early stages rather than abruptly converging to a limited area. Another version, the Adaptive Aquila Optimizer (AAO) based on these findings, is also proposed. In this, not only the G2 and QF are adaptively modified but the alpha; a hyperparameter was introduced to control the decrease of G2 function. The parameters were changed into modified adaptive functions; refer to Equations (11)–(14) and Algorithm 1. A few results are elaborated in Figure 3. Another possible direction could be found in [196].
a l p h a = a l p h a m i n + ( a l p h a m a x a l p h a m i n ) × f m a x f m i n f a v g f m i n f m a x f a v g
a l p h a m i n + ( a l p h a m a x a l p h a m i n ) × f m a x f m i n f m a x f a v g f m a x f a v g
a l p h a = 1 a l p h a ( t ) + e p s
G 2 = 2 × ( 1 t T ) a l p h a
Q F ( t ) = t 2 × 1 ( 1 T ) 2

5. Conclusions

We covered a number of methods for producing the best coverage pathways in spaces and addressed different errors when executing coverage. For autonomous vehicles, trajectory planning is of fundamental importance. A lot of research has been conducted in the last decade to address the strengths and challenges of autonomous vehicles. The numerical approaches and optimization techniques used in ground, airborne, and underwater vehicles were thoroughly discussed and described in this work. From the standpoint of use on land, aerial, and underwater vehicles, a full analysis of trajectory planning and optimization was offered. Different algorithms were addressed, which were numerical strategies used for accomplishing path planning. Finally, we discussed future directions for multi-robot coverage techniques that, in addition to increasing robustness guarantees, shorten the completion times by distributing the tasks among the many robot team members.
The most pertinent conclusion points are summarized as follows:
(1)
Consolidation of available information. A detailed review of the trajectory planning and optimization is presented from the application points of view of ground (single and multi-robot), aerial, and underwater vehicles. Solutions along with future directions are presented at the end of the manuscript.
(2)
Problem formulation and generation of optimal trajectories. An explanation of how different algorithms could be integrated to build a mathematical model for planning and the formation of trajectory components were presented with a literature survey.
(3)
Limitations and a way forward. Though numerous works have reviewed robotics, aerial and underwater vehicle systems have been presented together with optimization techniques and numerical methods, and no single algorithm produced desired results or accurate output; therefore, a hybridization of different algorithms was used by researchers. Two optimization algorithms or two numerical methods together can be integrated, or a mix and match of techniques can be used to obtain the desired characteristics results.

Author Contributions

Conceptualization, I.M. and F.G.; methodology, I.M., F.G., N.S. and B.A.; software, F.G.; validation, S.M. and M.A.K.; formal analysis, F.G.; investigation, I.M. and F.G. and N.S.; resources, A.H.G. and L.A.; data curation, I.M. and F.G.; writing—original draft preparation, F.G.; writing—review and editing, F.G., I.M. and M.A.K.; visualization, F.G.; supervision, I.M. and S.M.; project administration, I.M.; funding acquisition, A.H.G. and L.A. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
UAVUnmanned Aerial Vehicles
AUVAutonomous Underwater Vehicles
UGVsUnmanned Ground Vehicles
SLAMSimultaneous Localization and Mapping
sUAVSmall Unmanned Aerial Vehicle
UAAVUnmanned Aerial-Aquatic Vehicle
ROSRobot Operating System
UUVUnmanned Underwater Vehicle
GPSGlobal Positioning System
IMUInertial Measurement Unit
MPCModel Predictive Control
INInertial Navigation
IMImage Processing Technique
RLReinforcement Learning
PSOParticle Swarm Optimization
GWOGrey Wolf Optimization
ANNArtificial Neural Network
GAGenetic Algorithm
ALOAnt Lion Optimization
WOAWhale Optimization
MFOMoth Flame Optimization
PRMProbabilistic Roadmap
CNNConvolutional Neural Network
SLISylvester Law of Inertia
UWGUnderwater Glider

References

  1. Berlin, T. Spirit of Berlin: An Autonomous Car for the DARPA Urban Challenge Hardware and Software Architecture. Available online: https://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.108.3075&rep=rep1&type=pdf (accessed on 27 June 2022).
  2. Gul, F.; Mir, I.; Abualigah, L.; Sumari, P.; Forestiero, A. A Consolidated Review of Path Planning and Optimization Techniques: Technical Perspectives and Future Directions. Electronics 2021, 10, 2250. [Google Scholar] [CrossRef]
  3. Aguilar, W.G.; Sandoval, S.; Limaico, A.; Villegas-Pico, M.; Asimbaya, I. Path Planning Based Navigation Using LIDAR for an Ackerman Unmanned Ground Vehicle. In Proceedings of the International Conference on Intelligent Robotics and Applications, Shenyang, China, 8–11 August 2019; pp. 399–410. [Google Scholar]
  4. Le, A.V.; Nhan, N.H.K.; Mohan, R.E. Evolutionary algorithm-based complete coverage path planning for tetriamond tiling robots. Sensors 2020, 20, 445. [Google Scholar] [CrossRef] [PubMed]
  5. Thoma, J.; Paudel, D.P.; Chhatkuli, A.; Probst, T.; Gool, L.V. Mapping, localization and path planning for image-based navigation using visual features and map. In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition, Long Beach, CA, USA, 15–20 June 2019; pp. 7383–7391. [Google Scholar]
  6. Krell, E.; Sheta, A.; Balasubramanian, A.P.R.; King, S.A. Collision-free autonomous robot navigation in unknown environments utilizing pso for path planning. J. Artif. Intell. Soft Comput. Res. 2019, 9, 267–282. [Google Scholar] [CrossRef]
  7. Vis, I.F. Survey of research in the design and control of automated guided vehicle systems. Eur. J. Oper. Res. 2006, 170, 677–709. [Google Scholar] [CrossRef]
  8. Sanchez-Lopez, J.L.; Wang, M.; Olivares-Mendez, M.A.; Molina, M.; Voos, H. A real-time 3d path planning solution for collision-free navigation of multirotor aerial robots in dynamic environments. J. Intell. Robot. Syst. 2019, 93, 33–53. [Google Scholar] [CrossRef]
  9. Hussain, A.; Hussain, I.; Mir, I.; Afzal, W.; Anjum, U.; Channa, B.A. Target Parameter Estimation in Reduced Dimension STAP for Airborne Phased Array Radar. In Proceedings of the 2020 IEEE 23rd International Multitopic Conference (INMIC), Bahawalpur, Pakistan, 5–7 November 2020; pp. 1–6. [Google Scholar]
  10. Yi, J.H.; Lu, M.; Zhao, X.J. Quantum inspired monarch butterfly optimisation for UCAV path planning navigation problem. Int. J. Bio-Inspired Comput. 2020, 15, 75–89. [Google Scholar] [CrossRef]
  11. Majeed, A.; Lee, S. A new coverage flight path planning algorithm based on footprint sweep fitting for unmanned aerial vehicle navigation in urban environments. Appl. Sci. 2019, 9, 1470. [Google Scholar] [CrossRef]
  12. Hussain, A.; Anjum, U.; Channa, B.A.; Afzal, W.; Hussain, I.; Mir, I. Displaced Phase Center Antenna Processing For Airborne Phased Array Radar. In Proceedings of the 2021 International Bhurban Conference on Applied Sciences and Technologies (IBCAST), Islamabad, Pakistan, 12–16 January 2021; pp. 988–992. [Google Scholar]
  13. Forestiero, A.; Mastroianni, C.; Spezzano, G. Building a peer-to-peer information system in grids via self-organizing agents. J. Grid Comput. 2008, 6, 125–140. [Google Scholar] [CrossRef]
  14. Forestiero, A. Heuristic recommendation technique in Internet of Things featuring swarm intelligence approach. Expert Syst. Appl. 2022, 187, 115904. [Google Scholar] [CrossRef]
  15. Rath, M.K.; Deepak, B. PSO based system architecture for path planning of mobile robot in dynamic environment. In Proceedings of the 2015 Global Conference on Communication Technologies (GCCT), Thuckalay, India, 23–24 April 2015; pp. 797–801. [Google Scholar]
  16. Mir, I.; Eisa, S.A.; Maqsood, A. Review of dynamic soaring: Technical aspects, nonlinear modeling perspectives and future directions. Nonlinear Dyn. 2018, 94, 3117–3144. [Google Scholar] [CrossRef]
  17. Noor, M.A.; Noor, K.I.; Al-Said, E.; Waseem, M. Some new iterative methods for nonlinear equations. Math. Probl. Eng. 2010, 2010, 198943. [Google Scholar] [CrossRef]
  18. Hull, T.; Enright, W.H.; Jackson, K. Runge-Kutta Research at Toronto. Appl. Numer. Math. 1996, 22, 225–236. [Google Scholar] [CrossRef]
  19. Verbeke, J.; Cools, R. The Newton-Raphson method. Int. J. Math. Educ. Sci. Technol. 1995, 26, 177–193. [Google Scholar] [CrossRef]
  20. Wood, G.R. The bisection method in higher dimensions. Math. Program. 1992, 55, 319–337. [Google Scholar] [CrossRef]
  21. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey wolf optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef]
  22. Mirjalili, S.; Lewis, A. The whale optimization algorithm. Adv. Eng. Softw. 2016, 95, 51–67. [Google Scholar] [CrossRef]
  23. Meraihi, Y.; Ramdane-Cherif, A.; Acheli, D.; Mahseur, M. Dragonfly algorithm: A comprehensive review and applications. Neural Comput. Appl. 2020, 32, 16625–16646. [Google Scholar] [CrossRef]
  24. Abualigah, L.; Shehab, M.; Alshinwan, M.; Alabool, H. Salp swarm algorithm: A comprehensive survey. Neural Comput. Appl. 2019, 32, 1–21. [Google Scholar] [CrossRef]
  25. Saremi, S.; Mirjalili, S.; Lewis, A. Grasshopper optimisation algorithm: Theory and application. Adv. Eng. Softw. 2017, 105, 30–47. [Google Scholar] [CrossRef]
  26. Brammya, G.; Praveena, S.; Ninu Preetha, N.; Ramya, R.; Rajakumar, B.; Binu, D. Deer hunting optimization algorithm: A new nature-inspired meta-heuristic paradigm. Comput. J. 2019. [Google Scholar] [CrossRef]
  27. Mirjalili, S. The ant lion optimizer. Adv. Eng. Softw. 2015, 83, 80–98. [Google Scholar] [CrossRef]
  28. Mirjalili, S. Moth-flame optimization algorithm: A novel nature-inspired heuristic paradigm. Knowl.-Based Syst. 2015, 89, 228–249. [Google Scholar] [CrossRef]
  29. Ma, G.; Zhang, Y.; Nee, A. A simulated annealing-based optimization algorithm for process planning. Int. J. Prod. Res. 2000, 38, 2671–2687. [Google Scholar] [CrossRef]
  30. Abualigah, L.; Diabat, A.; Mirjalili, S.; Abd Elaziz, M.; Gandomi, A.H. The arithmetic optimization algorithm. Comput. Methods Appl. Mech. Eng. 2021, 376, 113609. [Google Scholar] [CrossRef]
  31. Gao, X.Z.; Govindasamy, V.; Xu, H.; Wang, X.; Zenger, K. Harmony search method: Theory and applications. Comput. Intell. Neurosci. 2015, 2015, 258491. [Google Scholar] [CrossRef]
  32. Abualigah, L.; Yousri, D.; Abd Elaziz, M.; Ewees, A.A.; Al-qaness, M.A.; Gandomi, A.H. Aquila Optimizer: A novel meta-heuristic optimization Algorithm. Comput. Ind. Eng. 2021, 157, 107250. [Google Scholar] [CrossRef]
  33. Jain, M.; Maurya, S.; Rani, A.; Singh, V. Owl search algorithm: A novel nature-inspired heuristic paradigm for global optimization. J. Intell. Fuzzy Syst. 2018, 34, 1573–1582. [Google Scholar] [CrossRef]
  34. Yiqing, L.; Xigang, Y.; Yongjian, L. An improved PSO algorithm for solving non-convex NLP/MINLP problems with equality constraints. Comput. Chem. Eng. 2007, 31, 153–162. [Google Scholar] [CrossRef]
  35. Huang, W.H.; Fajen, B.R.; Fink, J.R.; Warren, W.H. Visual navigation and obstacle avoidance using a steering potential function. Robot. Auton. Syst. 2006, 54, 288–299. [Google Scholar] [CrossRef]
  36. Gul, F.; Rahiman, W. An Integrated approach for Path Planning for Mobile Robot Using Bi-RRT. In Proceedings of the IOP Conference Series: Materials Science and Engineering, Terengganu, Malaysia, 27–28 August 2019; Volume 697, p. 012022. [Google Scholar]
  37. Gul, F.; Rahiman, W.; Nazli Alhady, S.S. A comprehensive study for robot navigation techniques. Cogent Eng. 2019, 6, 1632046. [Google Scholar] [CrossRef]
  38. Tzafestas, S.G. Mobile robot path, motion, and task planning. Introd. Mob. Robot. Control. 2014, 429–478. [Google Scholar] [CrossRef]
  39. Contreras-Cruz, M.A.; Ayala-Ramirez, V.; Hernandez-Belmonte, U.H. Mobile robot path planning using artificial bee colony and evolutionary programming. Appl. Soft Comput. 2015, 30, 319–328. [Google Scholar] [CrossRef]
  40. Ganeshmurthy, M.; Suresh, G. Path planning algorithm for autonomous mobile robot in dynamic environment. In Proceedings of the 2015 3rd International Conference on Signal Processing, Communication and Networking (ICSCN), Chennai, India, 26–28 March 2015; pp. 1–6. [Google Scholar]
  41. Montiel, O.; Orozco-Rosas, U.; Sepúlveda, R. Path planning for mobile robots using Bacterial Potential Field for avoiding static and dynamic obstacles. Expert Syst. Appl. 2015, 42, 5177–5191. [Google Scholar] [CrossRef]
  42. Tuncer, A.; Yildirim, M. Design and implementation of a genetic algorithm IP core on an FPGA for path planning of mobile robots. Turk. J. Electr. Eng. Comput. Sci. 2016, 24, 5055–5067. [Google Scholar] [CrossRef]
  43. Szczepanski, R.; Bereit, A.; Tarczewski, T. Efficient Local Path Planning Algorithm Using Artificial Potential Field Supported by Augmented Reality. Energies 2021, 14, 6642. [Google Scholar] [CrossRef]
  44. Chaari, I.; Koubaa, A.; Bennaceur, H.; Ammar, A.; Alajlan, M.; Youssef, H. Design and performance analysis of global path planning techniques for autonomous mobile robots in grid environments. Int. J. Adv. Robot. Syst. 2017, 14, 1729881416663663. [Google Scholar] [CrossRef]
  45. Do, C.H.; Lin, H.Y. Differential evolution for optimizing motion planning of mobile robot. In Proceedings of the 2017 IEEE/SICE International Symposium on System Integration (SII), Taipei, Taiwan, 11–14 December 2017; pp. 399–404. [Google Scholar]
  46. Szczepanski, R.; Tarczewski, T. Global path planning for mobile robot based on Artificial Bee Colony and Dijkstra’s algorithms. In Proceedings of the 2021 IEEE 19th International Power Electronics and Motion Control Conference (PEMC), Gliwice, Poland, 25–29 April 2021; pp. 724–730. [Google Scholar]
  47. Bertozzi, M.; Broggi, A.; Fascioli, A. Vision-based intelligent vehicles: State of the art and perspectives. Robot. Auton. Syst. 2000, 32, 1–16. [Google Scholar] [CrossRef]
  48. Franke, U.; Gavrila, D.; Gern, A.; Görzig, S.; Janssen, R.; Paetzold, F.; Wöhler, C. From door to door—Principles and applications of computer vision for driver assistant systems. In Intelligent Vehicle Technologies; Elsevier: Amsterdam, The Netherlands, 2001; pp. 131–188. [Google Scholar]
  49. Dickmanns, E.D.; Behringer, R.; Dickmanns, D.; Hildebrandt, T.; Maurer, M.; Thomanek, F.; Schiehlen, J. The seeing passenger car’VaMoRs-P’. In Proceedings of the Intelligent Vehicles’ 94 Symposium, Paris, France, 24–26 October 1994; pp. 68–73. [Google Scholar]
  50. Nagel, H.H.; Enkelmann, W.; Struck, G. FhG-Co-Driver: From map-guided automatic driving by machine vision to a cooperative driver support. Math. Comput. Model. 1995, 22, 185–212. [Google Scholar] [CrossRef]
  51. Thorpe, C.; Hebert, M.H.; Kanade, T.; Shafer, S.A. Vision and navigation for the Carnegie-Mellon Navlab. IEEE Trans. Pattern Anal. Mach. Intell. 1988, 10, 362–373. [Google Scholar] [CrossRef]
  52. Kahveci, N.E.; Ioannou, P.A. Adaptive steering control for uncertain ship dynamics and stability analysis. Automatica 2013, 49, 685–697. [Google Scholar] [CrossRef]
  53. Rao, A.V. A survey of numerical methods for optimal control. Adv. Astronaut. Sci. 2009, 135, 497–528. [Google Scholar]
  54. Bock, H.G.; Plitt, K.J. A multiple shooting algorithm for direct solution of optimal control problems. IFAC Proc. Vol. 1984, 17, 1603–1608. [Google Scholar] [CrossRef]
  55. Abualigah, L.; Elaziz, M.A.; Khodadadi, N.; Forestiero, A.; Jia, H.; Gandomi, A.H. Aquila Optimizer Based PSO Swarm Intelligence for IoT Task Scheduling Application in Cloud Computing. In Integrating Meta-Heuristics and Machine Learning for Real-World Optimization Problems; Springer: Berlin/Heidelberg, Germany, 2022; pp. 481–497. [Google Scholar]
  56. Janet, J.A.; Luo, R.C.; Kay, M.G. The essential visibility graph: An approach to global motion planning for autonomous mobile robots. In Proceedings of the 1995 IEEE International Conference on Robotics and Automation, Nagoya, Japan, 21–27 May 1995; Volume 2, pp. 1958–1963. [Google Scholar]
  57. Mir, I. Dynamics, Numeric Optimization and Control of Dynamic Soaring Maneuvers for a Morphing Capable Unmanned Aerial Vehicle. Ph.D. Thesis, National University of Sciences & Technology, Islamabad, Pakistan, 2018. [Google Scholar]
  58. Schubert, K.F.; Rao, A.V. Minimum-Time Low-Earth Orbit to High-Earth Orbit Low-Thrust Trajectory Optimization. In Proceedings of the AAS/AIAA Astrodynamics Specialist Conference, Hilton Head, SC, USA, 11–15 August 2013. [Google Scholar]
  59. Jodeh, N.M.; Coon, T.; Masternak, T.J.; Cobb, R.; Agte, J.S. Optimal Airborne Trajectories for Data Collected from Emplaced Ground Sensor Arrays. In Proceedings of the AIAA Guidance, Navigation, and Control Conference, National Harbor, MD, USA, 13–17 January 2014; p. 1291. [Google Scholar]
  60. Kim, M.K.; Tahk, M.J.; Park, B.G.; Kim, Y.Y. Terminal Velocity Maximization of Air-to-Air Missiles in Agile Turn Phase. In Proceedings of the MATEC Web of Conferences, Chongqing, China, 15–17 June 2016; EDP Sciences: Les Ulis, France, 2016; Volume 77, p. 07009. [Google Scholar]
  61. Zhou, W.; Zhang, C.; Li, J.; Fathy, H.K. A pseudospectral strategy for optimal power management in series hybrid electric powertrains. IEEE Trans. Veh. Technol. 2016, 65, 4813–4825. [Google Scholar] [CrossRef]
  62. Hong, S.M.; Seo, M.G.; Shim, S.W.; Tahk, M.J.; Lee, C.H. Sensitivity analysis on weight and trajectory optimization results for multistage guided missile. IFAC-PapersOnLine 2016, 49, 23–27. [Google Scholar] [CrossRef]
  63. Dahmen, T.; Saupeand, D. Optimal pacing strategy for a race of two competing cyclists. J. Sci. Cycl. 2014, 3, 12. [Google Scholar]
  64. Hu, X.; Perez, H.E.; Moura, S.J. Battery charge control with an electro-thermal-aging coupling. In Proceedings of the ASME 2015 Dynamic Systems and Control Conference. American Society of Mechanical Engineers, Columbus, OH, USA, 28–30 October 2015. [Google Scholar] [CrossRef]
  65. Kodera, M.; Ogawa, H.; Tomioka, S.; Ueda, S. Multi-objective design and trajectory optimization of space transport systems with RBCC propulsion via evolutionary algorithms and pseudospectral methods. In Proceedings of the 52nd Aerospace Sciences Meeting, National Harbor, MD, USA, 13–17 January 2014; p. 0629. [Google Scholar]
  66. Diwale, S.S.; Lymperopoulos, I.; Jones, C.N. Optimization of an airborne wind energy system using constrained gaussian processes. In Proceedings of the Control Applications (CCA), 2014 IEEE Conference on, Dubrovnik, Croatia, 3–5 October 2014; pp. 1394–1399. [Google Scholar]
  67. Moon, Y.; Kwon, S. Lunar soft landing with minimum-mass propulsion system using H2O2/kerosene bipropellant rocket system. Acta Astronaut. 2014, 99, 153–157. [Google Scholar] [CrossRef]
  68. Kaushik, H.; Mohan, R.; Prakash, K.A. Utilization of wind shear for powering unmanned aerial vehicles in surveillance application: A numerical optimization study. Energy Procedia 2016, 90, 349–359. [Google Scholar] [CrossRef]
  69. Hu, X.; Li, S.; Peng, H.; Sun, F. Charging time and loss optimization for LiNMC and LiFePO4 batteries based on equivalent circuit models. J. Power Sources 2013, 239, 449–457. [Google Scholar] [CrossRef]
  70. Wolf, S.; Bertschinger, R.; Saupe, D. Road cycling climbs made speedier by personalized pacing strategies. In Proceedings of the 4th International Congress on Sport Sciences Research and Technology Support, Porto, Portugal, 7–9 November 2016; pp. 109–114. [Google Scholar]
  71. Coşkun, E.c. Multistage Launch Vehicle Design with Thrust Profile and Trajectory Optimization. Ph.D. Thesis, Middle East Technical University, Çankaya/Ankara, Turkey, 2014. [Google Scholar]
  72. Grymin, D.J.; Farhood, M. Two-step system identification for control of small UAVs along pre-specified trajectories. In Proceedings of the American Control Conference (ACC), Portland, OR, USA, 4–6 June 2014; pp. 4404–4409. [Google Scholar]
  73. Lührs, B.; Niklass, M.; Froemming, C.; Grewe, V.; Gollnick, V. Cost-benefit assessment of 2d and 3d climate and weather optimized trajectories. In Proceedings of the 16th AIAA Aviation Technology, Integration, and Operations Conference, Washington, DC, USA, 13–17 June 2016; p. 3758. [Google Scholar]
  74. Peloni, A.; Rao, A.V.; Ceriotti, M. Automated Trajectory Optimizer for Solar Sailing (ATOSS). Aerosp. Sci. Technol. 2018, 72, 465–475. [Google Scholar] [CrossRef]
  75. Smith, E.; Tavernini, D.; Claret, C.; Velenis, E.; Cao, D. Optimal yaw-rate target for electric vehicle torque vectoring system. In The Dynamics of Vehicles on Roads and Tracks: Proceedings of the 24th Symposium of the International Association for Vehicle System Dynamics (IAVSD 2015), Graz, Austria, 17–21 August 2015; CRC Press: Boca Raton, FL, USA, 2016; p. 107. [Google Scholar]
  76. Gul, F.; Rahiman, W.; Alhady, S.N.; Ali, A.; Mir, I.; Jalil, A. Meta-heuristic approach for solving multi-objective path planning for autonomous guided robot using PSO–GWO optimization algorithm with evolutionary programming. J. Ambient. Intell. Humaniz. Comput. 2021, 12, 7873–7890. [Google Scholar] [CrossRef]
  77. Owen, M.P.; Duffy, S.M.; Edwards, M.W. Unmanned aircraft sense and avoid radar: Surrogate flight testing performance evaluation. In Proceedings of the 2014 IEEE Radar Conference, Cincinnati, OH, USA, 19–23 May 2014; pp. 0548–0551. [Google Scholar]
  78. Mir, I.; Maqsood, A.; Taha, H.E.; Eisa, S.A. Soaring Energetics for a Nature Inspired Unmanned Aerial Vehicle. In Proceedings of the AIAA Scitech 2019 Forum, San Diego, CA, USA, 7–11 January 2019; p. 1622. [Google Scholar]
  79. Mir, I.; Akhtar, S.; Eisa, S.; Maqsood, A. Guidance and control of standoff air-to-surface carrier vehicle. Aeronaut. J. 2019, 123, 283–309. [Google Scholar] [CrossRef]
  80. Mohamed, S.A.; Haghbayan, M.H.; Westerlund, T.; Heikkonen, J.; Tenhunen, H.; Plosila, J. A survey on odometry for autonomous navigation systems. IEEE Access 2019, 7, 97466–97486. [Google Scholar] [CrossRef]
  81. Mir, I.; Maqsood, A.; Akhtar, S. Dynamic modeling & stability analysis of a generic UAV in glide phase. In Proceedings of the MATEC Web of Conferences, Beijing, China, 12–14 May 2017; EDP Sciences: Les Ulis, France, 2017; Volume 114, p. 01007. [Google Scholar]
  82. Bitzinger, R.A. Chapter 2: Transition and Readjustment in Second-Tier Defence Industries: Five Case Studies. Adelphi Ser. 2003, 43, 39–62. [Google Scholar] [CrossRef]
  83. Mir, I.; Taha, H.; Eisa, S.A.; Maqsood, A. A controllability perspective of dynamic soaring. Nonlinear Dyn. 2018, 94, 2347–2362. [Google Scholar] [CrossRef]
  84. Mir, I.; Maqsood, A.; Akhtar, S. Optimization of Dynamic Soaring Maneuvers for a Morphing Capable UAV. In Proceedings of the AIAA Information Systems-AIAA Infotech@ Aerospace, Grapevine, TX, USA, 9–13 January 2017; p. 0678. [Google Scholar]
  85. Mir, I.; Maqsood, A.; Eisa, S.A.; Taha, H.; Akhtar, S. Optimal morphing–augmented dynamic soaring maneuvers for unmanned air vehicle capable of span and sweep morphologies. Aerosp. Sci. Technol. 2018, 79, 17–36. [Google Scholar] [CrossRef]
  86. Hasircioglu, I.; Topcuoglu, H.R.; Ermis, M. 3-D path planning for the navigation of unmanned aerial vehicles by using evolutionary algorithms. In Proceedings of the 10th Annual Conference on Genetic and Evolutionary Computation, Atlanta, GA, USA, 12–16 July 2008; pp. 1499–1506. [Google Scholar]
  87. Caselli, S.; Reggiani, M.; Rocchi, R. Heuristic methods for randomized path planning in potential fields. In Proceedings of the 2001 IEEE International Symposium on Computational Intelligence in Robotics and Automation (Cat. No. 01EX515), Banff, AB, Canada, 29 July–1 August 2001; pp. 426–431. [Google Scholar]
  88. Saska, M.; Macas, M.; Preucil, L.; Lhotska, L. Robot path planning using particle swarm optimization of Ferguson splines. In Proceedings of the 2006 IEEE Conference on Emerging Technologies and Factory Automation, Prague, Czech Republic, 20–22 September 2006; pp. 833–839. [Google Scholar]
  89. Mansury, E.; Nikookar, A.; Salehi, M.E. Artificial Bee Colony optimization of ferguson splines for soccer robot path planning. In Proceedings of the 2013 First RSI/ISM International Conference on Robotics and Mechatronics (ICRoM), Tehran, Iran, 13–15 February 2013; pp. 85–89. [Google Scholar]
  90. Zhao, Y.J. Optimal patterns of glider dynamic soaring. Optim. Control. Appl. Methods 2004, 25, 67–89. [Google Scholar] [CrossRef]
  91. Zhao, Y.J.; Qi, Y.C. Minimum fuel powered dynamic soaring of unmanned aerial vehicles utilizing wind gradients. Optim. Control. Appl. Methods 2004, 25, 211–233. [Google Scholar] [CrossRef]
  92. Gill, P.E.; Murray, W.; Saunders, M.A.; Wright, M.H. User’s Guide for NPSOL (version 4.0): A Fortran Package for Nonlinear Programming; Technical report; Stanford Univ Ca Systems Optimization Lab: Standford, CA, USA, 1986. [Google Scholar]
  93. Zhang, Z.; Xie, P.; Ma, O. Bio-inspired trajectory generation for UAV perching. In Proceedings of the 2013 IEEE/ASME International Conference on Advanced Intelligent Mechatronics, Wollongong, Australia, 9–12 July 2013; pp. 997–1002. [Google Scholar]
  94. Moses, A.; Rutherford, M.J.; Kontitsis, M.; Valavanis, K.P. UAV-borne X-band radar for collision avoidance. Robotica 2014, 32, 97. [Google Scholar] [CrossRef]
  95. Hügler, P.; Roos, F.; Schartel, M.; Geiger, M.; Waldschmidt, C. Radar taking off: New capabilities for UAVs. IEEE Microw. Mag. 2018, 19, 43–53. [Google Scholar] [CrossRef]
  96. Asvadi, A.; Peixoto, P.; Nunes, U. Detection and tracking of moving objects using 2.5 d motion grids. In Proceedings of the 2015 IEEE 18th International Conference on Intelligent Transportation Systems, Gran Canaria, Spain, 5–18 September 2015; pp. 788–793. [Google Scholar]
  97. Azim, A.; Aycard, O. Layer-based supervised classification of moving objects in outdoor dynamic environment using 3D laser scanner. In Proceedings of the 2014 IEEE Intelligent Vehicles Symposium Proceedings, Dearborn, MI, USA, 8–11 June 2014; pp. 1408–1414. [Google Scholar]
  98. Kim, Y.; Park, J.; Son, W.; Yoon, T. Modified turn algorithm for motion planning based on clothoid curve. Electron. Lett. 2017, 53, 1574–1576. [Google Scholar] [CrossRef]
  99. Zhang, K.; Sprinkle, J.; Sanfelice, R.G. A hybrid model predictive controller for path planning and path following. In Proceedings of the ACM/IEEE Sixth International Conference on Cyber-Physical Systems, Seattle, WA, USA, 14–16 April 2015; pp. 139–148. [Google Scholar]
  100. Sudhakara, P.; Ganapathy, V.; Sundaran, K. Optimal trajectory planning based on bidirectional spline-RRT for wheeled mobile robot. In Proceedings of the 2017 Third International Conference on Sensing, Signal Processing and Security (ICSSS), Chennai, India, 4–5 May 2017; pp. 65–68. [Google Scholar]
  101. Soylu, S.; Buckham, B.J.; Podhorodeski, R.P. A chattering-free sliding-mode controller for underwater vehicles with fault-tolerant infinity-norm thrust allocation. Ocean. Eng. 2008, 35, 1647–1659. [Google Scholar] [CrossRef]
  102. Herman, P. Numerical Test of Underwater Vehicle Dynamics Using Velocity Controller. In Proceedings of the 2019 12th International Workshop on Robot Motion and Control (RoMoCo), Poznań, Poland, 8–10 July 2019; pp. 26–31. [Google Scholar]
  103. Shen, C.; Shi, Y.; Buckham, B. Model predictive control for an AUV with dynamic path planning. In Proceedings of the 2015 54th Annual Conference of the Society of Instrument and Control Engineers of Japan (SICE), Hangzhou, China, 28–30 July 2015; pp. 475–480. [Google Scholar]
  104. Liu, C.; Lee, S.; Varnhagen, S.; Tseng, H.E. Path planning for autonomous vehicles using model predictive control. In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 174–179. [Google Scholar]
  105. Siddique, N.; Adeli, H. Nature inspired computing: An overview and some future directions. Cogn. Comput. 2015, 7, 706–714. [Google Scholar] [CrossRef] [PubMed]
  106. Zhang, Y.; Guan, G.; Pu, X. The robot path planning based on improved artificial fish swarm algorithm. Math. Probl. Eng. 2016, 2016, 3297585. [Google Scholar] [CrossRef]
  107. Wang, H.J.; Fu, Y.; Zhao, Z.Q.; Yue, Y.J. An Improved Ant Colony Algorithm of Robot Path Planning for Obstacle Avoidance. J. Robot. 2019, 2019, 6097591. [Google Scholar] [CrossRef]
  108. Saffari, M.; Mahjoob, M. Bee colony algorithm for real-time optimal path planning of mobile robots. In Proceedings of the 2009 Fifth International Conference on Soft Computing, Computing with Words and Perceptions in System Analysis, Decision and Control, Famagusta, North Cyprus, 2–4 September 2009; pp. 1–4. [Google Scholar]
  109. Dao, T.K.; Pan, T.S.; Pan, J.S. A multi-objective optimal mobile robot path planning based on whale optimization algorithm. In Proceedings of the 2016 IEEE 13th International Conference on Signal Processing (ICSP), Chengdu, China, 6–10 November 2016; pp. 337–342. [Google Scholar]
  110. Tsai, P.W.; Dao, T.K. Robot path planning optimization based on multiobjective grey wolf optimizer. In Proceedings of the International Conference on Genetic and Evolutionary Computing, Fuzhou, China, 7–9 November 2016; Springer: Berlin/Heidelberg, Germany, 2016; pp. 166–173. [Google Scholar]
  111. Guo, J.; Gao, Y.; Cui, G. The path planning for mobile robot based on bat algorithm. Int. J. Autom. Control. 2015, 9, 50–60. [Google Scholar] [CrossRef]
  112. Yang, X.S. Nature-Inspired Metaheuristic Algorithms; Luniver Press: Bristol, UK, 2010. [Google Scholar]
  113. Surmann, H.; Kanstein, A.; Goser, K. Self-organizing and genetic algorithms for an automatic design of fuzzy control and decision systems. In Proceedings of the EUFIT’93, Aachen, Germany, 7–10 September 1993. [Google Scholar]
  114. Payne, D.; Stern, J. Wavelength-switched passively coupled single-mode optical network. In Proceedings of the IOOC-ECOC, Venezia, Italy, 1–4 October 1985; Volume 85, p. 585. [Google Scholar]
  115. Karaboga, D.; Akay, B. A comparative study of artificial bee colony algorithm. Appl. Math. Comput. 2009, 214, 108–132. [Google Scholar] [CrossRef]
  116. Baykasoğlu, A.; Özbakır, L.; Tapkan, P. Artificial Bee Colony Algorithm and Its Application to Generalized Assignment Problem Swarm Intelligence Focus on Ant and Particle Swarm Optimization. In Swarm Intelligence: Focus on Ant and Particle Swarm Optimization; IntechOpen: London, UK, 2007. [Google Scholar]
  117. Kamil, R.T.; Mohamed, M.J.; Oleiwi, B.K. Path Planning of Mobile Robot Using Improved Artificial Bee Colony Algorithm. Eng. Technol. J. 2020, 38, 1384–1395. [Google Scholar] [CrossRef]
  118. Ismail, A.; Sheta, A.; Al-Weshah, M. A mobile robot path planning using genetic algorithm in static environment. J. Comput. Sci. 2008, 4, 341–344. [Google Scholar]
  119. Mitchell, M. An Introduction to Genetic Algorithms; MIT Press: Cambridge, MA, USA, 1998. [Google Scholar]
  120. Xin, D.; Hua-hua, C.; Wei-kang, G. Neural network and genetic algorithm based global path planning in a static environment. J. Zhejiang Univ. Sci. A 2005, 6, 549–554. [Google Scholar] [CrossRef]
  121. Li, J.; Deng, G.; Luo, C.; Lin, Q.; Yan, Q.; Ming, Z. A hybrid path planning method in unmanned air/ground vehicle (UAV/UGV) cooperative systems. IEEE Trans. Veh. Technol. 2016, 65, 9585–9596. [Google Scholar] [CrossRef]
  122. Lee, J.; Kang, B.Y.; Kim, D.W. Fast genetic algorithm for robot path planning. Electron. Lett. 2013, 49, 1449–1451. [Google Scholar] [CrossRef]
  123. Tian, L.; Collins, C. An effective robot trajectory planning method using a genetic algorithm. Mechatronics 2004, 14, 455–470. [Google Scholar] [CrossRef]
  124. Châari, I.; Koubaa, A.; Bennaceur, H.; Trigui, S.; Al-Shalfan, K. SmartPATH: A hybrid ACO-GA algorithm for robot path planning. In Proceedings of the 2012 IEEE Congress on Evolutionary Computation, Brisbane, Australia, 10–15 June 2012; pp. 1–8. [Google Scholar]
  125. Geisler, T.; Manikas, T.W. Autonomous robot navigation system using a novel value encoded genetic algorithm. In Proceedings of the The 2002 45th Midwest Symposium on Circuits and Systems, 2002. MWSCAS-2002, Tulsa, OK, USA, 4–7 August 2002; Volume 3, p. III. [Google Scholar]
  126. Han, W.G.; Baek, S.M.; Kuc, T.Y. Genetic algorithm based path planning and dynamic obstacle avoidance of mobile robots. In Proceedings of the 1997 IEEE International Conference on Systems, Man, and Cybernetics. Computational Cybernetics and Simulation, Orlando, FL, USA, 12–15 October 1997; Volume 3, pp. 2747–2751. [Google Scholar]
  127. Liu, K.; Zhang, M. Path planning based on simulated annealing ant colony algorithm. In Proceedings of the 2016 9th International Symposium on Computational Intelligence and Design (ISCID), Hangzhou, China, 10–11 December 2016; Volume 2, pp. 461–466. [Google Scholar]
  128. Zhang, S.; Zhou, Y.; Li, Z.; Pan, W. Grey wolf optimizer for unmanned combat aerial vehicle path planning. Adv. Eng. Softw. 2016, 99, 121–136. [Google Scholar] [CrossRef]
  129. Hussien, A.G.; Amin, M.; Abd El Aziz, M. A comprehensive review of moth-flame optimisation: Variants, hybrids, and applications. J. Exp. Theor. Artif. Intell. 2020, 32, 1–21. [Google Scholar] [CrossRef]
  130. Watkins, W.A.; Schevill, W.E. Aerial observation of feeding behavior in four baleen whales: Eubalaena glacialis, Balaenoptera borealis, Megaptera novaeangliae, and Balaenoptera physalus. J. Mammal. 1979, 60, 155–163. [Google Scholar] [CrossRef]
  131. Goldbogen, J.A.; Friedlaender, A.S.; Calambokidis, J.; Mckenna, M.F.; Simon, M.; Nowacek, D.P. Integrative Approaches to the Study of Baleen Whale Diving Behavior, Feeding Performance, and Foraging Ecology. BioScience 2013, 63, 90–100. [Google Scholar] [CrossRef]
  132. Qu, C.; Gai, W.; Zhang, J.; Zhong, M. A novel hybrid grey wolf optimizer algorithm for unmanned aerial vehicle (UAV) path planning. Knowl.-Based Syst. 2020, 194, 105530. [Google Scholar] [CrossRef]
  133. Stark, C.R.; Pyke, L.M. Dynamic pathfinding for a swarm intelligence based UAV control model using particle swarm optimisation. Front. Appl. Math. Stat. 2021, 7, 744955. [Google Scholar]
  134. Saied, M.; Slim, M.; Mazeh, H.; Francis, C.; Shraim, H. Unmanned Aerial Vehicles Fleet Control via Artificial Bee Colony Algorithm. In Proceedings of the 2019 4th Conference on Control and Fault Tolerant Systems (SysTol), Casablanca, Morocco, 18–20 September 2019; pp. 80–85. [Google Scholar]
  135. Janglová, D. Neural networks in mobile robot motion. Int. J. Adv. Robot. Syst. 2004, 1, 2. [Google Scholar] [CrossRef]
  136. Gasparri, A.; Prosperi, M. A bacterial colony growth algorithm for mobile robot localization. Auton. Robot. 2008, 24, 349–364. [Google Scholar] [CrossRef]
  137. Abbas, N.H.; Ali, F.M. Path planning of an autonomous mobile robot using enhanced bacterial foraging optimization algorithm. Al-Khwarizmi Eng. J. 2016, 12, 26–35. [Google Scholar] [CrossRef]
  138. Khalil, A.E.K.; Anwar, S.; Husnain, G.; Elahi, A.; Dong, Z. A Novel Bio-Inspired Path Planning for Autonomous Underwater Vehicle for Search and Tracing of Underwater Target. In Proceedings of the 2021 International Conference on Innovative Computing (ICIC), Online, 15–16 September 2021; pp. 1–7. [Google Scholar]
  139. Zhu, D.; Li, W.; Yan, M.; Yang, S.X. The path planning of AUV based on DS information fusion map building and bio-inspired neural network in unknown dynamic environment. Int. J. Adv. Robot. Syst. 2014, 11, 34. [Google Scholar] [CrossRef]
  140. Yilmaz, N.K.; Evangelinos, C.; Lermusiaux, P.F.; Patrikalakis, N.M. Path planning of autonomous underwater vehicles for adaptive sampling using mixed integer linear programming. IEEE J. Ocean. Eng. 2008, 33, 522–537. [Google Scholar] [CrossRef] [Green Version]
  141. Hu, Y.; Zhao, W.; Wang, L. Vision-based target tracking and collision avoidance for two autonomous robotic fish. IEEE Trans. Ind. Electron. 2009, 56, 1401–1410. [Google Scholar]
  142. Zhu, D.; Huang, H.; Yang, S.X. Dynamic task assignment and path planning of multi-AUV system based on an improved self-organizing map and velocity synthesis method in three-dimensional underwater workspace. IEEE Trans. Cybern. 2013, 43, 504–514. [Google Scholar] [PubMed]
  143. Yuan, H.; Qu, Z. Optimal real-time collision-free motion planning for autonomous underwater vehicles in a 3D underwater space. IET Control. Theory Appl. 2009, 3, 712–721. [Google Scholar] [CrossRef]
  144. Haghighi, H.; Sadati, S.H.; Dehghan, S.; Karimi, J. Hybrid form of particle swarm optimization and genetic algorithm for optimal path planning in coverage mission by cooperated unmanned aerial vehicles. J. Aerosp. Technol. Manag. 2020, 12. [Google Scholar] [CrossRef]
  145. Arantes, M.d.S.; Arantes, J.d.S.; Toledo, C.F.M.; Williams, B.C. A hybrid multi-population genetic algorithm for UAV path planning. In Proceedings of the Genetic and Evolutionary Computation Conference 2016, Denver, CO, USA, 20–24 July 2016; pp. 853–860. [Google Scholar]
  146. Dhargupta, S.; Ghosh, M.; Mirjalili, S.; Sarkar, R. Selective opposition based grey wolf optimization. Expert Syst. Appl. 2020, 151, 113389. [Google Scholar] [CrossRef]
  147. Bouhamed, O.; Ghazzai, H.; Besbes, H.; Massoud, Y. Autonomous UAV navigation: A DDPG-based deep reinforcement learning approach. In Proceedings of the 2020 IEEE International Symposium on Circuits and Systems (ISCAS), Sevilla, Spain, 10–21 October 2020; pp. 1–5. [Google Scholar]
  148. Challita, U.; Saad, W.; Bettstetter, C. Interference management for cellular-connected UAVs: A deep reinforcement learning approach. IEEE Trans. Wirel. Commun. 2019, 18, 2125–2140. [Google Scholar] [CrossRef]
  149. Zhang, P.; Xiong, C.; Li, W.; Du, X.; Zhao, C. Path planning for mobile robot based on modified rapidly exploring random tree method and neural network. Int. J. Adv. Robot. Syst. 2018, 15, 1729881418784221. [Google Scholar] [CrossRef]
  150. Gul, F.; Mir, S.; Mir, I. Coordinated Multi-Robot Exploration: Hybrid Stochastic Optimization Approach. In Proceedings of the AIAA SCITECH 2022 Forum, San Diego, CA, USA, 3–7 January 2022; p. 1414. [Google Scholar]
  151. Bakdi, A.; Hentout, A.; Boutami, H.; Maoudj, A.; Hachour, O.; Bouzouia, B. Optimal path planning and execution for mobile robots using genetic algorithm and adaptive fuzzy-logic control. Robot. Auton. Syst. 2017, 89, 95–109. [Google Scholar] [CrossRef]
  152. Chen, W.; Rahmati, M.; Sadhu, V.; Pompili, D. Real-time Image Enhancement for Vision-based Autonomous Underwater Vehicle Navigation in Murky Waters. In Proceedings of the International Conference on Underwater Networks & Systems, Atlanta, GA, USA, 23–25 October 2019; pp. 1–8. [Google Scholar]
  153. Kumari, S.; Mishra, P.K.; Anand, V. Fault resilient routing based on moth flame optimization scheme for underwater wireless sensor networks. Wirel. Networks 2020, 26, 1417–1431. [Google Scholar] [CrossRef]
  154. Buschhaus, A.; Blank, A.; Ziegler, C.; Franke, J. Highly efficient control system enabling robot accuracy improvement. Procedia CIRP 2014, 23, 200–205. [Google Scholar] [CrossRef]
  155. Qiao, G.; Weiss, B.A. Accuracy degradation analysis for industrial robot systems. In Proceedings of the International Manufacturing Science and Engineering Conference, American Society of Mechanical Engineers, Los Angeles, CA, USA, 4–8 June 2017; Volume 50749, p. V003T04A006. [Google Scholar]
  156. Lagisetty, R.; Philip, N.; Padhi, R.; Bhat, M. Object detection and obstacle avoidance for mobile robot using stereo camera. In Proceedings of the 2013 IEEE International Conference on Control Applications (CCA), Hyderabad, India, 28–30 August 2013; pp. 605–610. [Google Scholar]
  157. Fulgenzi, C.; Spalanzani, A.; Laugier, C. Dynamic obstacle avoidance in uncertain environment combining PVOs and occupancy grid. In Proceedings of the 2007 IEEE International Conference on Robotics and Automation, Roma, Italy, 10–14 April 2007; pp. 1610–1616. [Google Scholar]
  158. Michels, J.; Saxena, A.; Ng, A.Y. High speed obstacle avoidance using monocular vision and reinforcement learning. In Proceedings of the 22nd International Conference on Machine Learning, Bonn, Germany, 7–11 August 2005; pp. 593–600. [Google Scholar]
  159. Baldoni, P.D.; Yang, Y.; Kim, S.Y. Development of efficient obstacle avoidance for a mobile robot using fuzzy Petri nets. In Proceedings of the 2016 IEEE 17th International Conference on Information Reuse and Integration (IRI), Pittsburgh, PA, USA, 28–30 July 2016; pp. 265–269. [Google Scholar]
  160. Likhachev, M.; Ferguson, D. Planning long dynamically feasible maneuvers for autonomous vehicles. Int. J. Robot. Res. 2009, 28, 933–945. [Google Scholar] [CrossRef] [Green Version]
  161. Sánchez-Ibáñez, J.R.; Pérez-del Pulgar, C.J.; García-Cerezo, A. Path Planning for Autonomous Mobile Robots: A Review. Sensors 2021, 21, 7898. [Google Scholar] [CrossRef]
  162. Patle, B.; Pandey, A.; Parhi, D.; Jagadeesh, A. A review: On path planning strategies for navigation of mobile robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
  163. King, J.; Likhachev, M. Efficient cost computation in cost map planning for non-circular robots. In Proceedings of the 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems, St. Louis, MO, USA, 10–15 October 2009; pp. 3924–3930. [Google Scholar]
  164. Campbell, S.; O’Mahony, N.; Carvalho, A.; Krpalkova, L.; Riordan, D.; Walsh, J. Path planning techniques for mobile robots a review. In Proceedings of the 2020 6th International Conference on Mechatronics and Robotics Engineering (ICMRE), Columbus, OH, USA, 27–29 September 2020; pp. 12–16. [Google Scholar]
  165. Ibrahim, M.I.; Sariff, N.; Johari, J.; Buniyamin, N. Mobile robot obstacle avoidance in various type of static environments using fuzzy logic approach. In Proceedings of the 2014 2nd International Conference on Electrical, Electronics and System Engineering (ICEESE), Kuala Lumpur, Malaysia, 9–10 December 2014; pp. 83–88. [Google Scholar]
  166. Ajeil, F.H.; Ibraheem, I.K.; Azar, A.T.; Humaidi, A.J. Grid-based mobile robot path planning using aging-based ant colony optimization algorithm in static and dynamic environments. Sensors 2020, 20, 1880. [Google Scholar] [CrossRef]
  167. Ali, H.; Gong, D.; Wang, M.; Dai, X. Path planning of mobile robot with improved ant colony algorithm and MDP to produce smooth trajectory in grid-based environment. Front. Neurorobotics 2020, 14, 44. [Google Scholar] [CrossRef]
  168. Seraji, H.; Howard, A. Behavior-based robot navigation on challenging terrain: A fuzzy logic approach. IEEE Trans. Robot. Autom. 2002, 18, 308–321. [Google Scholar] [CrossRef]
  169. Sharma, P.S.; Chitaliya, D. Obstacle avoidance using stereo vision: A survey. Int. J. Innov. Res. Comput. Commun. Eng. 2015, 3, 24–29. [Google Scholar] [CrossRef]
  170. Typiak, A. Use of laser rangefinder to detecting in surroundings of mobile robot the obstacles. In Proceedings of the Symposium on Automation and Robotics in Construction, Vilnius, Lithuania, 26–29 June 2008; pp. 26–29. [Google Scholar]
  171. Yang, J.; Chen, P.; Rong, H.J.; Chen, B. Least mean p-power extreme learning machine for obstacle avoidance of a mobile robot. In Proceedings of the 2016 International Joint Conference on Neural Networks (IJCNN), Vancouver, BC, Canada, 24–29 July 2016; pp. 1968–1976. [Google Scholar]
  172. Haykin, S.; Network, N. A comprehensive foundation. Neural Netw. 2004, 2, 41. [Google Scholar]
  173. Sun, B.; Han, D.; Wei, Q. Application of Rolling Window Algorithm to the Robot Path Planning. Comput. Simul. 2006, 23, 159–162. [Google Scholar]
  174. Syed, U.A.; Kunwar, F.; Iqbal, M. Guided Autowave Pulse Coupled Neural Network (GAPCNN) based real time path planning and an obstacle avoidance scheme for mobile robots. Robot. Auton. Syst. 2014, 62, 474–486. [Google Scholar] [CrossRef]
  175. Al-Mutib, K.; Abdessemed, F.; Faisal, M.; Ramdane, H.; Alsulaiman, M.; Bencherif, M. Obstacle avoidance using wall-following strategy for indoor mobile robots. In Proceedings of the 2016 2nd IEEE International Symposium on Robotics and Manufacturing Automation (ROMA), Ipoh, Malaysia, 25–27 September 2016; pp. 1–6. [Google Scholar]
  176. Ahmed, A.A.; Abdalla, T.Y.; Abed, A.A. Path planning of mobile robot by using modified optimized potential field method. Int. J. Comput. Appl. 2015, 113, 6–10. [Google Scholar] [CrossRef]
  177. Zhong, M.; Yang, Y.; Dessouky, Y.; Postolache, O. Multi-AGV scheduling for conflict-free path planning in automated container terminals. Comput. Ind. Eng. 2020, 142, 106371. [Google Scholar] [CrossRef]
  178. Cherroun, L.; Boumehraz, M.; Kouzou, A. Mobile Robot Path Planning Based on Optimized Fuzzy Logic Controllers. In New Developments and Advances in Robot Control; Springer: Berlin/Heidelberg, Germany, 2019; pp. 255–283. [Google Scholar]
  179. Chhotray, A.; Parhi, D.R. Navigational control analysis of two-wheeled self-balancing robot in an unknown terrain using back-propagation neural network integrated modified DAYANI approach. Robotica 2019, 37, 1346–1362. [Google Scholar] [CrossRef]
  180. Naazare, M.; Ramos, D.; Wildt, J.; Schulz, D. Application of Graph-based Path Planning for UAVs to Avoid Restricted Areas. In Proceedings of the 2019 IEEE International Symposium on Safety, Security, and Rescue Robotics (SSRR), Wurzburg, Germany, 2–4 September 2019; pp. 139–144. [Google Scholar]
  181. Burchardt, H.; Salomon, R. Implementation of path planning using genetic algorithms on mobile robots. In Proceedings of the 2006 IEEE International Conference on Evolutionary Computation, Vancouver, BC, Canada, 16–21 July 2006; pp. 1831–1836. [Google Scholar]
  182. Su, K.; Wang, Y.; Hu, X. Robot path planning based on random coding particle swarm optimization. Int. J. Adv. Comput. Sci. Appl. 2015, 6, 58–64. [Google Scholar] [CrossRef]
  183. Darwish, A.H.; Joukhadar, A.; Kashkash, M. Using the Bees Algorithm for wheeled mobile robot path planning in an indoor dynamic environment. Cogent Eng. 2018, 5, 1426539. [Google Scholar] [CrossRef]
  184. Karaboga, D.; Gorkemli, B.; Ozturk, C.; Karaboga, N. A comprehensive survey: Artificial bee colony (ABC) algorithm and applications. Artif. Intell. Rev. 2014, 42, 21–57. [Google Scholar] [CrossRef]
  185. Agushaka, J.O.; Ezugwu, A.E. Advanced arithmetic optimization algorithm for solving mechanical engineering design problems. PLoS ONE 2021, 16, e0255703. [Google Scholar]
  186. Gul, F.; Mir, I.; Abualigah, L.; Sumari, P. Multi-Robot Space Exploration: An Augmented Arithmetic Approach. IEEE Access 2021, 9, 107738–107750. [Google Scholar] [CrossRef]
  187. Wu, H.S.; Zhang, F.M. Wolf pack algorithm for unconstrained global optimization. Mathematical Problems in Engineering 2014, 2014, 465082. [Google Scholar] [CrossRef]
  188. Mittal, N.; Singh, U.; Sohi, B.S. Modified grey wolf optimizer for global engineering optimization. Appl. Comput. Intell. Soft Comput. 2016, 2016, 7950348. [Google Scholar] [CrossRef]
  189. Liu, C.; Yan, X.; Liu, C.; Wu, H. The wolf colony algorithm and its application. Chin. J. Electron. 2011, 20, 212–216. [Google Scholar]
  190. Jalali, S.M.J.; Khosravi, A.; Kebria, P.M.; Hedjam, R.; Nahavandi, S. Autonomous robot navigation system using the evolutionary multi-verse optimizer algorithm. In Proceedings of the 2019 IEEE International Conference on Systems, Man and Cybernetics (SMC), Bari, Italy, 6–9 October 2019; pp. 1221–1226. [Google Scholar]
  191. Jalali, S.M.J.; Hedjam, R.; Khosravi, A.; Heidari, A.A.; Mirjalili, S.; Nahavandi, S. Autonomous robot navigation using moth-flame-based neuroevolution. In Evolutionary Machine Learning Techniques; Springer: Berlin/Heidelberg, Germany, 2020; pp. 67–83. [Google Scholar]
  192. Chhillar, A.; Choudhary, A. Mobile Robot Path Planning Based Upon Updated Whale Optimization Algorithm. In Proceedings of the 2020 10th International Conference on Cloud Computing, Data Science & Engineering (Confluence), Noida, India, 29–31 January 2020; pp. 684–691. [Google Scholar]
  193. Wang, S.; Jia, H.; Abualigah, L.; Liu, Q.; Zheng, R. An improved hybrid aquila optimizer and harris hawks algorithm for solving industrial engineering optimization problems. Processes 2021, 9, 1551. [Google Scholar] [CrossRef]
  194. Mahajan, S.; Abualigah, L.; Pandit, A.K.; Altalhi, M. Hybrid Aquila optimizer with arithmetic optimization algorithm for global optimization tasks. Soft Comput. 2022, 26, 4863–4881. [Google Scholar] [CrossRef]
  195. Zhao, J.; Gao, Z.M. The heterogeneous Aquila optimization algorithm. Math. Biosci. Eng. MBE 2022, 19, 5867–5904. [Google Scholar] [CrossRef] [PubMed]
  196. Forestiero, A.; Papuzzo, G. Agents-based algorithm for a distributed information system in Internet of Things. IEEE Internet Things J. 2021, 8, 16548–16558. [Google Scholar] [CrossRef]
Figure 1. Schematic showing different path planning methods.
Figure 1. Schematic showing different path planning methods.
Electronics 11 02801 g001
Figure 2. Conventional operational flow chart of trajectory planning algorithm.
Figure 2. Conventional operational flow chart of trajectory planning algorithm.
Electronics 11 02801 g002
Figure 3. The simulation of CME-AO and CME-AAO exploration algorithms.
Figure 3. The simulation of CME-AO and CME-AAO exploration algorithms.
Electronics 11 02801 g003
Table 1. Various parameters for robotics.
Table 1. Various parameters for robotics.
PanelSensorSoftwareMap Testing
ROSbot 2.0 [42]-Ros Operating SystemLab-based
Pioneer 3-DX [43]CameraXilinx, GA-IP FPGALab based
MATLAB (ROS system) [44]ROS (SLAM)Garage map
Aria P3-DX [45]Saphira softwaresimple environment
Husarian ROSbot [46]LiDARROSLab
Table 2. Scholarly contributions.
Table 2. Scholarly contributions.
RefSensorsContribution
Moses et al. [94]Radar SensorThe authors presented the overall efficiency of radar and put forward the novel design of lightweight X-band radar sensor for UAVs. The Doppler effect caused the propulsion of the UAV, which provided safe and easy identification of the target and efficient maneuverability to avoid collisions. The authors noted that the proposed design is scalable and can be used for larger vehicles.
Hugler et al. [95]Radar SensorThe authors presented a detailed study on the advantages of radar with UAVs for detecting obstacles, such as their velocity and angular rates. They also provided the range tendency and the multi-target detection in the angular range of ± 60 in azimuth. They conducted experimental work.
Mohamed et al. [80]Radar SensorThe authors highlighted the predominant features involved in radar sensors for detecting obstacles. They concluded that radar sensors have the capability to withstand weather conditions, making them suitable for outdoor applications. They can perfectly determine the sizes and shapes of obstacles while detecting them; however, the exact dimensions cannot be retrieved due to the low output resolutions of radar sensors.
Asvadi et al. [96]Velodyne LiDARThe authors presented the work of Velodyne LiDAR. A static 2D map was constructed, which was continuously compared with a previously constructed map using GPS/IMU.
Azim et al. [97]Velodyne LiDARThe researchers studied the obstacle detection and representation using OctoMap. They formulated the entire area with the Velodyne LiDAR sensor using spatial clustering and GPU for position correction.
Table 3. Nature-inspired algorithms.
Table 3. Nature-inspired algorithms.
TechniqueSeminal Work
ANN [113,114]Depends on self-organizing maps.
ABC [115,116,117]The algorithm is used for optimization and imitates the bee colony pattern for the food search. Classified into three: (i) employed bees, (ii) onlooker bees, and (iii) scouts.
GA [118,119,120,121,122,123,124,125,126]Extension of evolutionary algorithms; they depend on operators, e.g., mutation, crossover, and selection operators.
SA [127]A probabilistic method employed for searching the global minima. It depends on the physical phenomena in solidifying fluids, such as metals.
GWO [21,128]Depends on the hierarchical distribution of wolves. A mathematical model is obtained on how wolves hunt and prey.
AO [28,129]Depends on mathematical operators, i.e addition, subtraction, multiplication, and division. Its popularity stems from its ease of use, with fewer parameters, making it straightforward to execute and adaptable to a wide range of applications.
WO [22,130,131]Inspired by the hunting behavior of whales. They have an advantage because of their hunting strategies.
Table 4. Path planning challenges.
Table 4. Path planning challenges.
Problem AreaImprovement Areas
Noise occurrence [168]Numerous studies have been conducted to limit and accommodate noise incidences in vehicle systems; however, this remains a difficulty. These (and other issues) significantly impede the real-time implementation of any algorithm.
Vision-based [169,170]The difficulty comes from identifying joint points in the same dimension. This leads to uncertainty in recognizing points, resulting in conflicting interpretations of images.
ANN [171,172]This approach has various advantages; however, it requires a large data set of the surrounding region for hidden layer tuning. The well-known backpropagation technique has its own drawbacks since it rapidly converges to local minima.
Table 5. Benefits and weaknesses of algorithms involved in autonomous vehicle path planning.
Table 5. Benefits and weaknesses of algorithms involved in autonomous vehicle path planning.
AlgorithmsBenefitsWeaknessImplementationTime Complexity
Fuzzy Logic(a) It is easy to tune fuzzy rules according to need [177](a) Membership functions are difficult to implement.Simulated world and real-time T 0 ( n 2 )
(b) Logic building is easy [178]
(c) Can easily integrate with bio-inspired algorithms [177]
Neural Network(a) Real-time implementation is easy compared to fuzzy(a) Neuron layer embedded in the network results in harder implementation [171]Real-time and simulation T 0 ( n 2 )
(b) Control logic imitation is easy(b) Layered structure increases the complexity [171]
(c) Backpropagation is beneficial [179]
(d) Dataset collection is difficult in real-time [171]
Genetic Algorithm(a) Faster convergence rate [180](a) Local minima problem exists in a complex environment [181]Simulated world T 0 ( n 2 )
(b) Easily integrable with other algorithms [180](b) System needs a lot of tuning [182]
(c) Easy implementation [183]
ABC(a) Fewer control parameters [117](a) Weak convergence rate [184]Simulated world T 0 ( n 2 )
(b) Less execution time is needed [183]
(c) Integrable with other algorithms [183]
Arithmetic Algorithm(a) Easy implementation [185](a) (Tad bit) less of a convergence rate [186]Simulated World T 0 ( n 2 )
GWO(a) Convergence rate is fast [187](a) A bit tricky in a complex environment [188]Simulated world T 0 ( n 2 )
(b) Tuning of the parameter is easy [187]
(c) Performs better when integrated with another algorithm  [189]
Moth flame(a) Performs effectively in a complex environment [190](a) Suffers from premature convergence [191]Simulated world and real-time T 0 ( n 2 )
WOA(a) Fast convergence rate [192](a) Not easily implementable in a dynamic environment [109]Simulated world and real-time T 0 ( n 2 )
Aquila Optimizer(a) Effective at producing good solutions in a complex environment [193](a) Requires tuning of a lot of variables [194]Simulated world and real-time T 0 ( n 2 )
(b) Convergence rate is faster initially(b) Becomes a tad bit slow at latter iterations [195].
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Mir, I.; Gul, F.; Mir, S.; Khan, M.A.; Saeed, N.; Abualigah, L.; Abuhaija, B.; Gandomi, A.H. A Survey of Trajectory Planning Techniques for Autonomous Systems. Electronics 2022, 11, 2801. https://doi.org/10.3390/electronics11182801

AMA Style

Mir I, Gul F, Mir S, Khan MA, Saeed N, Abualigah L, Abuhaija B, Gandomi AH. A Survey of Trajectory Planning Techniques for Autonomous Systems. Electronics. 2022; 11(18):2801. https://doi.org/10.3390/electronics11182801

Chicago/Turabian Style

Mir, Imran, Faiza Gul, Suleman Mir, Mansoor Ahmed Khan, Nasir Saeed, Laith Abualigah, Belal Abuhaija, and Amir H. Gandomi. 2022. "A Survey of Trajectory Planning Techniques for Autonomous Systems" Electronics 11, no. 18: 2801. https://doi.org/10.3390/electronics11182801

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