Abstract

Safe and smooth mobile robot navigation through cluttered environment from the initial position to goal with optimal path is required to achieve intelligent autonomous ground vehicles. There are countless research contributions from researchers aiming at finding solution to autonomous mobile robot path planning problems. This paper presents an overview of nature-inspired, conventional, and hybrid path planning strategies employed by researchers over the years for mobile robot path planning problem. The main strengths and challenges of path planning methods employed by researchers were identified and discussed. Future directions for path planning research is given. The results of this paper can significantly enhance how effective path planning methods could be employed and implemented to achieve real-time intelligent autonomous ground vehicles.

1. Introduction

In recent years, mobile robot path planning research aimed at achieving intelligent autonomous ground vehicles has received more attention. Path planning and motion control are very important but complex navigation tasks in robotics. Path planning in mobile robotics refers to strategies to determine how a mobile robot gets to its goal safely ensuring that obstacles are avoided [1]. To successfully achieve path planning and motion control, a vehicle is expected to possess the ability to perceive and detect obstacles to be avoided to enable it to reach its target safely. What is expected in robotics is to develop real-time intelligent autonomous navigation robots that can sense and interpret information collected from their environment to determine their position, direction to goal, avoid obstacles and perform smooth navigation in both structured and unstructured environments. The robots are expected to perform these tasks with safe and shortest path, and lowest time to their target and finally perform their assigned task without the intervention of humans [27]. There are many applications and benefits to be derived from intelligent autonomous robots. Some of which include: rescue operations during disaster, task performance in factories, homes, in areas of transportation, medicine, education, agriculture and many others.

Mobile robotics path planning is described as multi-objective optimization problem since it is required to generate the appropriate trajectories as well as obstacle avoidance in the environment [8]. Three tasks are required during mobile robot path planning. These include acquiring information from its environment, localization of its current position, and finally taking necessary decision based on the provided algorithm and the information acquired to execute its task [9, 10]. Lavalle [11] identified feasibility and optimality as path planning criterion with different concerns. The concern of feasibility criteria is to determine a plan to reach goal irrespective of the efficiency. Optimality is concerned with determining an optimized feasible plan to reach goal with efficient performance. Comparing the two, achieving a feasible path planning was described to be a problem but that of optimal path planning is more problematic. Path planning and obstacle avoidance methods could be classified into static or dynamic based on the environment and as global or local based on the path planning algorithm [12]. Environment composed of stationary objects is described as static while those with moving objects are termed as dynamic. When the path planning occurs in a static environment and all the information of the environment required by the robot to perform path planning and obstacle avoidance is available, it is described as global path planning. Local path planning on the other hand occurs when the robot is in motion and it reacts to changes in the environment to decide its movement [1, 10]. Path planning can also be described as either online or off-line and reactive or map based [13]. Off-line techniques compute the path before navigation while online techniques perform the computations and take decision incrementally during the navigation process. Data derived from cameras and sensors including ultrasonic sensors, infrared sensors and light sensors are interpreted in different ways by algorithms to embark on safe path planning. Control of navigation and obstacle avoidance for mobile robots can be described as a reactive approach [1416] because the robot is expected to react against its changing environment by reacting immediately to new information received from sensors. Control of path planning is however described as deliberative approach because the robot is expected to provide the exact planning to achieve a goal relying on the geometric model of the environment and the appropriate theory. The most common control method of avoiding obstacles in cluttered environment by mobile robot is the reactive local navigation schemes where the robot’s action depends on sensor information.

Ongoing research in mobile robotics is geared towards building autonomous and intelligent robots that perform robust motion planning and navigation in dynamic environments [17]. There are records of considerable number of research that aimed at addressing path planning and obstacle avoidance problem using diverse approaches and algorithms [1729]. Despite the numerous efforts to address the problem of safe path planning of mobile robots, there still exists a challenge in achieving real safe and optimal path planning to achieve the use of intelligent autonomous vehicles [5, 3035]. These outstanding challenges motivated this research to conduct an overview of the popular methods and strategies used by researchers to address the problem and to identify the strengths and challenges of these approaches and consider the way forward to achieving intelligent autonomous vehicles.

Mobile robot path planning methods could be categorized in different ways. In this paper, we classified them into nature-inspired computation, conventional, and hybrid methods. Methods and strategies which have something to do with the imitation of phenomena of nature are described as nature-inspired computation method. Those that are not related to imitation of nature phenomena are classified under conventional method. Methods that combine two or more strategies are described as hybrid methods in this paper.

The remainder of this paper is organized as follows: discussion of conventional mobile robot path planning methods is given in Section 2. The strengths and challenges of the conventional methods are given in Section 3. Discussion of nature-inspired mobile robot path planning methods with their strengths and challenges is covered in Sections 4 and 5. In Sections 6 and 7, hybrid methods with their strengths and challenges are presented. Conclusion and the way forward for mobile robot path planning and obstacle avoidance are given in Section 8.

2. Conventional Path Planning Methods

The conventional path planning methods (CPPM) are the traditional methods used over the years by researchers for mobile robot path planning. Most of these methods rely on distance information from objects to the robots, force of attraction and repulsion, statistical methods, clustering, or graphical map calculations to determine the path planning of the robot. They are comparatively computationally expensive. Notable among them are artificial potential field (APF), distance control algorithm, bumper event approach, wall-following, sliding mode control (SMC), dijkstra, A, D, Stereo block matching, voronoi diagram (VD), simultaneous localization and mapping (SLAM), vector field histogram (VFH), rapidly exploring random tree (RRT), curvature velocity, lane curvature, dynamic window, and tangent graph. Accounts of the use of some of these approaches are given in the next subsections.

2.1. Artificial Potential Field Path Planning Method

One of the popular methods used by researchers over the years is APF. APF is a mathematical method which causes a robot to be attracted to the goal but repelled by obstacles in the environment [6, 34, 36, 37]. There are notable research works carried out using APF with sensors to plan the path of mobile robots to provide autonomous navigation, taking obstacle avoidance into consideration [12, 3747]. The idea of applying APF to path planning originated from Khatib [34]. APF approach was modified by some researchers to make it more efficient for path planning and obstacle avoidance [41, 43, 48, 49]. The algorithm of APF comprises the attractive force, repulsive potential force, and the total potential force. APF algorithm using Gaussian function as in [50] can be expressed as shown in the following:where   is total attraction force;   is maximum value of attraction force at any instance;   is attractive constant;   is Euclidean distance between the robot and the goal;   is total repulsive force;   is maximum value of repulsive force at any instance;   is repulsive constant;   is Euclidean distance between the robot and the obstacle.

One of the recent usages of APF in mobile robot path planning is found in [40]. They extended the APF method by considering household animals’ motion attributes with the purpose of improving human-robot interaction. The attractive and the repulsive forces of APF were all extended. A real robot experiment was conducted using holonomic robot with six cameras to test their algorithm and to confirm the simulation results. Also, to help solve the point mass problem of APF for car-like robots, potential field window which is an extension of APF method was proposed in [51] to provide safe navigation. With this method, the potential field computations were done differently compared to the conventional APF method. APF has also been considered in multiple-robot path planning in [52].

2.2. Vision-Based Path Planning Method

