Next Article in Journal
Smart Thermostats for a Campus Microgrid: Demand Control and Improving Air Quality
Next Article in Special Issue
Fault-Tolerant Control for Reducing Harmonic Distortion of Dual Three-Phase Permanent Magnet Synchronous Motor
Previous Article in Journal
Numerical Investigation of the Sensitivity of the Acoustic Power Level to Changes in Selected Design Parameters of an Axial Fan
Previous Article in Special Issue
Data-Driven Fault Diagnosis for Automotive PEMFC Systems Based on the Steady-State Identification
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques

DRIVE Laboratory EA1859, University of Bourgogne Franche Comté, F58000 Nevers, France
*
Author to whom correspondence should be addressed.
Energies 2022, 15(4), 1358; https://doi.org/10.3390/en15041358
Submission received: 21 November 2021 / Revised: 3 February 2022 / Accepted: 9 February 2022 / Published: 14 February 2022
(This article belongs to the Special Issue Diagnosis and Fault Tolerant Control of Electrical Vehicle)

Abstract

:
Mobile robot path planning has passed through multiple phases of development and took up several challenges. Up to now and with the new technology in hands, it becomes less complicated to conduct path planning for mobile robots and avoid both static and dynamic obstacles, so that collision-free navigation is ensured. Thorough state of the art review analysis with critical scrutiny of both safe and optimal paths for autonomous vehicles is addressed in this study. Emphasis is given to several developed techniques based using sampling algorithms, node-based optimal algorithms, mathematic model-based algorithms, bio-inspired algorithms, which includes neural network algorithms, and then multi-fusion-based algorithms, which combine different methods to overcome the drawbacks of each. All of these approaches consider different conditions and they are used for multiple domains.

1. Introduction

Over the last three decades, the autonomous and electric vehicle, also known as automated vehicle [1], has been the topic of unprecedented excitement. It is seen as the future of motorized mobility, both in terms of ecology, by tightening emission standards, reducing CO2 and pollutant emissions and environmental impacts, and in terms of safety, including improved road safety [2], where main cause of accidents and crashes are due to human errors. This solution will be accompanied by intelligent assistance to warn the driver or decide and/or anticipate avoiding a collision with static or dynamic objects, vehicles, or pedestrians. Nevertheless, this assistance can have an impact on mobility when there are also non-autonomous vehicles in the same environment; this problem has two solutions, either to have an area only for this type of navigation or to develop a cooperative navigation with other road users. Research has been conducted on dynamic path planning and more based on how to increase the performance of these vehicles in such a difficult environment to avoid any strange and hazardous situation which the vehicle may be able to confront in real navigation. The main purpose of planning and navigation is to provide vehicles with a safe driving and collision-free path towards their destinations, accounting for vehicle dynamics, maneuvering capabilities in the presence of obstacles, and traffic rules and road boundaries.
A global reasoning of all possible paths should finally allow the finding of the best safe path according to different criteria, such as safety distance, travel time, cost, and comfort, while satisfying some dynamic constraints related to the environment. An intelligent planning system should be able to consider the nature, size, and speed of the vehicle or the robot [3]. In this study, we review different methods of path planning and path optimization for mobile robots and autonomous vehicles.
The remainder of the present work is organized as follows. Section 2 presents a taxonomy of autonomous vehicles and their evolution within the six levels of automation. Section 3 consists of five sub-sections which refer to the five categories of path planning, where a discussion of the existing methods in the literature for path planning for autonomous vehicles is performed, whilst Section 4 compares the advantages and drawbacks of these methods and reveals the best solution that gives the optimal path within the environment complexities. A categorization is thus proposed of the different existing approaches. Finally, some concluding remarks are addressed in Section 5.

2. Autonomous Vehicles Evolution

Nowadays, most vehicles are equipped with advanced driver-assistance systems (ADAS) functions, including ACC, ABS, ESP, LKA, etc., which reminds to level one and two of automation. Indeed, there exist six levels of automation according to SAE J3016 standard as can depicted in Figure 1, from 0 to 5, from a vehicle with only human control to a vehicle totally autonomous without human interaction, such as Google self-driving car Waymo.
  • Level 0 is a no automation vehicle where the human driver monitors all aspects of the dynamic driving tasks with a full-time performance and the vehicle is manually controlled with no driving mode;
  • Level 1 is a driver assistance system where the driver monitors the driving environment but there is only one automated driver assistance system for lateral control by acting on steering angle (example of lane keeping assist system which can help the driver to stay in his lane, if he drifts) or longitudinal control in which based on the management of vehicle speed and inter-vehicular spacing by performing on throttling/braking (example of adaptive cruise control can control speed, the driver has to steer);
  • The second level of automation is a partial automation which has an advanced driver assistance system, so that the vehicle control both steering and acceleration/deceleration. The system takes the execution of dynamic driving and the driver performs all remaining aspects of the dynamic driving task. The human driver can take control of the car at any time;
  • Level 3 is the beginning of the automated driving system that monitors driving environment. The level 3 is a conditional automation where the vehicle has an object and event detection and appropriate response (OEDR) to these objects and events. The human override is required;
  • The fourth is a high automation level, the vehicle performs all driving tasks under specific conditions but he human input as a driver is still required;
  • The last is full automation level where the vehicle can navigate and handle all different sorts of driving modes, different driving conditions, and roads autonomously without the need for human driver interaction. The vehicle performs in all driving tasks under all circumstances.
Today, in the vehicles market, we can only find vehicles with level 2 and level 3 of driving automation, because of the navigation environment and inter-vehicular communication in real roads which is not yet allowed. Therefore, it is important to study the impact of different levels of automation on the mobility of people, especially for full driving automation (level 6) which is still under development [4]. However, most intelligent systems acquire information from sensors. These are limited and some data cannot be accessed by the sensors. The solution is therefore based on the use of wireless communication to exchange information between vehicles and between infrastructures and vehicles, which remains the subject of several researches.
Research has been conducted on dynamic path planning and more based on how to increase the performance of these vehicles in such a difficult environment to avoid any strange situation the vehicle may be able to confront in real driving. The main objective of planning and navigation is to provide vehicles with safe and collision-free driving towards their final goal, taking into account vehicle dynamics, obstacle maneuvering capabilities, and traffic rules.

3. Path Planning and Navigation Technique for Autonomous Vehicles