Although most approaches use information from cameras and sensors to determine the execution of their algorithms, some methods rely basically on image processing of information from cameras. These methods were described as vision-based methods [33, 5357]. A recent visual-based approach was presented in [56] to deal with path planning and obstacle avoidance problem for small unmanned vehicles by adopting the region interest extraction method used in [57]. Local blind deconvolution was utilized to classify the regions of the images collected relative to each other to help produce a feature map composed of localized structural formation of the processed images. The feature maps realized were then used as the basis for the detection and obstacle avoidance. This approach was first introduced in [58]. With this approach, before the robot decides to move to a given direction, images are captured and downsized to 320-pixel column width to aid faster computations. The feature map is then extracted. The parts of the map are then used to determine if there are obstacles before the robot makes a move to the appropriate direction. Comparative results demonstrated that this method resulted in less frequent obstacle hits of 4-5% compared to histogram-based contrast (HC), region-based contrast (RC), and spectra residual (SR) which registered between 11 and 14% hits.

A visual-based navigation algorithm for mobile robot using obstacle flow extracted from captured images to determine the estimated depth and the time to collision using the control law called balanced strategy was also presented in [53]. A combination of very low-resolution images and a sonar sensor was also used to develop a vision-based obstacle detection algorithm in unstructured indoor environment in [33]. While a digital camera was used to take images for segmentation, the sonar sensor was used to extract depth information from the image. Kim and Do [54] on the other hand presented a visual-based dynamic obstacle detection and avoidance approach with block-based motion estimation (BBME) using a single camera. A single camera sensor based on relative focus maps method was also presented in [58]. Extracted region of images was taken and divided into 3x3 regions to determine the intensity of the regions. The region with high intensity specifies an obstacle and those with low intensity determine the way to go during navigation.

Instead of using cameras as others did, Lenser and Veloso [55] demonstrated visual sonar method to detect known and unknown objects by considering the occlusions of the floor of known colors to aid detection and obstacle avoidance. With the assumption that, target velocity is known remaining that of the speeds of dynamic obstacles, a sensor-based online method termed as directive circle (DC) for motion planning and obstacle avoidance proposal was made in [59]. Both static and moving obstacles were considered in a simulation using the approach.

Recently, a visual navigation approach based on transfer learning was presented in [60] to enhance the environmental perception capacity in semantic navigation of autonomous mobile robots. The method is made up of three-layer models including place recognition, rotation region, and side recognition. Results from real experiments indicate good performance of the method in semantic navigation. The robot was able to recognize its initial state and poses and performed pose correction in real time. Improvement is required for its implementation in complex and outdoor environment.

2.3. Wall-Following Path Planning Method

Wall-following (WF) method was also considered by researchers. WF method considers the wall around the robot to guide it movement from one location to another by the help of range sensors. Gavrilut et al. [61] demonstrated a wall-following approach to mobile robot obstacle avoidance by considering the faster response time and easy integration of IR sensors into microcontrollers. Robby RP5 robot equipped with two IR proximity sensors was used to test their algorithm. Though the completion time during the experiment was low, errors were generated because of interference of emitted signals from the two sensors used. In addition, relatively small obstacles could not be detected.

2.4. Sliding Mode Control Path Planning Method

In a different development, sliding mode control (SMC) was considered by some researchers [6264]. SMC is a nonlinear control method that brings about changes in the dynamics of a nonlinear system by applying discontinuous control signal that force the system to slide towards a cross section of the normal behavior of the system. Matveev et al. [62] presented a sliding mode strategy which is mathematically expensive for border patrolling and obstacle avoidance involving obstacles in motion. Obstacles were considered to have different shapes randomly at different periods. The velocities of the moving objects were considered to aid in the avoidance of obstacles in motion. Simulation and experiment with unicycle-like robot were performed to evaluate the approach.

2.5. A Reactive Dynamic Path Planning Method

A reactive dynamic approach employs sensor-based or vision-based approach by reacting to unforeseen obstacles and situations during navigation with appropriate decisions. A reactive dynamic approach to path planning and obstacle avoidance has been implemented in autonomous mobile robots over the years [12, 6567]. One of such works is seen in Tang and Ang [66]. Based on situated-activity paradigm and divide-and-conquer strategy, they adopted a reactive-navigation approach to propose a method called virtual semicircles (VSC) which put together division, evaluation, decision, and motion generation modules to enable mobile robots to avoid obstacles in complex environments. Simulation was used in the implementation of this approach. Matveev, Hoy, and Savkin [5] proposed a computational expensive approach termed as a reactive strategy for navigation of mobile robots in dynamic environment unknown to the robots with cluttered moving and deformed obstacles. This approach was implemented using simulation. A reactive-navigation approach using integrated environment representation was proposed for obstacle avoidance in dynamic environment with variety of obstacles including stationary and moving objects in [68]. The approach was experimented on a Pioneer P3-DX mobile wheeled robot in an indoor environment. A method using reactive elliptic trajectories with reactive obstacle avoidance algorithm embedded in a multicontroller architecture to aid obstacle avoidance was also presented in [69].

2.6. Dynamic Window Path Planning Approach

Some researchers also considered the dynamic window approach (DWA) to provide optimal obstacle avoidance [7074]. Recently, an improved dynamic window approach was proposed in [75] for mobile robot obstacle avoidance. Considering the drawbacks of local minima of this approach causing the robot to be trapped in a U-shaped obstacle, a laser range finder was used as the sensor to ensure optima path decision making of the robot. The size of the robot was considered in this approach. Simulation was used to evaluate the approach and compared with other DWA results in MATLAB and the former performs better according to the authors.

2.7. Other Conventional Path Planning Methods

Accounts of other conventional path planning methods used by researchers other than those described above are summarized below.

A heuristic A-Star (A) algorithm and dynamic steering algorithm were employed in [10] to propose an approach to obtain the shortest path and the ability to avoid obstacles that are known to the robot in a predefined grid-based environment map based on information derived from sonar sensors.

A research on using robot motion strategies to enable a robot to track a target in motion in a dynamic environment was done in [76]. Four ultrasonic range sensors with two control algorithms where one controlled the stopping of the vehicle upon sensing an obstacle and the other deciding the direction of movement were presented in [77]. This method was implemented on a three-wheeled mobile robot in indoor environment.

Distance control algorithm for mobile robot navigation using range sensors was also considered by researchers for path planning. Notable among them was the research by Ullah et al. [78, 79]. They employed distance control algorithm to develop a remote-controlled robot to predict and avoid collisions between vehicles by maintaining a given safe distance between the robot and the obstacle

In another development, a bumper event approach was employed to develop an algorithm for obstacle avoidance of Turtlebot in [80]. The approach however did not provide collision free navigation.

Kunwar et al. [81] conducted a research into using rendezvous guidance approach to track moving targets of robots in a dynamic environment made up of stationary and moving obstacles. To enable efficient noise filtration of data collected from the environment, Chih-Hung, Wei-Zhun, and Shing-Tai [82] recently evaluated the performance of Extended Kalman Filtering (EKF) and Kalman Filtering (KF) for obstacle avoidance for mobile robots. Implementation was carried out using a two-wheeled mobile robot with three sonar sensors. EKF approach was described to have performed better than KF in the experiment.

Semi-global stereo method (SGBM) with local block matching algorithm (BM) where obstacles were identified using a method that checks the relative slopes and height differences of objects was used in [83]. A disparity map obtained from the processed pair of images using stereo cameras was taken through further processing and finally to the obstacle avoidance algorithm to determine the movement of the vehicle to the defined GPS point while avoiding obstacles. Real-time experiment was performed using an electric vehicle as shown in Figure 1.

Other methods including velocity space [84], SLAM, VD [85, 86], VFH [87], RRT [88, 89], and others have also gained popularity in the field of mobile robot path planning. Recently, a visual SLAM system-based method was proposed in [90] for a mobile robot equipped with depth sensor or camera to map and operate in unknown 3D structure. The purpose of the approach was to improve the performance of mapping in a 3D structure with unknown environment where positioning systems are lacking. Simulation was done using Gazebo simulator. Real experiment was performed using Husky robot equipped with Kinect v2 depth sensor and laser range scanner. Results confirmed improvement against classical frontier-based exploration algorithms in a house structure. Improvement may be required to address how to differentiate similar structures and to deal with errors in determining waypoints.

3. Strengths and Challenges of Conventional Path Planning Methods

The conventional path planning methods have their strengths and weaknesses. These are discussed in the next subsections.

3.1. Strengths of Conventional Path Planning Methods

Even though conventional methods of path planning are computational expensive, they are easy to implement. Methods like APF, DWA, A, PRM and other conventional methods are simple to implement. The implementation of SMC strategy for instance is easy and fast with respect to response time. It also performs well in a condition with uncertain and unconducive external factors [64]. Also, these methods can combine well with other methods and they perform better when blended with other methods. Popular among them is APF which many researchers combined with other methods. A for instance is very good at obtaining the shortest path from the initial state to the goal. When combined with other methods, the hybrid method is able to generate optimal path.

3.2. Challenges of Conventional Path Planning Methods

Notwithstanding the strengths of conventional methods for path planning, there exist challenges affecting the achievement of intelligent autonomous ground vehicles. The following are some of the challenges with these methods.

To begin with, most of the approaches including conventional methods discussed used cameras and sensors to collect data from the environment to determine the execution of the respective path planning algorithms [55, 9193]. Unfortunately, readings from cameras and sensors are interfered with noise due to changes in pressure, lightening system, temperature and others. This makes the collected data uncertain to enable control algorithms to achieve safe and optimal path planning [92, 94]. The dynamics of the vehicles also cause noise including electric noise of the mobile robots [5]. These conditions affect the accuracy, efficiency, and reliability of the acquired real-time environmental data collected to enable the robot to take a decision [95]. Research work has been done to address the noise problem, but it is still a challenge. This has effect on the practical implementation of proposed approaches.

Typical with vision-based obstacle avoidance strategies, factors including distance of objects from the robot, color, and reflection from objects affects the performance of detecting obstacles especially moving objects [54]. The use of stereo vision approaches [96, 97] is very limited and can work only within the coverage of the stereo cameras and could not work in regions that are texture-less and reflective [98]. There is a problem identifying pairs of matched points such that each of these points demonstrate the projection of the same 3D point [99]. This results in ambiguity of information between points of the images obtained which may lead to inconsistent interpretation of the scene [100].

Furthermore, some of the approaches rely on the environmental map to enable the robot take decisions in navigation. There is a problem with unnecessary stopping of the mobile robot during navigation to update its environmental map. This affects the efficiency and the real applications of mobile robots to provide safe and smooth navigation. This challenge was considered in [101] and was demonstrated through simulation. However, it could not achieve the safe optimal path to the target and was not also demonstrated in a real experiment to determine its efficiency in support of simulation results.

DWA also has the drawback of resulting in local minima problems and nonoptimal motion decision due to constraints of the mobile robot the approach could not manage [75, 102104].

In addition, despite the popularity of the use of APF approach in path planning and obstacle avoidance of mobile robots, it has serious challenges. Navigation control of robots using APF considers the attraction forces from target and the repulsion forces from the obstacles. When performing this attraction and repulsion task, environmental information is compared to a virtual force. Computations lead to loss of important information regarding the obstacles and cause local minima problem [36, 40, 41, 105, 106]. APF can also result in unstable state of the robot where the robot finds itself in a very small space [107]. It can cause the robot to be trapped at a position rather than the goal [51]. Other problems of APF include inability of the robot to pass between closely spaced obstacles, oscillations at the point of obstacles, and oscillations when the passage is very small for the robot to navigate and goals nonreachable with obstacle nearby (GNRON). It also performed poorly in environment with different shapes of obstacles [108110]. Limited sensing ability, bounded curvature, limited steering angle, and velocity or finite angular and linear acceleration of the mobile robot hardware have great effect on the performance of APF methods [51]. It may also be far from the optimum when planning is local and reactive [111].

Though VFH, unlike APF strategy, does well in narrow spaces, if the size and kinematics of the robot are not taken into consideration it can fail especially in narrow passages [112]. Incorrect target positioning may also result in VFH algorithm not being reliable [113].

Besides, SMC methods are fast with respect to response time and are also good transient robust when it comes to uncertain systems and other external factors that are not conducive [64]. But, it does not perform well if the longitudinal velocity of the robot is fast. It also has the problem of chattering which may result in low control accuracy [114].

Moreover, some methods like VD, RRT, and others do well in simulation environment but relatively difficult to implement in real robot platform experiments. VD, RRT, and PRM are good at generating global roadmap but a local planner is required to generate the path. They are not good at performing in dynamic environments if not combined with other methods. A method on the other hand has the problem with generating smooth path and it requires path smoothening algorithms to achieve smooth path.

4. Nature-Inspired Computation-Based Methods

According to Siddique and Adeli [115], nature-inspired computing is made up of metaheuristic algorithm that try to imitate or base on some phenomena of nature given by natural sciences. A considerable number of researchers tried addressing the problem of mobile robotics path planning and obstacle avoidance using stochastic optimization algorithm techniques that imitate the behavior of some living things including bees, fish, birds, ants, flies, and cats [116122]. These algorithms are referred to as nature-inspired paradigms and has been applied in engineering to solve research problems [123, 124]. Nature-inspired computation-based methods use ideas obtained from observing how nature behaves in different ways to solve complex problems that are characterized with imprecision, uncertainty and partial truth to achieve practical and robust solution at a lower cost [125]. Notable among nature-inspired methods used in path planning and obstacle avoidance research include artificial neural networks (ANN), genetic algorithms (GA), simulated annealing (SA), ant colony optimization (ACO), particle swarm optimization (PSO), fuzzy logic (FL), artificial bee colony (ABC), and human navigation dynamics. Nature-inspired computation-based methods were claimed to be better navigation approaches compared to conventional ones such as APF methods [126]. Most of these methods consider reinforcement learning to ensure mobile robots perform well in unknown and unstructured environments. Accounts of the use of some of these approaches are discussed in the next subsections.

4.1. Fuzzy Logic Path Planning Method