Road accidents and time wasted in traffic jams and health problems caused by local air pollution are the most challenging and complicated issues in city life. To deal with these problems and security issues, autonomous driving (self-driving) is therefore a promising alternative. To develop this solution, path planning must come first after the perception layer, as its modules are responsible for generating a reference path for the vehicle which could avoid obstacles and satisfy vehicle dynamics constraints [5,6]. The main challenge for all the already conducted works is to improve performance through the use of the proposed models which present the dynamics of the vehicle in the nearest way to real dynamics. The trajectory planning is based on generating a set of possible paths starting from the initial position toward the final position; to do this operation we need first all the information about the surrounding environment that we can get from special sensors as lidar, RGB camera, radar, etc.
Knowing the position of each object existing in the environment, either local or global, the proposed method can be applied to find the desired trajectory that could be the only one or the optimal among others. Since the desired trajectory is found, the vehicle should track the planned path while avoiding 3D objects. The state-of-the-art planning offers different approaches. It can be broken down into the architecture that uses one single real-time algorithm to plan and track the trajectory, and the architecture that uses two separate algorithms where the first one is an offline planner and the second is a real-time tracker, and there are others using a divided trajectory planning and tracking but with real-time algorithms.
After all, as the implementation of some approaches for the task of path planning for autonomous vehicles was quite difficult due to many complexities, such as environmental disturbances, weather, noise and so on, the implementation of these methods using a mobile robot, which represents a vehicle well, shows the effectiveness of the proposed method. Then, we used simulators, such as ‘Carmaker’, in order to simulate the possible real-world disturbances to ensure the performance of the method. In this study, we have presented several works in which the authors deal with the trajectory planning of mobile robots that can also be used for the development of autonomous vehicles.
This section intends to discuss the different methods of path planning for autonomous vehicles. Planning takes into account path decision and optimization. Mobile robot navigation needs a pre-planned path to ensure a safe trajectory, so that path planning can be decomposed in five categories, as illustrated in Figure 2; we will discuss each method by categories in the next sub-sections.

3.1. Sampling-Based Algorithms

Sampling-based algorithms can be divided (Figure 3) into two parts, active and passive. Active algorithms have a processing procedure to achieve the best possible path to the objective. Rapidly exploring random tree (RRT) method is an active sampling-based algorithm proposed by LaValle. This approach is very used to solving path planning problems of different kinematic constraints and it has the ability to handle multi-DOF problems. The principle of RRT is to rapidly search the configuration space to generate the path that connects the start node and the goal node. Indoor space can be a tunnel or underground parking where the absence of the network and the performance of some sensors is poor, which can affect the input data. A study of an optimal path planning of a mobile robot in an unknown indoor space is presented in [7]. It implements a process by using deep learning “GoogLeNet” for obstacles classification, then applying RRT for robot path planning in order to ensure an intelligent path process while avoiding obstacles with a ray tracing technique. An algorithm grows a tree of feasible trajectories originating from the current vehicle position that attempts to reach a desired final goal position. It aims at using multi-directional rapidly exploring trees for path planning [8]. Besides, this method is implemented to deal with a degree of directional instability using the flexible multi-directional rapidly exploring trees method that built at each level a tree on demand. Then, based on the previous path exploration vertices, they use a fusion method of all trees to generate a local optimal path based on a complete and optimal path.
Moreover, there exist other RRT variants in literature trying to adapt and solve complex path planning problems with static and dynamic objects, and differential constraints as non-holonomic and kino dynamic constraints. RRT- Connect builds only two random trees then generates an optimal path. RRT* uses a predefined cost function to choose the optimal path that has a low cost and ensures the computational complexity. RRT*smart (Stretch) it is an extension of RRT* that accelerates the convergence rate by optimizing the path and sampling in a smarter way [9]. RRT* Connect unifies the RRT- connect and RRT* in order to ensure optimality [10].
BIT Conventional and MPC [11] proposes a path planning method with modified Conventional BIT* “Batch Informed Trees” based on informed RRT*, in order to accelerate the convergence rate and also to decrease operation time to reach the final goal with a collision free path. The authors integrate a stretch method that improves the path point’s connections. Then, they added an MPC method for trajectory tracking and motion control for obstacles avoidance and to ensure safety. The work in [12] explains the purpose of using a MPC for autonomous vehicles considering the nonlinearity of the vehicle dynamic model.
Artificial potential field APF approach is well used in this field [13] and it will be presented in following; the gradient of a potential field is constructed by virtual forces. The path can be achieved along the steepest gradient of the potential field. The artificial potential field is able to ensure a collision-free path, but it can fall into a local minimum problem. It needs whole workspace sampling information to escape from local minima. A membrane evolutionary artificial potential field is a combined method to find parameters to come up with a possible and safe path toward the target in static and dynamic environments [14]. In [15], the authors introduce a discrete artificial potential field that can be used with near real time of operation for practical applications in complex environments. For a discrete configuration, this approach uses the APF, then customizes it and adapts in order to achieve a fast and effective solver of complex problems.
The second type of sampling-based algorithms are passive algorithms, which only generate a route net from start to the goal, therefore a combination of search algorithms to pick up the best feasible path between all feasible paths existing in the net map. In this category, probabilistic road maps PRM approach is introduced. It is a technique that samples some points in the map, then connects these points to construct a graph that contains feasible routes with collision-free edges. To pick up the optimal path, it is necessary to use graph search algorithm. The authors in [16] try to optimize a path by eliminating unnecessary nodes and repositioning the nodes to form the best route toward the ending point. Another approach is called fast marching trees [17], which comes with a combination of both advantages of RRT and PRM seen before. 3D Voronoi works as a PRM which cannot generate an optimal path itself. In general, this method forms a 3D obstacle avoidance network based on pre-known knowledge of the environment. The Voronoi method permits robot to navigate at equidistant value with respect to its surrounding objects [18].
Figure 3. Sampling-based approaches with the main advantages and drawbacks.
Figure 3. Sampling-based approaches with the main advantages and drawbacks.
Energies 15 01358 g003

3.2. Node-Based Optimal Algorithms