FL is one of the most significant methods used over the years for mobile robot path planning. Though FL had been studied since 1920 [127], the term was introduced in 1965 by Lotfi Zadeh when he proposed fuzzy set theory [128]. FL is a form of many-valued logic with truth values of variables of real number between 0 and 1 used in handling problems of partial truth. It is believed that Fuzzy controllers based on FL possess the ability to make inferences even in uncertain scenarios [129]. FL can extract heuristic knowledge of human expertise and imitate the control logic of human. It has the “if-then” human-like rules of thinking. This characteristic has made FL and other derived approaches based on FL become the most used approach by many researchers in mobile robot path planning [4, 17, 18, 28, 130151].

Recently, fuzzy logic was employed in [152] to propose mobile robot path planning in environment composed of static and dynamic obstacles. Eight sensors were used to collect data from the environment to aid detecting the obstacles and determining trajectory planning. Implementation was done in simulation and real-time experiments in a partially known environment and the performance of the proposed approach was described to be good. Multivalued logic framework was used to propose a preference based fuzzy behavior system to control the navigation of mobile robots in cluttered environment [147]. Experiment was done using a Pioneer 2 robot with laser range finder and localization sensors in indoor modelled forest environment. The possibility of this approach performing in the real outdoor environment with considerable number of constraints and moving obstacles is yet to be determined.

In another development, FL based path planning algorithm using fuzzy logic was presented by Li et al. [139]. The positions of the obstacles and the angle between the robot and the goal positions were considered as the input variables processed, using fuzzy control system to determine the appropriate movement of the robot to avoid colliding with obstacles. The approach was implemented in simulation.

Fuzzy logic approach was employed in [153] to develop a controller with 256 fuzzy logic rules with environmental data collected using IR sensors. Webot Pro and MATLAB were used for the software development and simulation, respectively. The performance in obstacle avoidance using the method in simulation was described to be good. However, since no real experiment is implemented, we could hardly judge if the approach could work in the real environment where constraints including noise and the limitation of hardware components of mobile robots are common. An approach involving fuzzy logic to formulate the map of an input to output to determine a decision described as fuzzy inference system (FIS) was employed to propose a method to control autonomous ground vehicles in unstructured environment using sensor-based navigation technique [28, 154]. During robot navigation, environmental mapping is done in most cases to enable the robot to decide its movement [147]. At the course of navigation, the robot stops to update the environmental map to determine the next move [14]. However, Baldoni, Yang and Kim [101] are of the view that periodic stopping to update the environmental map compromises the efficiency and practical applications of these robots. Hence, they proposed a model using a graphical and mathematical modelling tool called Fuzzy Petri net with a memory module and ultrasonic sensors to control a mobile robot to provide dynamic and continuous obstacle avoidance. The approach was demonstrated using simulation which achieved 8% longer than the ideal path as against 17% longer than ideal path with the approach without memory.

Apart from the discussion above, some researchers also employed FL with the help of ultrasonic and infrared sensors to develop path planning algorithms which were successfully implemented in both simulation and real robots platform [17, 25, 135, 144151].

4.2. Artificial Neural Network Path Planning Method

Research involving the use of ANN as intelligent strategy in solving navigation and obstacle avoidance problems in mobile robotics has also been explored extensively [102, 155166]. The application of ANN tries to imitate the human brain to provide intelligent path planning.

Chi and Lee [157] proposed neural network control strategy with backpropagation model to control mobile robot to navigate through obstacles without collision. P3DX mobile robot was used to evaluate the developed algorithm for navigation from the start to the exit of maze as shown in Figure 2.

ANN is believed to be very good at resolving nonlinear problems that require mapping input and output relation without necessarily having knowledge of the system and its environment. Based on this strength, Akkaya, Aydogdu and Canan [167], proposed global positioning system (GPS) and dead reckoning (DR) sensor fusion approach by adopting ANN nonlinear autoregressive with external input (NARX) model to control mobile robot to avoid hitting obstacles. The mobile robot kinematics was modelled using ANN. Based on the performance of the approach through simulation and experiment, the approach was presented by the authors as an alternative to conventional navigation methods that use Kalman filter.

To achieve intelligent mobile robot control in unknown environment, Panigrahi et al. [168] proposed a redial basis function (RBF) NN approach for mobile robot path planning. Farooq et al. [169] also contributed by designing an intelligent autonomous vehicle capable of navigating noisy and unknown environment without collision using ANN. Multi-layer feed forward NN controllers with back error propagation was adopted for robot safe path planning to reach goal. During the evaluation of the approach, it was identified that the efficiency of the neural controller deteriorates as the number of layers increase due to the error term that is determined using approximated function.

In another development, Medina-Satiago et al. [170] considered path planning as a problem of pattern classification. They developed a path planning algorithm using multilayer perceptron (MLP) and back propagation (BP) of ANN which was experimented on a differential drive mobile robot. Alternatively, Syed et al. [171] contributed by proposing guided autowave pulse coupled neural network (GAPCNN) which is an improvement of pulse coupled neural network (PCNN) by Qu et al. [172] for mobile robot path planning and obstacle avoidance. Dynamic thresholding technique was applied in their method. Results from simulation and experiments described the approach to be time efficient and good for static and dynamic environments compared to modified PCNN.

In [173], a data-driven end-to-end motion planning method based on CNN was introduced to control a differential drive. The method aimed at providing the ability to learn navigation strategies. Simulation and real experiment indicated that the model can be trained in simulation and transferred to a robotic platform to perform the required navigation task in the real environment. Local minima and oscillation problems of the method need to be addressed.

4.3. Genetic Algorithm Path Planning Methods

Another popular method used by researchers over the years for mobile robot path planning is GA. GA is a metaheuristic inspired by the process of natural selection that belongs to the larger class of evolutionary algorithms (EA). GA are normally considered when there is the need to generate high-quality solutions to help optimization and search problems by using bio-inspired operators including mutation, crossover, and selection [174]. GA is a category of search algorithms and optimization methods that make use of Darwin's evolutionary theory of the survival of the fittest [175]. Research on the application of GA to robotic path planning and obstacle avoidance was done in the past [38, 176184].

Tuncer and Yildirim [178] considered GA to present a new mutation operator for mobile robot path planning in dynamic environment. According to the authors, comparing the results to other methods showed better performance of their technique in terms of path optimality. With the motivation to provide optimal and collision free mobile robot navigation, a combinatorial optimization technique based on GA approach was used in [184] to propose bacterial memetic algorithm to make a mobile robot navigate to a goal while avoiding obstacles at a minimized path length.

4.4. Memetic Algorithm Path Planning Method

Memetic algorithm is a category of evolutionary [185] method which combines evolutionary and local search methods. Memetic algorithm has been used to attempt solving optimization problems in [186]. There is remarkable research work using memetic algorithm in mobile robot path planning [187, 188].

One of such works is by Botzheim, Toda and Kubota [189]. They adopted the bacterial memetic algorithm in [190] by considering bacterial mutation and gene transfer operation as the operators. The approach was applied to mobile robot navigation and obstacle avoidance in static environment (see Figure 3).

4.5. Particle Swarm Optimization Path Planning Method

PSO technique emerged from Kennedy and Eberhart [191]. The technique was inspired by the social behavior of birds and fish in groups by considering the best positions of each bird or fish in search of food using fitness function parameter. PSO is simple to implement and requires less computing time and performs well in various optimization problems [192195]. PSO has been adopted by a considerable number of researchers in mobile robot path planning task [192, 196208]. The mathematical equations describing PSO [196] are shown in the following:

where is particle number, is velocity of the particle i, is position of the particle i, is iteration counter, is inertial weight (decreasing function), and are acceleration coefficients known as cognitive and social parameters, and are random values in , is best position of particle, and is global best position of particle

Recently, Rath and Deepak [196] used PSO technique to develop a motion planner for stationary and movable objects. The developed algorithm was implemented in simulation and it is yet to be implemented in robotic platform to confirm the results achieved in simulation.

PSO approach applied in [209, 210] was adopted from [205, 206, 210, 211] for motion planning and obstacle avoidance in dynamic environment. The approach was implemented in simulation environment.

4.6. Artificial Bee Colony Path Planning Method

ABC algorithm was also considered by few researchers [212]. Based on swarm intelligence and chaotic dynamic of learning, Lin and Huang [119] presented ABC algorithm for path planning for mobile robots. Though the paper stated the method was more efficient than GA and PSO, it was not tested in real robot platform to ascertain that fact. Optimal path planning method based on ABC was also introduced in [116] to provide collision free navigation of mobile robot with the aim of achieving optimal path. Simulation was used to test the algorithm which was described to be successful. However, the method was not demonstrated in experiment with real robot.

Abbass and Ali [122] on their part presented what they described as directed artificial bee colony algorithm (DABC) based on ABC algorithm for autonomous mobile robot path planning. The DABC algorithm was used to direct the bees to the direction of the best bee to help obtain optimal path while avoiding obstacles. Simulation results compared to conventional ABC algorithm was described to have performed better as demonstrated in Figures 4 and 5.

Recently, bees algorithm was used in [213] to present a real-time path planning method in an indoor dynamic environment. The bees algorithm was used to generate the path in static environment which is later updated online using modified bees algorithm to enable preventing hitting obstacles in dynamic environment. Neighborhood shrinking was used to optimize the performance of the algorithm. Simulation and experiment using AmigoBot were used to evaluate the method and it was described to have performed well with optimal path in a real time.

4.7. Simulated Annealing Algorithm Path Planning Method

SA is a probabilistic technique used for estimating the global optimum of a function. It was used in past research for mobile robot obstacle avoidance task [214216]. SA algorithm was used in [217] to propose an algorithm to enable mobile robots to reach a goal through dynamic environment composed of obstacles with optimal path. This method was implemented successfully in simulation.

4.8. Ant Colony Optimization Algorithm Path Planning Method

ACO is a probabilistic method used for finding solution for computational problems including path planning. ACO technique has been considered by researchers for mobile robot path planning over the years [29, 218222]. Using ACO, Guan-Zheng et al. [220] demonstrated through algorithm and simulation a path planning method for mobile robots. Results were compared to GA method and it was indicated that the method was effective and can be used in the real-time path planning of mobile robots.

Vien et al. [221] used Ant-Q reinforcement learning based on Ant Colony approach algorithm as a technique to address mobile robot path planning and obstacle avoidance problem. Results from simulation were compared with results from other heuristic based on GA. Comparatively, Ant-Q reinforcement learning approach was described to be better in terms of convergence rate.

Considering the complex obstacle avoidance problem involving multiple mobile robots, Ioannidis et al. [222] proposed a path planner using Cellular Automata (CA) and ACO techniques to provide collision free navigation for multiple robots operating in the same environment while keeping their formation immutable. Implementation was done in a simulated environment consisting of cooperative team of robots and an obstacle.

Real robot platform experimental implementation may be required to prove the efficiency of these approaches to confirm the simulation results.

4.9. Human Navigation Dynamics Path Planning Methods

Human navigation dynamics (HND) research was also given attention by researchers [68, 223230]. However, very few considerations were given to the application of HND strategies to path planning and obstacle avoidance of mobile robots. HND strategy termed as all-or-nothing strategy was used by Frank et al. [231] to propose a minimalistic navigation model based on complex number calculus to solve mobile robots’ navigation and obstacle avoidance problem. This approach did not, however, demonstrate any implementation through experiments. Much work may be required in this area to explore and experiment the use of human navigation strategies to robotics motion planning and obstacle avoidance.

5. Strengths and Challenges of Nature-Inspired Path Planning Methods

5.1. Strengths of Nature-Inspired Path Planning Methods

Nature-inspired path planning methods possess the ability to imitate the behavior of some living things that have natural intelligence. Methods like ANN and FL are good at providing learning and generalization [232]. FL for instance possess the ability to make inferences in uncertain scenarios. When combined with FL method, ANN can tune the rule base of FL to produce better results. The learning component of these methods aids in effective performance in unknown and dynamic environment of the autonomous vehicle. GA and other nature-inspired methods have good optimization ability and are good at solving problems that are difficult dealing with using conventional approaches. ACO method and memetic algorithms are noted for their fast convergence characteristics and good at obtaining optimal result [233235]. Moreover, nature-inspired methods can combine well with other optimization algorithms [236, 237] to provide efficient path planning in the real environment.

5.2. Challenges of Nature-Inspired Path Planning Methods

Notwithstanding the strengths discussed above, there are some weaknesses of nature-inspired path planning methods, some of which include trapping in local minima, slow convergence speed, premature convergence, high computing power requirement, oscillation, difficulty in choosing initial positions, and the requirement of large data set of the environment which is difficult to obtain.

Despite the strength of ANN stated in the previous section, they require large set of data of the environment during training to achieve the best result which is difficult to obtain especially with supervised learning [232]. The use of backpropagation technique to provide efficient algorithm also have its challenges. BP method easily converges to local minima if the situation action mapping is not convex with the parameters [238]. The algorithm stops at local minima if it is above its global minimum. Moreover, it is also described to have very slow convergence speed which may result in some collisions before the robot gets to its defined goal [232]. FL systems can provide knowledge-based heuristic situation action mapping; however, their rule bases are hard to build in unstructured environment [232]. This makes it difficult using FL method to address path planning problems in unstructured environments without combining it with other methods. Despite the strength of good optimization capacity of GA, it is difficult for GA to scale well with complex scenarios and it is characterized with convenience at local minima and oscillation problems [239, 240]. Also, due to its complex principle, it may be difficult to deal with dynamic data sets to achieve good results [233]. Though PSO is described to be simple with less computing time requirement and effective in implementing with varied optimization problems with good results [192195], it is difficult to deal with trapping into local minima problems under complex map [194, 240]. Although ACO is noted for fast convergence with optimal results [233, 234], it requires a lot of computing time and it is difficult to determine the parameters which affects obtaining quick convergence [233, 240]. Compared to conventional algorithms, memetic algorithm is described to possess the ability to produce faster convergence and good result; however, it can result in premature convergence [235]. ABC is simple with fewer control parameters with less computational time, but low convergence is a drawback of ABC algorithm [241]. It is believed that SA performs well in approximating the global optimum, but the algorithm is slow, and it is difficult choosing the initial position for SA [242].

6. Hybrid Methods