Node-based optimal algorithms (Figure 4) based on certain graph decomposition is a method can find an optimal path, with a principle of exploring among a set of cells in the map, where information sensing and processing procedures are already executed. It can be divided into two groups: the first group is the grid search algorithms, the grid based or evidential occupancy grid method is widely used in the field of autonomous driving, especially in low-speed scenes as they are not suitable for high-speed driving, as it consists of mapping the environment to a set of cells, and each cell represents the presence of an obstacle at that position; if it contains information in the evidence form, such as the mass or the belief value, which is called the evidential occupancy grid. This approach needs an algorithm to generate a feasible path toward the final goal. In [19], the authors use two optimal search algorithms A* and D* to find the global optimal path that connects the initial position of each cell to the goal position (will be discussed in the next section). Researchers in [20] use the clothoïd tentacles method for generating a set of clothoïds tentacles as feasible trajectories on an egocentric occupancy grid around the vehicle in operation. The clothoïd tentacles are a geometrical shape which is able to model possible trajectories. They are also known by considering the vehicle’s current steering angle and making smooth variations in the vehicle’s main dynamic variables, such as the yaw rate, the side-slip angle, and the steering angle. In this work [21], a local trajectory planning is built based on the following of a desired reference trajectory defined on the map while avoiding collisions by using the perception information that represents the environment. The authors create and update the occupancy grid with sensors data, the generated tentacles will represent the feasible trajectories, and then the best tentacle is chosen. The main objective of this method is to integrate and manage uncertainties of the environment for trajectory planning for autonomous driving [22].
In [23], the authors present a trajectory planning approach using clothoid tentacles which are generated in an ego-centered grid representing feasible and realistic trajectories by the vehicle; then, the problem is formulated as a Markov decision process in order to choose the best one.
This paper [24] presents a way to organize all environmental information/sensor’s data by means of a map, which is the semantic map. It includes high-level features that model the human concepts: objects, shapes, places, and the relationships of all these. Additionally, a metric map is to add semantic information on top of the semantic map to retain all geometrical features the robot should be aware of in order to safely navigate within its surroundings. The purpose of this method [25] is to build a planning scheme using semantic maps in order to improve the goal reaching capabilities of the robot in a task-planning scenario. This method can integrate existing path planners into the topological graph planner that produces faster reaching of goals. Semantic mapping paradigms have been employed both in indoor and outdoor interpretations.
After discretizing the map into a graph, the second group, which is the graph search algorithms, came to complete the first type. Dijkstra is a special form of dynamic programming and A* is the heuristic search algorithms in artificial intelligence. These algorithms are widely used in robot operation system; they are both improved by finding the path with the least cost by reducing the number of searching grids through a heuristic estimation. In this work [26], the authors combine both Dijkstra and dynamic window approach (DWA) for the global and the local path planning algorithms in order to avoid obstacles from the initial position and reach the goal position in a smooth and shortest-planned path.
A* (A star) is known by its simple principle, easy implementation, high efficiency, it is very effective in a search path optimization algorithm, and it is faster than the Dijkstra algorithm [27]. A* is based on a heuristic function to estimate the closest point on the map and gives several path choices to pick up the optimized one; it assures a safe path planning of mobile robot in complex terrains [28,29]. Lifelong Planning A* (LPA*) algorithm is a repeating version of A* and it is characterized by the ability to handle dynamic threats. LPA* is a simple principle that is easier to understand and to analyze, and is easier to extend than A* algorithm and is also more efficient. As A* worked well for path planning for mobile robots, researchers in [30] developed a virtual sensor called D* algorithm, which is a real time sensor-based algorithm that deals with dynamic obstacles and forms a temporal map for the robots movement from the initial position to the final position. D* knows an unrealistic distance problem but it has a fast searching ability and deals with dynamic environments. Plus, an extension and a simplified version of D* algorithm is developed based on LPA*, where in each iteration of re-planning the goal changed; this approach is named D* -Lite [18].
Theta* and Lazy Theta* are proposed and compared to A* algorithm. Theta has the ability to obtain several system constrains in the 3D environment and find shorter and more realistic paths. This comparison is made to prove that Theta* reduces the searching and acts well compared to A*. Lazy Theta* is proposed to avoid unnecessary checks of unexpected neighbors in 3D environment. The process of Lazy Theta* may cause extra computational consumption; however, it can deal with dynamical threats and converge fast to the final goal.
Figure 4. Node-based optimal approaches with the main advantages and drawbacks.
Figure 4. Node-based optimal approaches with the main advantages and drawbacks.
Energies 15 01358 g004

3.3. Mathematic Model Based Algorithms

The third category of path planning is the mathematic model-based algorithms presented in Figure 5. This field can be split into two subcategories: linear algorithms and optimal control. In general, this category is based on geometrical approaches that model the environment and the system in order to build the kinematic and dynamic system. Then, a cost function is used to achieve an optimal solution.
The linear algorithms include flatness, which employs differential flatness to ensure control flatness along the reference path; it deals with control disturbance and its uncertainty. Mixed integer linear programming MILP and binary linear programming BLP, which is a special case of linear programming, is found in some works to have variables that have only 0 and 1 integer values. MILP combines both binary and integer logical constraints which offer a close representation of the environment, so as the system [31].
In robotics, the optimal control is considered as a path planning problem optimization by finding the control-oriented path based on differential equations. This work [32] shows a method that gives an optimal path selection based on discrete optimization, which has very great success in autonomous driving. This method contains three levels, which are the center line construction, path candidate generation, and then the path selection. Discrete optimization selects an optimal path from a generated finite set of path candidates, and at the same time determines appropriate vehicle acceleration and speed to reach the goal position. This approach is able to identify a safe and comfortable path for vehicles in operation, but this work deals only with one dynamic obstacle.
The second method in this area is called limit cycle [33,34]. It is a control architecture that generates robot trajectories, which are defined according to a set of differential equations where the stability is proven by Lyapunov function. This method generates a cylindrical box of each object existing in the environment, where the center of the cylinder is respectively the object position. The robot follows the given cycle in order to avoid obstacles with an optimal path in case of a feasible collision-free and the safety distance is respected. This approach is known by this optimality and it uses specific reactive rules which allows the robot to avoid deadlocks, local minima, and oscillations. Furthermore, two extensions of the limit cycle exist, called elliptic limit cycle and parallel elliptic limit cycle “PELC” [35,36], which are characterized by their elliptic boxes instead of cylindrical ones. Two methods were combined to predict the robot trajectory to avoid obstacles in [37]. The approach uses the ‘ELC’ elliptic limit cycle which is a mathematical method and neural network method called the “DBN” dynamic bayesian network which is a maneuvering recognition-based method for decision-making.
Figure 5. Mathematic model-based approaches with the main advantages and drawbacks.
Figure 5. Mathematic model-based approaches with the main advantages and drawbacks.
Energies 15 01358 g005

3.4. Bio-Inspired Algorithms

In the light of the inspired technique from biological behavior, we reach bio-inspired algorithms, in Figure 6. The principle of these methods is to search a near optimal path based on stochastic approaches. It is characterized by solving the “NP” problems, which are nonlinear problems with a large number of variables, and are known by the nonlinear objective functions with a high complexity to overcome the algorithms fails or falling into local minima.
This method includes both neural network and evolutionary algorithms, such as genetic algorithm “GA”, particle swarm optimization PSO, ant colony optimization “ACO”, shuffled frog leaping algorithm “SFLA”, and so on.

3.4.1. Evolutionary Algorithms