To take advantage of the strengths of some methods while reducing the effects of their drawbacks, some researchers have combined two or more methods in their investigations to provide efficient hybrid path planning method to control autonomous ground vehicles. Some of these approaches include neuro-fuzzy, wall-following-based fuzzy logic, fuzzy logic combined with Kalman Filter, APF combined with GA, and APF combined with PSO. Some of the hybrid approaches are discussed in the next subsections.

6.1. Neuro-Fuzzy Path Planning Method

Popular among the hybrid approaches is neuro-fuzzy also termed as fuzzy neural network (FNN). It is a combination of ANN and FL. This approach considers the human-like reasoning style of fuzzy systems using fuzzy sets and linguistic model that are composed of if-then fuzzy rules as well as ANN [243]. The use of neuro-fuzzy system approach in obstacle avoidance for mobile robots’ research has been considered by many researchers [101, 244260].

A weightless neural network (WNN) approach using embedded interval type-2 neuro-fuzzy controller with range sensor to detect and avoid obstacles was presented in [256, 257]. This approach worked but its performance was described to be interfered by noise. Unified strategies of path planning using type-1 fuzzy neural network (T1FNN) was proposed in [16] to achieve obstacle avoidance. It is however identified in [101] that the use of (T1FNN) have challenges including the unsatisfactory control performance and the difficulty of reducing the effect of uncertainties in achieving task and the oscillation behavior that is characterized by the approach during obstacle avoidance. Kim and Chwa [14] took advantage of this limitation and modified the TIFNN to propose an obstacle avoidance method using interval type-2 fuzzy neural network (IT2FNN). Evaluation of this strategy was carried out using simulation and experiment and compared with the T1FNN approach. The IT2FNN was described to have produced better results.

AbuBaker [258] presented a neuro-fuzzy strategy termed as neuro-fuzzy optimization controller (NFOC) to control mobile robot to avoid colliding with obstacles while moving to goal. NFOC approach was evaluated in simulation and was compared with fuzzy logic controller (FLC40) and FLC625 and the performance was described to be better in terms of response time.

Chen and Richardson [261] on the other hand tried to look at path planning and obstacle avoidance of mobile robot in relation to the human driver point of view. They adopted a new fuzzy strategy to propose a dynamic recurrent neuro-fuzzy system (DRNFS) with short memory. Their method was simulated using three ultrasonic sensors to collect data from the environment, 18 obstacle avoidance trajectories and 186 training data pairs to train the DRNFS and compared to conventional fuzzy rule-based navigation system and the approach was described to be better in performance. Figure 6 demonstrates the performance of the DRNFS compared to the conventional fuzzy rule-based navigation system.

Another demonstration of neuro-fuzzy approach was presented in [259] with backpropagation algorithm to drive mobile robot to avoid obstacles in a challenging environment. Simulation and experimental results showed partial solution of reduction of inaccuracies in steering angle and reaching goal with optimal path. A proposal using FL control combined with artificial neural network was presented by Jeffril and Sariff [260] to control the navigation of a mobile robot to avoid obstacles.

To capitalize on the strengths of neural network and FL, Algabri, Mathkour and Ramdane [262] proposed adaptive neuro-fuzzy inference system (ANFIS) approach for mobile robot navigation and obstacle avoidance. Simulation was carried out using Khepera simulator (KiKs) in MATLAB as shown in Figure 7. Practical implementation was also done using Khepera robot in an environment scattered with few obstacles.

A combination of FL and spiking neural networks (SNN) approach was proposed in [263] and simulation results was compared to that of FL. The new approach was described to have performed better. Alternatively, ANFIS controller was developed using neural network approach to control multiple mobile robot to reach their target while avoiding obstacles in a dynamic indoor environment [18, 264266]. The authors developed ROBNAV software to handle the control of mobile robot navigation using the ANFIS controller developed.

Pothal and Parhi [267] developed Adaptive Neuron Fuzzy Inference System (ANFIS) controller for mobile robot path planning. Implementation was done using single robot as well as multiple robots. The average percentage error of time taken for a single robot to reach its target comparing simulation and experiment results was 10.47%.

To deal with the effect of noise generation during information collection using sensors, a Hybrid Intelligent System (HIS) was proposed by Alves and Lopes [268]. They adopted FL and ANN to control the navigation of the robot. While, in neuro-fuzzy system, training needs to be done from scratch, this method deviated a little bit where only the fuzzy module is calibrated and trained. Simulation results showed that the method was successful.

Realizing the challenge of training and updating parameters of ANFIS in path planning which usually leads to local minimum problem, teaching-learning-based optimization (TLBO) was combined with ANFIS to present a path planning method in [269]. The aim was to exploit the benefits of the two methods to obtain the shortest path and time to goal in strange environment. The TLBO was used to train the ANFIS structure parameters without seeking to adjust parameters. PSO, invasive weed optimization (IWO), and biogeography-based optimization (BBO) algorithms were also used to train the ANFIS parameters to aid comparison with the proposed method. Simulation results indicated that TLBO-based ANFIS emerged with better path length and time. Improvement may be required to consider other path planning tasks. It may also require comparison with other path planning methods to determine its efficiency. Real experiment should be considered to prove the effectiveness of the method in the real environment.

6.2. Other Hybrid Methods That Include FL

Wall-following-based FL approach has also been considered by researchers. One of the pioneers among them is Braunstingl, Anz-J,and Ezkera [270]. They used fuzzy logic rules to implement a wall-following-based obstacle controller. Wall-following control law based on interval type-2 fuzzy logic was also proposed in [131, 271, 272] for path planning and obstacle avoidance while trying to improve noise resistance ability. Recently, Al-Mutib and Adessemed [273] tried to address the oscillation and data uncertainties problems and proposed a fuzzy logic wall-following technique based on type-2 fuzzy sets for obstacle avoidance for indoor mobile robots. The fuzzy controller proposed relied on the distance and orientation of the robot to the object as inputs to generate the needed wheel velocities to move the robot smoothly to its target while switching to the obstacle avoidance algorithm designed to avoid obstacles.

Despite the problem of sensor data uncertainties, Hank and Haddad [274] took advantage of the strengths of FL and combined trajectory-tracking and reactive-navigation mode strategy with fuzzy controller used in [275] for mobile robot path planning. Simulation and experiments were performed to test the approach which was described to have produced good results.

In [276], an approach called dynamic self-generated fuzzy Q-learning (DSGFQL) and enhanced dynamic self-generated fuzzy Q-learning (EDSGFQL) were proposed for obstacle avoidance task. The approach was compared to fuzzy Q-learning (FQL) [277], dynamic fuzzy Q-learning (DFQL) of Er and Deng [135], and clustering and Q-value based GA learning scheme for fuzzy system design (CQGAF) of Juang [278] and it was proven to perform better through simulation. Considering a learning technique in a different direction, a method termed as reinforcement ant optimized fuzzy controller (RAOFC) was designed by Juang and Hsu [279] for wheeled mobile robot wall-following under reinforcement learning environments. This approach used an online aligned interval type-2 fuzzy clustering (AIT2FC) method to generate fuzzy rules for the control automatically. This makes it possible not to initialize the fuzzy rules. Q-value aided ant colony optimization (QACO) technique in solving computational problems was employed in designing the fuzzy rules. The approach was implemented considering the wall as the only obstacle to be avoided by the robot in an indoor environment.