In evolutionary algorithms, path planning of mobile robots based on an improved genetic algorithm performs well in overcoming the problem of falling into local optimal solutions easily and the low search efficiency in path planning, and presents an improved genetic algorithm. In [38], one presents a collision-free path for mobile robot navigation based on improved genetic algorithm; they use a grid method to describe the operating environment of the robot, then two fitness functions for collision avoidance and for the shortest path from the start point to the final point. These functions have an influence on the convergence and the stability of the algorithm.
PSO is inspired by the living mode of movement of a group of birds. In an area where particles are positioned, at each iteration these particles move according to their current velocity and their best solution is obtained in their neighborhood in order to ensure a convergence of the particles towards a global minimum. Three algorithms are combined [39] to build a hierarchical approach to find the global path planning of a mobile robot evolved in such cluttered environments, starting by a triangular decomposition, secondly Dijkstra’s algorithm, and then a proposed particle swarm optimization called constrained multi-objective particle swarm optimization (CMOPSO) with an accelerated update methodology based on Pareto dominance principle. A developed, improved PSO based on using a continuous uniform random distribution [40] to not lose the randomness of particles and avoid its fall in local minima, and evaluation function, cubic spline interpolation for a smooth path planning, so that the accuracy and dynamic characteristics of the path are improved. Another approach in this category, called colony optimization ‘ACO’, is presented in [41]. It is a swarm intelligent algorithm recently developed and widely applied to deal with mobile robot’s navigation in different domain and is known by its advantage as it can be combined to many other approaches seen above. The two works [42,43] introduce an improved ant colony algorithm for mobile robot path planning that uses a simulating probability in order to make the best selection of the next grid where the probability depends on the number of the obstacles around the grid. Then, global heuristic information is employed based on the principle of unlimited heuristic search and an expanded vision field to find the shortest path. Shuffled frog leaping algorithm ‘SFLA’ is a proposed method based on the behavior of frogs, that make it unique in engineering field and optimization fields as it is easy to implement, improves convergence speed, and has better search capacity with the existence of uncertainty. A multi-objective based on the shuffled frog leaping algorithm [44] is introduced in order to ensure the path safety, path length, and the path smoothness. Memetic algorithms are also called hybrid GA. MA has the same principle and the exploring process as GA, but is more efficient in path smoothness with low computational complexity; the only disadvantage is the high time complexity [45].
Cuckoo optimization algorithm it is a new suggested method for solving nonlinear problems, such as a mobile robot path planning problem in a dynamic environment. The advantages of this approach is that it is able to find a short, safe, smooth, and collision-free path in different environmental conditions, including dynamic and static.
Figure 6. Evolutionary algorithms with the main advantages and drawbacks.
Figure 6. Evolutionary algorithms with the main advantages and drawbacks.
Energies 15 01358 g006

3.4.2. Neural Network Algorithms

Neural network algorithms (NNA), in Figure 7, are widely used in autonomous mobile robots, not only in motion planning but also in robot perception, guidance, self-driving, obstacle avoidance, and so forth. In navigation, deep learning, convolution neural network, artificial neural network, and decision network [46] are employed to avoid obstacles and decision making in real time operations in either static environments or dynamic environments. Since sensor data are learned, the architecture of the neural network can be organized into two parts: the perception system and the decision-making system, which contains lane change left and right, lane keep, and maintains velocity in order to build a safe path for the mobile robot. Another method is the fuzzy method: fuzzy optimized decision function [47] uses fuzzy decision function for choosing the optimal path planning for the robot in two-dimensional spaces in complex environments, including indoor environments. The fuzzy decision mechanism is built to model uncertain systems and it is used to reach the goal of safe navigation, in the same time, to ensure path optimization and time optimization. The noteworthy advantages are low deviation percentage and a better performance than genetic algorithm. In this work, the authors only consider static obstacles; future works will deal with dynamic goals and moving obstacles. Furthermore, fuzzy logic is a hybrid method that can be combined to several other algorithms, such as NN, GA, PA, ACO, and so forth. An adaptive neuro-fuzzy inference system (ANFIS) [48] is developed to resolve the path tracking issue where it shows an improvement in tracking job, high precision, and better noise resistance than the fuzzy-only system. This study [49] introduces deep reinforcement learning technology for an effective end-to-end mobile robot path planning application. The considered method is able to determine an optimal path toward the goal point while avoiding obstacles using the original visual perception based on the RGB image perception. This approach includes three stages: first, they designed a deep Q-network (DQN) to approximate the robot state action value function. Second, they trained the DQN to determine the Q value, which is the robot’s actions: it can be turn right, turn left, or toward. The DQN takes only the RGB image as input. Then, an action selection strategy is used to pick up the current optimal mobile robot action.
To ensure local navigation tasks in un-known environments while avoiding static obstacles, reinforcement learning (RL) is presented in [50]. They used a true online sarsa informed biased softmax regression learning process (TOSL_iBSR) that includes a cost function to ensure fast convergence. In their experiments, they also implemented two other learning processes called Q-learning softmax regression (Q-SR) and true online state action reward state action Q biased softmax regression (TOSL–QBIASSR), to compare the computational cost, to show that TOSL-iBASSR takes the first most effective learning process with less number steps to accomplish the task, then Q-SR, and at last it comes TOSL-QBIASSR which demands more learning steps to complete the given task. The future work will deal with dynamic obstacles. An improved path planning algorithm based on Q-Learning is proposed in [51]. Deep reinforcement learning (DRL) for autonomous self-learning robot navigation in unknown and indoor environments without using a map or planner is designed [52]. The data used in this work is a fusion of recovered 2D laser scanner data, RGB-D camera data, and the orientation of the robot to the goal. The NNA are usually combined with other path planning categories to build hybrid control architecture and to recover both advantages. Concerning the training on a neural network, authors in [53] presented a great work on DRL, where they provided a very different paradigm for deep reinforcement learning. They introduced asynchronous variants of four standard RL algorithms, then showed that parallel actor-learners have a great impact on stabilizing the training, which allows the four methods to successfully train neural controllers.
Figure 7. Neural network algorithms with the main advantages and drawbacks.
Figure 7. Neural network algorithms with the main advantages and drawbacks.
Energies 15 01358 g007

3.5. Multi-Fusion-Based Algorithms

Since fusion-based become the solution to improve 3D path planning performance, multi-fusion-based algorithms, Figure 8, are introduced. In this kind of study, a single approach is not enough to provide an optimal path. In addition, in the presence of unknown environments and the existence of either static or dynamic obstacles, the robot should deal with such a situation and make a decision. Thus, trying to combine different approaches was a feasible solution to come out with a fast searching and optimal algorithm. Multi-fusion algorithms can be divided in two categories: embedded multi-fusion algorithms and ranked multi-fusion algorithms. The first one combines two algorithms or more and gathers the advantages of each, the algorithms work simultaneously to improve a high performance, whilst the second one forms a hierarchical structure, where each algorithm works separately [18,37].
The combined method of Dijkstra algorithm and dynamic window algorithm ‘DWA*’ method was used for the purpose of gathering the global path planning algorithm and local path planning algorithm. The validity and feasibility of the combined algorithm are approved by simulation results. Authors used depth information via SLAM algorithm to create a map of an unknown environment. This approach ensures a fast planning, safe and reliable, and good real-time performance [54]. DWA* combines the sampled multiple sets of speed with the motion constraints of speed and acceleration, then evaluates the simulated multiple sets of trajectories through an evaluation function, and selects the optimal speed corresponding to the trajectory as the drive of the car.
The combined method based on improved artificial potential filed and ant colony optimization is a great example to show that it is possible to avoid shortcomings. In this work [55], the authors proposed an algorithm that can provide an initial path obtained by an improved IAPF to be the inspired factors of ACO for avoiding its premature convergence and local optimum. Another novel approach based on a combination is presented in [56]. Called fuzzy ant colony optimization (FACO), it is built to find the shortest path planning while avoiding obstacles in complex environments. The obstacles are detected using an ultrasonic transducer. Then, fuzzy control is used to overcome the fact that ACO can easily fall into local minima and it ensures a safe trajectory for the mobile robot toward the final goal. This combination of ant colony algorithm and improved potential field is also introduced in [57] in order to avoid obstacles and make autonomous vehicles drive more safely.
The aim of [58] is to propose a study for decision making for autonomous driving, ensuring in the main time that there is safe navigation under uncertainties, especially in emergency situations. Its purpose is to develop the necessary systems for autonomous driving to be able to assess the risk in the surrounding environment, take appropriate decisions in nominal driving situations, and execution followed by verification of the coherence of the executed maneuvers in case of an unexpected behavior or an undetected obstacle. Their study is based on a proposed probabilistic multi-controller architecture P-MCA, which contains navigation strategy assumptions, including a hierarchical action selection for target reaching obstacles avoidance using elliptic limit cycle; then, they used P-MCA for navigation, which has perception and localization module, route planning, probabilistic decision making module, and its safety assessment and verification criteria, motion planning, prediction, and evasive strategy module used in case of a detected anomaly, control law module, and the lane keeping assist, adaptive cruise control, and the automatic lane changing. Additionally, they proposed a safety management strategy connected to the decision-making strategy, which has two levels: the first one is for the risk assessment strategy, which takes in charge the extended time-to-collision ETTC. The second one is the safety verification mechanism on inter-vehicular distance prediction that identify static/dynamic predicted inter-distance profile.
Figure 8. Multi-Fusion based algorithms with the main advantages and drawbacks.
Figure 8. Multi-Fusion based algorithms with the main advantages and drawbacks.
Energies 15 01358 g008

4. Comparison

Recently, the field of mobile robots was widely developed in several applications, such as care systems, military systems, mining, agriculture, industry, and many more, where the main reason is to prevent people from facing dangerous situations and improve the operation’s success rate and safety.
However, we cannot deny that each category is characterized by its advantages, and each single method was used several times by researchers in order to achieve their objectives, which have already proved to be successful. This review first classifies all the work carried out into five categories which are: sampling algorithms, node optimal algorithms, mathematic model-based algorithm, bio-inspired algorithms including neural network algorithms, and then multi-fusion based algorithms. Then, the elements of each category were listed and discussed; we summarize all the advantages and weaknesses of all elements in each category and analyze each subcategory in detail, as illustrated in Table 1. As a result, we get the following properties: sampling algorithms are on-line and can handle static and not all dynamic environment with a high time efficiency; additionally, sampling-based can be further classified as active algorithms which can find the optimal path by their own, and passive algorithms cannot. Node-based optimal algorithms are grid-based exploring algorithms which operate in real time in a static environment and remain weak in a dynamic environment, as the results of this algorithm rely much on the preconstructed graph, and it needs to be combined with other methods to achieve global optimality. Mathematical model algorithms can only operate off-line in both of static and dynamic environment with a time complexity which depends on the polynomial equation, this kind of method aims to describe the whole workspace in a mathematical form which allows to easily represent dynamic and kinematic constraints, as well as giving an overall consideration to safety, reliability, and efficiency. Bio-inspired algorithms are also off-line operations in static and only a part of dynamic environment with a high time complexity, this category is characterized by importing heuristic idea and can deal with NP-hard problems. Then, multi-fusion algorithms are designed to work real-time and depend on the combined algorithms to deal with static or dynamic environments, or both; these kinds of algorithms have the ability to achieve several objectives simultaneously, especially to achieve global optimal and cost minimum.
Compared to all categories where each has its exploring process to build an optimal path in different environments with such a situation that the vehicle can be able to drive safely. The one implementation of one approach is still limited in terms of advantages, so that use of only one technique is not enough to deal with vehicle self-navigation and path planning problems, or find the only ‘optimal path’ when every vehicle in such an environment has its own characteristics and challenges. The best solution can be achieved with a fusion method that combines two or more approaches to come out with an efficient strategy that gathers self-navigation, obstacle avoidance, and especially to solve mobile robot navigation problems and overcome the inconvenience of each category discussed above.

5. Conclusions

In this paper, we presented all the most used methods throughout the literature in path planning for autonomous vehicles in navigation tasks. The trajectory planning is not only a path generation from an initial point towards the final point, but also it should ensure optimality and smoothness of the chosen path in different environments, either local or global. Moving the vehicle from point A to B requires techniques of perception, state estimation, trajectory planning, and motion control. Although many autonomous navigation systems have been proposed, they generally follow a classic hierarchical planning paradigm, as has been shown above.
A comparative study with critical regard of the existing methods in terms of their operating principles pros and cons were highlighted.
In addition, even though many methods have been exposed, some avenues remain open and several perspectives are considered in order to improve the proposed approaches. In the future, we will focus on the coupling of multi-fusion path planning and environment modeling methods, as this can become the best key direction for 3D path planning in different complex situations, and it is also recommended to include control uncertainty for added security.
The key technologies of obstacle avoidance for self-driving include decision making, path planning, and path tracking. In future work, we will focus on decision-making and path tracking or motion control.

Author Contributions

Conceptualization, S.A. and E.-H.A.; Formal analysis, S.A. and E.-H.A.; Investigation, S.A. and E.-H.A.; Methodology, S.A., E.-H.A., A.C. and A.K.; Supervision, E.-H.A.; Writing—original draft, S.A. and E.-H.A.; Writing—review & editing, S.A., E.-H.A., A.C. and A.K. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded and supported by RÉGION BOURGOGNE FRANCHE-COMTÉ, through the “Itinéraire Chercheur Entrepreneur” grant number 20204-20607—https://www.bourgognefranchecomte.fr (accessed on 3 February 2022).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The author declares there is no conflict of interest.

Acronyms

ADASAdvanced Driver-Assistance Systems.
ACCAdaptive Cruise Control
ABSAnti-lock Braking System
ESPElectronic Stability Program
LKALane Keeping Assist
OEDRObject and Event Detection and Appropriate Response
DOFDegree Of Freedom
RRTRapidly Exploring Random Tree
BITBatch Informed Trees
MPCModel Predictive Control
APFArtificial Potential Field
PRMProbabilistic Road Maps
FMTFast Marching Trees
DWADynamic Window Approach.
LPA*Lifelong Planning
MILPMixed Integer Linear Programming
BLPBinary Linear Programming
PELCParallel Elliptic Limit-Cycle
ELCElliptic Limit-Cycle
DBNDynamic Bayesian Network
GAGenetic Algorithm
PSOParticle Swarm Optimization
ACOAnt Colony Optimization
SFLAShuffled Frog Leaping Algorithm
CMOPSOConstrained Multi-Objective Particle Swarm Optimization
MAMemetic Algorithms
ANNArtificial Neural Network.
NNANeural Network Algorithms
RLReinforcement Learning
DLDeep Learning.
DRLDeep Reinforcement Learning
DQNDeep Q-Network
CNNConvolutional Neural Network
BNNBayesian Neural Network
ANFISAdaptive Neuro-Fuzzy Interface System
SLAMSimultaneous Localization And Mapping
FACOFuzzy Ant Colony Optimization
ETTC Extended Time-To-Collision
FDF Fuzzy Decision Function