Recently, a path planning approach for goal seeking in unstructured environment was proposed using least mean p-norm extreme learning machine (LMP-ELM) and Q-learning by Yang et al. [232]. LMP-ELM and Q-learning are neural network learning algorithm. To control errors that may affect the performance of the robots, least mean P-power (LMP) error criterion was introduced to sequentially update the output. Simulation results indicated that the approach is good for path planning and obstacle avoidance in unknown environment. However, no real experiment was conducted to evaluate the method.

Considering the limitation of conventional APF method with the inability of mobile robots to pass between closed space, Park et al. [280] combined fuzzy logic and APF approaches as advanced fuzzy potential field method (AFPFM) to address this limitation. The position and orientation of the robot were considered in controlling the robot. The approach was evaluated using simulation.

To address mobile robot control in unknown environment, Lee et al. [281] proposed sonar behavior-based fuzzy controller (BFC) to control mobile robot wall-following. The sub-fuzzy controllers with nine fuzzy rules were used for the control. The Pioneer 3-DX mobile robot was used to evaluate the proposed method. Although the performance was good in the environment with regular shaped obstacles, collisions were recorded in the environment with irregular obstacles. Moreover, the inability to ensure consistent distance between the robot and the wall is a challenge.

A detection algorithm for vision systems that combines fuzzy image processing algorithm, bacterial algorithm, GA and A was presented in [282] to address path planning problem. The fuzzy image processing algorithm was used to detect the edges of the images of the robot’s environment. The bacterial algorithm was used to optimize the output of the processed image. The optimal path and trajectory were determined using GA and A algorithms. The results of the method indicate good performance in detecting edges and reducing the noise in the images. This method requires optimization to control performance in lighting environment to deal with reflection from images.

6.3. Other Hybrid Path Planning Methods

There are many other hybrid approaches used for path planning that did not include FL. Some of these include APF combined with SA [216], PSO combined with gravitational search (GS) algorithm [283], VFH algorithm combined with Kalman Filter [113], integrating game theory and geometry [284], combination of differential global positioning system (DGPS), APF, FL and A path planning algorithm [41], A search and discrete optimization methods [92], a combination of differential equation and SMC [243], virtual obstacle concept was combined with APF [106], and recently the use of LIDAR sensor accompanied with curve fitting. Few of such methods are discussed in this section.

Recently, Marin-Plaza et al. [285] proposed and implemented a path planning method based on Ackermann model using time elastic bands. Dijkstra method was employed to obtain the optimal path for the navigation. A good result was achieved in a real experiment conducted using iCab for the validation of the method.

Considering the strengths and weaknesses of APF in goal seeking and obstacle avoidance, Montiel et al. [6] combined APF and bacterial evolutionary algorithm (BEA) methods to present Bacterial Potential Field (BPF) to provide safe and optimal mobile robot navigation in complex environment. The purpose of the strategy was to eliminate the trapping in local minima drawbacks of the traditional APF method. Simulation results was described to have showed better results compared to genetic potential field (GPF) and pseudo-bacterial potential field (PBPF) methods. Unknown obstacles were detected and avoided during the simulation (See Figure 8). The BPF algorithm in [6] is given in Algorithm 1.

1: procedure NAVIGATION(, , , , e, M, )
2:  i 0
3:  navigation ← True
4:  Ƥ BPF(, , , , e, M, ) Ƥ is an array
5:  while  navigation  do
6:   Perform  verification of the environment
7:   if environment has changed then
8:    qoƤ(i)
9:    Ƥ BPF(, , , , e, M, )
10:    i 0
11:   end if
12:   i i+ 1
13:   Perform  trajectory planning to navigate from Ƥ(i-1) to Ƥ(i)
14:  if i length of Ƥ then
15:   navigation← False
16:   Display  Goal has been achieved
17:  end if
18: end while
19: end procedure

Experiment demonstrated that BPF approach compared to other APF methods used a lower computational time of a factor of 1.59 to find the optimal path.

APF method was optimized using PSO algorithm in [36] to develop a control system to control the local minima problem of APF. Implementation of this approach was done using simulation as demonstrated in Figure 9. Real robot platform implementation may be required to confirm the effectiveness of the technique demonstrated in simulation.

A visual-based approach using a camera and a range sensor was presented in [286] by combining APF, redundancy and visual servoing to deal with path planning and obstacle avoidance problem of mobile robots. This approach was improved upon in [287] by including visual path following obstacle bypassing and collision avoidance with deceleration approach [288, 289]. The method was designed to enable robots progress along a path while avoiding obstacles and maintaining closeness to the 3D path. Experiment was done in outdoor environment using a cycab robot with a 70% field of view. Also, based on extended Kalman filters, a classical motion stereo vision approach was demonstrated in [290] for visual obstacle detection which could not be detected by laser range finders. Visual SLAM algorithm was also proposed in [291] to build a map of the environment in real time with the help of Field Programmable Gate Arrays (FPGA) to provide autonomous navigation of mobile robots in unknown environment. Since navigation involves obstacle avoidance, APF method was presented for the obstacle avoidance. The algorithm was tested in indoor environment composed of static and dynamic obstacles using a differential mobile robot with cameras. Different from the normal Kalman filters, computed depth estimates derived from traditional stereo method were used to initialize the filters instead of using simple heuristics to choose the initial estimates. Target-driven visual navigation method was presented in [292] to address the impractical application problem of deep reinforcement learning in real-world situations. The paper attributed this problem to lack of generalization capacity to new goals and data inefficiency when using deep reinforcement learning. Actor-critic and AI2-THOR models were proposed to address the generalization and data efficiency problems respectively. SCITOS robot was used to validate the method. Though results showed good performance, a test in environment composed of obstacles may be required to determine its efficiency in the real-world settings.

A biological navigation algorithm known as equiangular navigation guidance (ENG) law approach accompanied with the use of local obstacle avoidance techniques using sensors was employed in [13] to plan the motion of a robot to avoid obstacles in complex environment with many obstacles. The choice of the shortest path to goal was however not considered.

Savage et al. [293] also presented a strategy combining GA with recurrent neural network (RNN) to address path planning problem. GA was used to find the obstacle avoidance behavior and then implemented in RNN to control the robot. To address path planning problem in unstructured environment with relation to unmanned ground vehicles, Michel et al. [94] presented a learning algorithm approach by combining reinforcement learning (RL), computer graphics, and computer vision. Supervised learning was first used to approximate the depths from a single monocular image. The proposed algorithm then learns monocular vision cues to estimate the relative depths of the obstacles after which reinforcement learning was used to render the appropriate synthetic scenes to determine the steering direction of the robot. Instead of using the real images and laser scan data, synthetic images were used. Results showed that combining the synthetic and the real data performs better than training the algorithm on either synthetic or real data only.

To provide effective path planning and obstacle avoidance for a mobile robot responsible for transporting components from a warehouse to production lines, Zaki, Arafa and Amer [294] proposed an ultrasonic ranger slave microcontroller system using hybrid navigation system approach that combines perception and dead reckoning based navigation. As many as 24 ultrasonic sensors were used in this approach.

In [295], the authors demonstrated the effectiveness of GA and PRM path planning methods in simple and complex maps. Simulation results indicated that both methods were able to find the path from the initial state to the goal. However, the path produced by GA was smoother than that of PRM. Again, comparing GA and PRM, PRM performed path computation in lesser time which makes it more effective in reactive path planning applications. GA and PRM could be combined to exploit the benefits of the two methods to provide smooth and less time path computation. Real experiment is required to evaluate the effectiveness of the methods in a real environment.

Hassani et al. [296] aimed at obtaining safe path in complex environment for mobile robot and proposed an algorithm combining free segments and turning points algorithms. To provide stability during navigation, sliding mode control was adopted. Simulation in Khepera IV platform was used to evaluate the method using maps of known environment composed of seven static obstacles. Results indicated that safe and optimal path was generated from the initial position to the target. This method needs to be compared to other methods to determine its effectiveness. Moreover, a test is required in a more complex environment and in an environment with dynamic obstacles. Issues of replanning should be considered when random obstacles are encountered during navigation.

Path planning approach to optimize the task of mobile robot path planning using differential evolution (DE) and BSpline was given in [297]. The path planning task was done using DE which is an improved form of GA. To ensure easy navigation path, the BSpline was used to smoothen the path. Aria P3-DX mobile robot was used to test the method in a real experiment. Compared to PSO method, the results showed better optimality for the proposed method. Another hybrid method that includes BSpline is presented in [298]. The authors combined a global path planner with BSpline to achieve free and time-optimal motion of mobile robots in complex environments. The global path planner was used to obtain the waypoints in the environment while the BSpline was used as the local planner to address the optimal control problem. Simulation results showed the efficiency of the method. The KUKA youBot robot was used for real experiment to validate the approach but was carried out in simple environment. A test in a complex environment may be required to determine the efficiency of the method.

Recently, nonlinear kinodynamic constraints in path planning was considered in [299] with the aim of achieving near-optimal motion planning of nonlinear dynamic vehicles in clustered environment. NN and RRT were combined to propose NoD-RRT method. RRT was modified to perform reconstruction to address the kinodynamic constraint problem. The prediction of the cost function was done using NN. The proposed method was evaluated in simulation and real experiment using Pioneer 3-DX robot with sonar sensors to detect obstacles. Compared to RRT and RRT, it was described to have performed better.

7. Strengths and Challenges of Hybrid Path Planning Methods

Because hybrid methods are combination of multiple methods, they possess comparatively higher merits by taking advantage of the strengths of the integrated methods while minimizing the drawbacks of these methods. For instance, integration of appropriate methods can help improve noise resistance ability and deal better with oscillation and data uncertainties and controlling local minima problem associated with APF [36, 131, 171, 272, 273].

Though hybrid methods seem to possess the strengths of the methods integrated while reducing their drawbacks, there are still challenges using them. Compatibility of some of these methods is questionable. The integration of incompatible methods would produce worse results than using a single method. Other weaknesses not noted with the individual methods combined may emerge when the methods are integrated and implemented. New weaknesses that emerge because of the combination may also lead to unsatisfactory control performance and difficulty of reducing the effects of uncertainty and oscillations. Noise from sensors and cameras in addition to other hardware constraints, including the limitation of motor speed, imbalance mass of the robot, unequal wheel diameter, encoder sampling errors, misalignment of wheels, disproportionate power supply to the motors, uneven or slippery floors and many other systematic and nonsystematic errors affects the practical performance of these approaches.

8. Conclusion and the Way Forward

In conclusion, achieving intelligent autonomous ground vehicles is the main goal in mobile robotics. Some outstanding contributions have been made over the years in the area to address the path planning and obstacle avoidance problems. However, path planning and obstacle avoidance problem still affects the achievement of intelligent autonomous ground vehicles [77, 145]. In this paper, we analyzed varied approaches from some outstanding publications in addressing mobile robot path planning and obstacle avoidance problems. The strengths and challenges of these approaches were identified and discussed. Notable among them is the noise generated from the cameras, sensors, and the constraints of the mobile robots which affect the reliability and efficiency of the approaches to perform well in real implementations. Local minima, oscillation, and unnecessary stopping of the robot to update its environmental maps, slow convergence speed, difficulty in navigating in cluttered environment without collision, and difficulty reaching target with safe optimum path were among the challenges identified. It was also identified that most of the approaches were evaluated only in simulation environment. The challenge is how successful or efficient these approaches would be when implemented in the real environment where real conditions exist [266]. A summary of the strengths and weaknesses of the approaches considered are shown in Tables 1, 2 and 3.

The following general suggestions are given in this paper when proposing new methods for path planning for autonomous vehicles. Critical consideration should be given to the kinematic dynamics of the vehicles. The systematic and nonsystematic errors that may affect navigation should be looked at. Also, the limitation of the environmental data collection devices like sensors and cameras needs to be considered since their limitation affects the information to be processed to control the robots by the proposed algorithm. There is therefore the need to provide a method that can control noise generated from these devices to aid best estimation of data to control and achieve safe optimal path planning. To enable the autonomous vehicle to take quick decision to avoid collision into obstacles, the computation complexity of algorithms should be looked at to reduce the execution time. Moreover, the strengths and limitations of an approach or a method should be looked at before considering its implementation. Possibly, hybrid approaches that possess the ability to take advantage of the benefits and reduce the limitations of each of the methods involved can be considered to obtain better techniques for path planning and obstacle avoidance task for autonomous ground vehicles. Again, efforts should be made to implement proposed algorithms in real robot platform where real conditions are found. Implementation should be aimed at both indoor and outdoor environments to meet real conditions required of intelligent autonomous ground vehicles.

To achieve safe and efficient path planning of autonomous vehicles, we specifically recommend a hybrid approach that combines visual-based method, morphological dilation (MD), VD, neuro-fuzzy, A, and path smoothing algorithms. The visual-based method is to help in collecting and processing visual data from the environment to obtain the map of the environment for further processing. To reduce uncertainties of data collection tools, multiple cameras and distance sensors are required to collect the data simultaneously which should be taken through computations to obtain the best output. The MD is required to inflate the obstacles in the environment before generating the path to ensure safety of the vehicles and avoid trapping in narrow passages. The radius for obstacle inflation using MD should be based on the size of the vehicle and other space requirements to take care of uncertainties during navigation. The VD algorithm is to help in constructing the roadmap to obtain feasible way points. VD algorithm which finds perpendicular bisector of equal distance among obstacle points would add to providing safety of the vehicle and once a path exists, it would find it. The neuro-fuzzy method may be required to provide learning ability to deal with dynamic environment. To obtain the shortest path, A may be used and finally a path smoothening algorithm to get a smooth navigable path. The visual-based method should also help to provide reactive path planning in dynamic environment. While implementing the hybrid method, the kinematic dynamics of the vehicle should be taken into consideration. This is a task we are currently investigating.

This study is necessary in achieving safe and optimal navigation of autonomous vehicles when the outlined recommendations are applied in developing path planning algorithms.

Conflicts of Interest

The authors declare that there are no conflicts of interest regarding the publication of this paper.