References

  1. Latrech, C.; Chaibet, A.; Boukhnifer, M.; Glaser, S. Integrated Longitudinal and Lateral Networked Control System Design for Vehicle Platooning. Sensors 2018, 18, 3085. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  2. Boukhari, M.R.; Chaibet, A.; Boukhnifer, M.; Glaser, S. Proprioceptive Sensors’ Fault Tolerant Control Strategy for an Autonomous Vehicle. Sensors 2018, 18, 1893. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  3. Hamieh, A. Planification Automatique de Chemins à L’Intérieur de Bâtiments Basée sur un Modèle BIM. Ph.D. Thesis, Université de Valenciennes et du Hainaut-Cambresis, Valenciennes, France, 2018. [Google Scholar]
  4. Hamadneh, J.; Esztergár-Kiss, D. The Influence of Introducing Autonomous Vehicles on Conventional Transport Modes and Travel Time. Energies 2021, 14, 4163. [Google Scholar] [CrossRef]
  5. Wang, P.; Gao, S.; Li, L.; Sun, B.; Cheng, S. Obstacle Avoidance Path Planning Design for Autonomous Driving Vehicles Based on an Improved Artificial Potential Field Algorithm. Energies 2019, 12, 2342. [Google Scholar] [CrossRef] [Green Version]
  6. Prochowski, L.; Ziubiński, M.; Szwajkowski, P.; Gidlewski, M.; Pusty, T.; Stańczyk, T.L. Impact of Control System Model Parameters on the Obstacle Avoidance by an Autonomous Car-Trailer Unit: Research Results. Energies 2021, 14, 2958. [Google Scholar] [CrossRef]
  7. Zhang, L.; Zhang, Y.; Li, Y. Path planning for indoor mobile robot based on deep learning. Optik 2020, 219, 165096. [Google Scholar]
  8. Qian, K.; Liu, Y.; Tian, L.; Bao, J. Robot path planning optimization method based on heuristic multi-directional rapidly-exploring tree. Comput. Electr. Eng. 2020, 85, 106688. [Google Scholar] [CrossRef]
  9. Islam, F.; Nasir, J.; Malik, U.; Ayaz, Y.; Hasan, O. Rrt∗-smart: Rapid convergence implementation of rrt∗ towards optimal solution. In Proceedings of the 2012 IEEE International Conference on Mechatronics and Automation, Chengdu, China, 5–8 August 2012; pp. 1651–1656. [Google Scholar]
  10. Klemm, S.; Oberländer, J.; Hermann, A.; Roennau, A.; Schamm, T.; Zollner, J.M.; Dillmann, R. RRT∗-Connect: Faster, asymptotically optimal motion planning. In Proceedings of the IEEE International Conference on Robotics and Biomimetics (ROBIO), Zhuhai, China, 6–9 December 2015; pp. 1670–1677. [Google Scholar]
  11. Xu, P.; Wang, N.; Dai, S.-L.; Zuo, L. Motion Planning for Mobile Robot with Modified BIT* and MPC. Appl. Sci. 2021, 11, 426. [Google Scholar] [CrossRef]
  12. Sun, C.; Zhang, X.; Xi, L.; Tian, Y. Design of a Path-Tracking Steering Controller for Autonomous Vehicles. Energies 2018, 11, 1451. [Google Scholar] [CrossRef] [Green Version]
  13. Wang, S.; Zhang, J.; Liu, Z. A Research on Overtaking Lane Planning for Intelligent Vehicles Based on Improved Artificial Potential Field Method. Automob. Technol. 2018, 3, 5–9. [Google Scholar]
  14. Orozco-Rosas, U.; Montiel, O.; Sepúlveda, R. Mobile robot path planning using membrane evolutionary artificial potential field. Appl. Soft Comput. 2019, 77, 236–251. [Google Scholar] [CrossRef]
  15. Lazarowska, A. Discrete Artificial Potential Field Approach to Mobile Robot Path Planning. IFAC-PapersOnLine 2019, 52, 277–282. [Google Scholar] [CrossRef]
  16. Lv, J.; Ma, J.; Li, X. Indoor Robot Path Planning Based on an Improved Probabilistic Road Map Method. In Proceedings of the 8th International Conference on Networks, Communication and Computing, Luoyang, China, 13–15 December 2019; pp. 244–247. [Google Scholar] [CrossRef]
  17. Janson, L.; Schmerling, E.; Clark, A.; Pavone, M. Fast Marching Tree: A Fast Marching Sampling-Based Method for Optimal Motion Planning in Many Dimensions. Int. J. Rob. Res. 2015, 34, 883–921. [Google Scholar] [CrossRef]
  18. Yang, L.; Qi, J.; Song, D.; Xiao, J.; Han, J.; Xia, Y. Survey of Robot 3D Path Planning Algorithms. J. Control. Sci. Eng. 2016, 2016, 7426913. [Google Scholar] [CrossRef] [Green Version]
  19. Xu, W.; Pan, J.; Wei, J.; Dolan, J.M. Motion planning under uncertainty for on-road autonomous driving. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 2507–2512. [Google Scholar] [CrossRef] [Green Version]
  20. Mouhagir, H.; Cherfaoui, V.; Talj, R.; Aioun, F.; Guillemard, F. Using evidential occupancy grid for vehicle trajectory planning under uncertainty with tentacles. In Proceedings of the 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), Yokohama, Japan, 16–19 October 2017; pp. 1–7. [Google Scholar] [CrossRef] [Green Version]
  21. Mouhagir, H.; Cherfaoui, V.; Talj, R.; Aioun, F.; Guillemard, F. Trajectory Planning for Autonomous Vehicle in Uncertain Environment Using Evidential Grid. IFAC-PapersOnLine 2017, 50, 12545–12550. [Google Scholar] [CrossRef]
  22. Alia, C.; Tagne, G.; Talj, R.; Charara, A. Local Trajectory Planning and Tracking of Autonomous Vehicles, Using Clothoid Tentacles Method. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Korea, 28 June–1 July 2015; pp. 674–679. [Google Scholar] [CrossRef]
  23. Mouhagir, H.; Talj, R.; Cherfaoui, V.; Guillemard, F.; Aioun, F. A Markov Decision Process-Based Approach for Trajectory Planning with Clothoid Tentacles. In Proceedings of the IEEE Intelligent Vehicles Symposium (IV), Gotenburg, Sweden, 19–22 June 2016; pp. 1254–1259. [Google Scholar] [CrossRef] [Green Version]
  24. Kostavelis, I.; Gasteratos, A. Semantic Mapping for Mobile Robotics Tasks: A Survey. Robot. Auton. Syst. 2015, 66, 86–103. [Google Scholar] [CrossRef]
  25. Ravankar, A.A.; Abhijeet, R.; Takanori, E.; Yukinori, K. Path Planning for Mobile Robots based on Semantic Mapping. Proc. JSME Annu. Conf. Robot. Mechatron. 2020, 2020, 1P1–D16. [Google Scholar] [CrossRef]
  26. Liu, L.; Lin, J.; Yao, J.; He, D.; Zheng, J.; Huang, J.; Shi, P. Path Planning for Smart Car Based on Dijkstra Algorithm and Dynamic Window Approach. Wirel. Commun. Mob. Comput. 2021, 2021, 8881684. [Google Scholar] [CrossRef]
  27. Cui, Z. Research on Path Planning of Mobile Robot Based on A* Algorithm. Int. J. Eng. Res. 2019, 8, IJERTV8IS110186. [Google Scholar] [CrossRef]
  28. Zhang, H.-M.; Li, M.-L.; Le, Y. Safe Path Planning of Mobile Robot Based on Improved A* Algorithm in Complex Terrains. Algorithms 2018, 11, 44. [Google Scholar] [CrossRef] [Green Version]
  29. Das, P.K.; Romesh, L.; Amit, K. Path Planning of Mobile Robot in Unknown Environment. Int. J. Comput. Commun. Technol. 2010, 1, 122–127. [Google Scholar] [CrossRef]
  30. Koenig, S.; Likhachev, M. Improved Fast Replanning for Robot Navigation in Unknown Terrain. In Proceedings of the IEEE International Conference on Robotics and Automation, Washington, DC, USA, 11–15 May 2002. [Google Scholar] [CrossRef] [Green Version]
  31. Ioan, D.; Ionela, P.; Sorin, O.; Florin, S.; Silviu-Iulian, N. Mixed-integer programming in motion planning. Annu. Rev. Control. 2021, 51, 65–87. [Google Scholar] [CrossRef]
  32. Hu, X.; Chen, L.; Tang, B.; Cao, D.; He, H. Dynamic Path Planning for Autonomous Driving on Various Roads with Avoidance of Static and Moving Obstacles. Mech. Syst. Signal Processing 2018, 100, 482–500. [Google Scholar] [CrossRef]
  33. Adouane, L. Orbital Obstacle Avoidance Algorithm for Reliable and On-Line Mobile Robot Navigation. In Proceedings of the 9th Conference on Autonomous Robot Systems and Competitions, Castelo Branco, Portugal, 7 May 2009. [Google Scholar]
  34. Wang, C.; Xia, W.; Xie, G. Limit-Cycle-Based Design of Formation Control for Mobile Agents. IEEE Trans. Autom. Control. 2019, 65, 3530–3543. [Google Scholar] [CrossRef]
  35. Adouane, L. Reactive versus Cognitive Vehicle Navigation Based on Optimal Local and Global PELC∗. Robot. Auton. Syst. 2017, 88, 51–70. [Google Scholar] [CrossRef]
  36. Lounis, A. Toward Fully Autonomous Vehicle Navigation: From Behavioral to Hybrid Multi-Controller Architectures. In Proceedings of the 11th International Workshop on Robot Motion and Control (RoMoCo), Wasowo Palace, Poland, 3–5 July 2017; pp. 85–98. [Google Scholar] [CrossRef] [Green Version]
  37. Iberraken, D.; Lounis, A.; Dieumet, D. Multi-Controller Architecture for Reliable Autonomous Vehicle Navigation: Combination of Model-Driven and Data-Driven Formalization. In Proceedings of the IEEE Intelligent Vehicles Symposium (IV), Paris, France, 9–12 June 2019; pp. 245–251. [Google Scholar] [CrossRef]
  38. Li, Y.; Huang, Z.; Xie, Y. Path planning of mobile robot based on improved genetic algorithm. In Proceedings of the 3rd International Conference on Electron Device and Mechanical Engineering (ICEDME), Suzhou, China, 1–3 May 2020; pp. 691–695. [Google Scholar] [CrossRef]
  39. Mac, T.-T.; Cosmin, C.; Duc, T.-T.; Robin, D.-K. A Hierarchical Global Path Planning Approach for Mobile Robots Based on Multi-Objective Particle Swarm Optimization. Appl. Soft Comput. 2017, 59, 68–76. [Google Scholar] [CrossRef]
  40. Li, X.; Wu, D.; He, J.; Bashir, M.; Ma, L. An Improved Method of Particle Swarm Optimization for Path Planning of Mobile Robot. J. Control. Sci. Eng. 2020, 2020, 3857894. [Google Scholar] [CrossRef]
  41. Patle, B.K.; Ganesh, B.-L.; Anish, P.; Parhi, D.R.K.; Jagadeesh, A. A Review: On Path Planning Strategies for Navigation of Mobile Robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
  42. Xiong, C.; Chen, D.; Lu, D.; Zeng, Z.; Lian, L. Path planning of multiple autonomous marine vehicles for adaptive sampling using Voronoi-based ant colony optimization. Robot. Auton. Syst. 2019, 115, 90–103. [Google Scholar] [CrossRef]
  43. Akka, K.; Farid, K. Mobile Robot Path Planning Using an Improved Ant Colony Optimization. Int. J. Adv. Robot. Syst. 2018, 15, 172988141877467. [Google Scholar] [CrossRef] [Green Version]
  44. Hidalgo-Paniagua, A.; Miguel, A.; Vega-Rodríguez, J.-F.; et Nieves, P. MOSFLA-MRPP: Multi-Objective Shuffled Frog-Leaping Algorithm applied to Mobile Robot Path Planning. Eng. Appl. Artif. Intell. 2015, 44, 123–136. [Google Scholar] [CrossRef]
  45. Zhu, Z.; Wang, F.; He, S.; Sun, Y. Global path planning of mobile robots using a memetic algorithm. Int. J. Syst. Sci. 2015, 46, 1982–1993. [Google Scholar] [CrossRef]
  46. Iberraken, D.; Adouane, L.; Dieumet, D. Reliable Risk Management for Autonomous Vehicles Based on Sequential Bayesian Decision Networks and Dynamic Inter-Vehicular Assessment. In Proceedings of the 2019 IEEE Intelligent Vehicles Symposium (IV), Paris, France, 9–12 June 2019; pp. 2344–2351. [Google Scholar] [CrossRef]
  47. Patle, B.-K.; Alok Jha, A.-P.; Gudadhe, N.; Kashyap, S.K. The Optimized Path for A Mobile Robot Using Fuzzy Decision Function. Mater. Today Proc. 2019, 18, 3575–3581. [Google Scholar] [CrossRef]
  48. Masoud, I.; Mansouri, M.; Shoorehdeli, M.A. Tracking Control of Mobile Robot Using ANFIS. In Proceedings of the IEEE International Conference on Mechatronics and Automation, Beijing, China, 7–10 August 2011; pp. 422–427. [Google Scholar] [CrossRef]
  49. Xin, J.; Zhao, H.; Liu, D.; Li, M. Application of Deep Reinforcement Learning in Mobile Robot Path Planning. In Proceedings of the Chinese Automation Congress (CAC), Jinan, China, 20–22 October 2017; pp. 7112–7116. [Google Scholar] [CrossRef]
  50. Khan, M.-U. Mobile Robot Navigation Using Reinforcement Learning in Unknown Environments. Balk. J. Electr. Comput. Eng. 2019, 7, 235–244. [Google Scholar] [CrossRef]
  51. Zhang, F.; Wang, C.; Cheng, C.; Yang, D.; Pan, G. Reinforcement Learning Path Planning Method with Error Estimation. Energies 2022, 15, 247. [Google Scholar] [CrossRef]
  52. Surmann, H.; Jestel, C.; Marchel, R.; Musberg, F.; Elhadj, H.; Ardani, M. Deep Reinforcement Learning for Real Autonomous Mobile Robot Navigation in Indoor Environments. arXiv 2020, arXiv:2005.13857. [Google Scholar]
  53. Kiran, B.; Sobh, I.; Talpaert, V.; Mannion, P.; Sallab, A.; Yogamani, S.; Perez, P. Deep Reinforcement Learning for Autonomous Driving: A Survey. IEEE Trans. Intell. Transp. Syst. 2021, 1–18. [Google Scholar] [CrossRef]
  54. Chen, G.; Jie, L. Mobile Robot Path Planning Using Ant Colony Algorithm and Improved Potential Field Method. Comput. Intell. Neurosci. 2019, 2019, 1932812. [Google Scholar] [CrossRef] [Green Version]
  55. Yen, C.-T.; Cheng, M.-F. A Study of Fuzzy Control with Ant Colony Algorithm Used in Mobile Robot for Shortest Path Planning and Obstacle Avoidance. Microsyst. Technol. 2018, 24, 125–135. [Google Scholar] [CrossRef]
  56. Iberraken, D. Safe Trajectories and Sequential Bayesian Decision-Making Architecture for Reliable Autonomous Vehicle Navigation. Ph.D. Thesis, Clermont Auvergne University, Clermont-Ferrand, France, 2020. [Google Scholar]
  57. Yuan, C.; Wei, Y.; Shen, J.; Chen, L.; He, Y.; Weng, S.; Wang, T. Research on Path Planning Based on New Fusion Algorithm for Autonomous Vehicle. Int. J. Adv. Robot. Syst. 2020, 17, 172988142091123. [Google Scholar] [CrossRef]
  58. Mnih, V.; Badia, A.P.; Mirza, M.; Graves, A.; Lillicrap, T.; Harley, T.; Kavukcuoglu, K. Asynchronous methods for deep reinforcement learning. In Proceedings of the 33rd International Conference on Machine Learning, New York, NY, USA, 19 June–24 June 2016; pp. 1928–1937. [Google Scholar]
Figure 1. The six levels of driving automation [SAE J3016TM LEVELS OF DRIVING AUTOMATIONTM. Copyright © 2021 SAE International].
Figure 1. The six levels of driving automation [SAE J3016TM LEVELS OF DRIVING AUTOMATIONTM. Copyright © 2021 SAE International].
Energies 15 01358 g001
Figure 2. Scheme of path planning methods classified by five categories.
Figure 2. Scheme of path planning methods classified by five categories.
Energies 15 01358 g002
Table 1. Analysis of path planning algorithms.
Table 1. Analysis of path planning algorithms.
CategoryMethodAdvantagesDrawbacks
Sampling-basedRRT, RRT*, RRT* SmartHandle multi-DOF problems,
low time complexity,
fast searching ability
Static threat, single path,
non-optimal.
BIT Conventional & MPCAccelerate the convergence rate,
short operation time,
Dynamic threat
Need parameters adjacency.
PRMDeals with complex environments,
re-planning situations
Static threat, expensive collision check, non-optimal. high execution time.
3D VoronoiEasy to implement, decreases the
dimension of the problem to one
Cannot generate an optimal path itself, Incomplete representation, Non-convergence
APFFast convergence, fast execution time,
ensure a collision-free path.
Falls into local minima.
Node based optimalDijkstraEasy to implement,
various environments
Heavy time burden, large calculation cost, static threats.
A*Faster than Dijkstra,
high efficiency
Heavy time burden, large calculation cost, static threats
D*
D*-Lite
Dynamic threat,
fast searching ability
Unrealistic distance.
Theta*;
Lazy theta*
Shorter & realistic path,
low search time
Consumes much time to check unexpected neighbors
Clothoid tentaclesGeometrical shape which fits well the shape of obstacles;
realistic method with respect to vehicle dynamics and real road structure
Large number of tentacles calculated and high calculation time
Bio-inspiredGAsolve NP- hard & multi-objectives problems.High time complexity, early convergence.
ACODeals with multi-objectives & continuous planning problems,
strong robustness
High time complexity, premature convergence and ant colony lost
PSO, CMOPSOActs faster than GA,
deal with a low number of individuals problems
Premature convergence & parameter sensitive, high time complexity
SFLAEasy to implement,
improves convergence speed,
better search capacity with the existence of uncertainty
High time complexity
MAEfficient in path smoothness with low computational complexityHigh time complexity
Neural NetworkDRLEffective end-to end path planning,
optimal strategy,
local navigation
Expensive to train, complex data models.
BNNHandle uncertainty,
optimal & safe path,
real time operations
Computationally tractable; expensive calculation.
ANNPerforms well in complex environmentsHigh time complexity.
FDFOptimal path planning,
complex and indoor environment,
deals with uncertainty
Needs broad testing with equipment.
Mathematic Model-BasedMIL, BIPGives closely representation of the environment so as the system,
optimal solution
High time complexity, no analytic solutions.
FlatnessEnsure control flatness,
optimal solution,
deals with control disturbance and uncertainty
High time complexity, no analytic solutions.
Discrete optimizationIdentify a safe and comfortable pathDeals only with one dynamic obstacle
Limit-Cycle, ELC, EPLCAvoid deadlocks,
local minima & oscillations,
safety distance respected,
does not need any complex computation
-----------
Multi-Fusion BasedEmbedded multi-fusionGather advantages of each algorithm,
high performance,
static & dynamic threats,
fast searching
Have to control uncertainty
Ranked multi-fusionStatic & dynamic threats,
fast searching
Each algorithm works separately.
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Abdallaoui, S.; Aglzim, E.-H.; Chaibet, A.; Kribèche, A. Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques. Energies 2022, 15, 1358. https://doi.org/10.3390/en15041358

AMA Style

Abdallaoui S, Aglzim E-H, Chaibet A, Kribèche A. Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques. Energies. 2022; 15(4):1358. https://doi.org/10.3390/en15041358

Chicago/Turabian Style

Abdallaoui, Sara, El-Hassane Aglzim, Ahmed Chaibet, and Ali Kribèche. 2022. "Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques" Energies 15, no. 4: 1358. https://doi.org/10.3390/en15041358

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