Open access peer-reviewed chapter

Path Planning Algorithms for Mobile Robots: A Survey

Written By

Zaharuddeen Haruna, Muhammed Bashir Mu’azu, Abubakar Umar and Glory Okpowodu Ufuoma

Submitted: 30 July 2023 Reviewed: 31 July 2023 Published: 26 November 2023

DOI: 10.5772/intechopen.1002655

From the Edited Volume

Motion Planning for Dynamic Agents

Zain Anwar Ali and Amber Israr

Chapter metrics overview

269 Chapter Downloads

View Full Metrics

Abstract

Mobile robots have applications in military (for reconnaissance, search and rescue operations, bomb detection, surveillance), transportation (for cargo and packet delivery), data acquisition, etc. For the mobile robots to be able to execute these tasks with minimum or no human intervention, they need to be autonomous and intelligent. Path planning (PP) is one of the most critical areas of concern in the field of autonomous mobile robots. It is about obtaining a collision-free motion optimal path based on either time, distance, energy or cost in a static or dynamic environment containing obstacles. However, power limitation hinders the mobile robots to accomplish their task of reaching the target location as there are several paths they can follow. Each of these paths has its own path length, cost (i.e., time to reach destination), and energy constraint, thus, the need to plan for an optimal path according to a certain performance criterion. Significant research has been conducted in recent years to address the PP problem. Hence, this chapter is aimed at presenting the different approaches for PP of mobile robots with respect to different optimality criteria (time, distance, energy and cost), challenges and making recommendations on possible areas of future research.

Keywords

  • mobile robots
  • autonomous systems
  • path planning
  • energy constraint
  • optimality criterion

1. Introduction

Mobile robots play a crucial role in diverse applications, including search and rescue, cargo and packet delivery, environmental monitoring, and remote sensing, among others [1, 2, 3]. These robots operate in various environments and are classified according to their deployment technology into ground mobile robots, aerial mobile robots, water surface mobile robots, and underwater mobile robots. Ground mobile robots utilize mobile platforms like wheels, tracks, legs, or even biomimicry inspired by animals such as snakes. Aerial mobile robots include drones and helicopters, used for tasks like remote sensing, surveillance, and packet delivery [4, 5]. Water surface mobile robots operate on water for data acquisition, environmental monitoring, and surveillance. Underwater mobile robots, on the other hand, undertake missions in the ocean depths, ranging from underwater construction to ocean exploration and military applications.

Achieving autonomy in these challenging environments with minimal or no human intervention requires robust path-planning techniques. Path planning refers to the process by which mobile robots determine the optimal or feasible path from their current location to a desired destination while intelligently avoiding obstacles and adhering to various constraints [6]. In this review paper, we explore the path-planning techniques employed by ground mobile robots in different environments, addressing the unique challenges faced in ground scenarios. By enabling efficient and safe navigation, path planning plays a pivotal role in unlocking the full potential of mobile robots for accomplishing a wide range of tasks in real-world applications.

The robot path-planning problem is a fundamental challenge falling under the broader category of scheduling and routing problems, known for its NP-complete nature [7]. When seeking its target destination, a mobile robot typically has multiple paths to choose from. However, determining the optimal path involves evaluating various criteria such as path length, time, energy consumption, and cost [8]. Among these criteria, path length and time are the most commonly used measures for optimizing robot trajectories.

Mobile robot path planning can be broadly classified into two classes based on the nature of the environment in which the robot operates [8, 9]. These classes are crucial in guiding the path-planning approach and algorithms used to navigate the robot effectively. This is shown in Figure 1:

  1. Path planning of robot in static environment: this is the class of path planning that contains only static obstacles in the environment;

  2. Path planning in dynamic environment: this is the class of path planning that contains both static and moving obstacles in the environment.

Figure 1.

Classification of mobile robot path planning [10].

The dynamic path planning can be further sub divided into global path planning and local path planning [8, 9, 10]. Global path planning, also known as off-line path planning, refers to the process in which the robot possesses complete knowledge of the environment and the positions of obstacles before it starts moving. During global path planning, the robot calculates the optimal path just once at the beginning and then follows this path until it reaches the target destination. This approach assumes that the environment remains static and does not change during the robot’s movement [8, 11].

On the other hand, online or local path planning involves situations where the robot lacks prior information about the environment and the positions of obstacles before it starts moving. In this scenario, the mobile robot relies on its sensors to perceive the environment in real-time. It uses the sensor data to build a map that accurately represents the structure of the environment. Based on this dynamic map, the robot then plans its path on-the-fly, continuously adapting to changing conditions and obstacles as it navigates toward its goal [8, 10, 12].

In the domain of mobile robot path planning, researchers have explored a variety of approaches in the literature to address this challenging problem. These approaches can be broadly classified into three categories: classical (conventional), heuristics, and metaheuristics [12, 13, 14].

Advertisement

2. Path-planning approaches

Figure 2 presents the classification of path-planning approaches:

Figure 2.

Path-planning approaches.

2.1 Classical (conventional) approaches

These methods typically involve using algorithms based on traditional problem-solving techniques. Examples include road map, cell decomposition, potential field, and sub-goal network approaches. These methods are well-suited for simple environments with relatively small search spaces, where they can effectively find optimal or near-optimal paths for mobile robots.

However, in more complex scenarios with larger and intricate environments, these approaches may encounter challenges due to their exhaustive nature. Local minima convergence and high computational cost are some of the limitations associated with these methods. Local minima convergence occurs when the algorithms get trapped in suboptimal paths, preventing them from finding the best solution. Additionally, the high computational cost can become a significant hindrance, especially in real-time applications or scenarios with limited computational resources. The inherent unpredictability and uncertainty of real-world applications further compound these limitations. The dynamic and changing nature of real-world environments can make it difficult for traditional methods to adapt and find optimal paths in such uncertain conditions. Also, by providing insights into the most effective path planning algorithms, the paper can contribute to the advancement of mobile robot technologies, leading to improved efficiency, safety, and cost-effectiveness in multiple industries and critical scenarios.

2.1.1 Cell decomposition

In this method, a set of simple cells are obtained by decomposing the free configuration space. The relationships among the adjacent cells are then computed. The cells housing the start and the goal locations of the mobile robot are identified so as to generate a collision-free optimal path by using a sequence of connected cells to connect them [15, 16]. Figure 3 presents an example of cell decomposition.

Figure 3.

Cell decomposition [16].

2.1.2 Potential field

The concept of this method was first introduced in [17]. A robot in this method is considered as a point in a configuration space that is subjected under the action of an artificial potential function (U) whose variations are seen as the structure of the free space. The potential function is defined as the summation of the attractive and repulsive potentials that respectively pull the robot toward the goal configuration and push the robot away from the obstacles. The results of the potential function lead the robot to the goal destination [18].

U=Faq+FrqE1

Where Fa is the attractive force that pulls the robot to the goal destination, while Fr is the repulsive force that pushes the robot from the obstacles [19].

Faq=12kaqqf2E2

Where q is the current state of the robot, ka is the attractive proportional gain, and qf is the coordinate of the goal location.

Frq=12ka1p1p02ifpp00ifp>p0E3

Where p is the distance of the robot to the nearest obstacle, p0 is the distance limit of the repulsion, and kr is the repulsive proportional gain.

The application of this method and modified versions are found in motion controller for obstacle avoidance of robots [20].

2.1.3 Road map

This method is also referred to as a retraction approach. In this approach, a set of possible motions are retracted and mapped onto a one-dimensional network of lines. This method is a graph searching since the solution is only restricted to the network. The famous roadmaps are discussed below.

Visibility graph: this involves collection of lines that connect a feature of an object to another object in the configuration space. These features in their principal form are vertices of obstacles (polygonal shapes). In this approach, the number of edges is defined by On2. This can be constructed in a 2D configuration space and in On2, where n denotes the number of features. The visibility graph is used for motion planning of mobile robots [21]. Figure 4 presents the visibility graph:

Figure 4.

Visibility graph [15].

Voronoi diagram: in this method, as shown in Figure 5, cells are obtained by partitioning the configuration space. Each cell consists points that are closer to a particular object in the space than any other. Voronoi diagram has been applied for robot motion planning [23].

Figure 5.

Voronoi diagram [22].

Silhouette method: In Refs. [24, 25], this method was developed in arbitrary dimensions to construct a roadmap by projecting an object from a higher to lower dimensional space. The projection boundary curves are then traced out.

2.1.4 Sub-goal network

In this method, a list of reachable formations from start to the goal destination are maintained. The motion planning is only solved when the goal destination is reachable. A local motion planning algorithm (local operator) is used to determine the reachability of one formation from another by moving the robot to the target goal in a straight line [26]. Figure 6 presents sub-goal graphs on a grid:

Figure 6.

Sub-goal graphs on grid [27].

2.1.5 Dijkstra’s algorithm

Dijkstra’s algorithm is a classic and widely used pathfinding algorithm for finding the shortest path between two points in a graph. It is suitable for mobile robot path planning in scenarios where the environment can be represented as a graph, such as grid-based or road networks [28, 29].

However, it has heavy memory because of the computation of all possible outcomes for the determination of the shortest path especially in large and complex environments [29].

2.2 Heuristic approaches

Heuristic techniques leverage domain-specific knowledge or rules to guide the search for a feasible path efficiently. They sacrifice completeness and optimality to gain computational speed, making them suitable for real-time applications [30]. Examples include Dijkstra’s algorithm, A* (A-star), D* (D-star), and Genetic algorithm.

2.2.1 A-star algorithm

The A* algorithm is a popular and widely used pathfinding algorithm for finding the shortest path between a starting point and a goal in a graph or grid-based environment. It efficiently combines elements of Dijkstra’s algorithm (breadth-first search) and Greedy Best-First Search to achieve optimal pathfinding with reduced computational cost. Its operation is such that it works based on its lowest cost path tree from the start point to the final point [31]. The f-value of a node is defined as the sum of the cost function (g), and the heuristic function (h) for that node is given as:

fn=gn+hnE4

Where gn is the cost function to track the actual cost of reaching a node from the starting point, and hn is the heuristic function that estimates the cost from the current node to the goal node.

A* algorithm has many variants, and they are computationally timesaving based on the accuracy of their heuristic function. Its efficiency and optimality make it a popular choice for mobile robot path planning, especially in grid-based environments and scenarios where finding the shortest path is crucial.

2.2.2 D* algorithm

The D* algorithm is a popular path planning algorithm designed for dynamic environments, where the cost of traversing a particular path can change over time due to the presence of moving obstacles or changes in the environment. It is an improved version of the A* algorithm, specifically tailored to address the challenges of re-planning paths in such dynamic scenarios [32].

fn=hnE5

The D* algorithm’s ability to handle dynamic environments and its efficiency in updating paths in real-time make it well-suited for mobile robot path planning in scenarios where the environment is subject to frequent changes or where re-planning is essential to ensure safe and efficient navigation [33].

2.2.3 Genetic algorithm

Genetic algorithm (GA) was introduced in [34] as an evolutionary technique that utilized the advantage operators like natural selection, crossover, and mutation in its search process [35]. Selection operator is utilized in ranking chromosomes on the basis of fitness (i.e., distances of chromosomes from goal) and selecting chromosomes with the minimum path length to generate new solutions. Crossover operator is then utilized to generate a new solution from the selected chromosomes. The crossover operator splits the selected chromosomes and generates new solutions by exchanging their parts. Mutation operator is utilized to randomize the chosen chromosome(s). This operator is typically used whenever the solution converges toward local minima or whenever a certain generation needs performance improvement as a result of poor genetic diversity [36, 37].

2.3 Artificial intelligence approaches

The classical approaches have disadvantages like high computation cost, applicability to only 2D, and trapping in local minima [8, 10, 38]. Also, path planning is a non-deterministic polynomial time hard problem [10]. Thus, metaheuristic search techniques are better techniques for solving this type of problem.

2.3.1 Particle swarm optimization algorithm

Particle swarm optimization algorithm was developed by Eberhart and Kennedy in [35]. The algorithm is a nature-inspired search algorithm that mimics the social behavior of a group of birds or fish schooling [39, 40]. This algorithm belongs to the class of population-based stochastic search technique and is applied by researchers in solving global optimization problems. During the search process of the algorithm, the swarm of particles achieves the objective of obtaining the optimal solution by sharing common information across each member in the swarm. This enables them to globally move together, knowing the position of each at every step of the particles [1, 30, 41].

2.3.2 Ant colony optimization algorithm

Proposed by Marco Dorigo in 1992 as ant system, ant colony optimization is a population-based stochastic search approach used to solve combinatorial optimization problems. It is a nature-inspired algorithm that mimics ants’ foraging behavior and their inherent ability of obtaining minimum path length while searching for food sources [6, 42, 43]. Naturally, ants are blind, and they tend to move randomly when searching for food. Ants return to their nest by dropping a chemical pheromone trail that helps them generate the shortest path to their nest from the food source, thereby increasing the probability of that path being followed by other ants [44].

2.3.3 Cuckoo search algorithm

Yang and Deb [45] developed this metaheuristic search algorithm by mimicking the characteristics of brood parasitism of some cuckoo species. Three idealized rules were developed for modeling the algorithm. The first rule deals with the process initialization in which each cuckoo’s egg is laid and dumped in a randomly selected nest. The second rule deals with the search process. In this rule, the fittest nest will be passed over to the next generations. The number of host nests is fixed. The final rule deals with the probability of discovering a cuckoo’s egg. The probability of discovering a cuckoo’s egg should always be between 0 and 1 [45, 46].

2.3.4 Bat algorithm

Yang in 2010 developed this search algorithm as a nature-inspired algorithm. This algorithm mimics the echolocation behavior of micro bats [47]. Micro bats emit ultrasonic while searching for food to detect their preys and the presence of obstacles along their search path. They also use it in dark places to detect cracks in their nests. The ultrasonic sound is usually emitted at the rate of 10 to 200 times per second. The reflected sound after striking the chase or obstacles is called echo. Micro bats navigate the environment by using the time delay to receive the echo to detect an obstacle-free motion path, the distance to the obstacle, and the type of chase. They also use the variations of Doppler effect to differentiate target insects [38, 47, 48].

2.3.5 Artificial neural network

This is a learning algorithm that mimics the human brain’s working mechanism. It is designed to emulate the learning process of computational elements called neurons. It consists of input, hidden, and output layers. These layers are interconnected through links known as synaptic weights. Synaptic weights are a set of parameters that are adapted so that the artificial neural network can vary its behavior with respect to the problem to be addressed. The artificial neural network is trained with a supervised learning technique that utilizes back propagation algorithm. The network outputs a model that can be applied for controlling the movement of mobile robots from one location to another while avoiding obstacles in an autonomous manner [49, 50, 51].

2.3.6 Fuzzy logic controller

This type of controller has been successfully applied to address various industrial problems. It has three basic components: Fuzzification (input), fuzzy inference (set of linguistic IF – THEN rules), and defuzzification (output). For a path-planning application, the set of linguistic rules that form the fuzzy inference are modeled based on the behavior of the robot. The controller can be used for the navigation of the autonomous robot especially when navigating from a source location to a target destination in an environment with obstacles [52, 53, 54].

In summary, the choice of the path-planning approach depends on the specific characteristics of the environment, the computational resources available, and the desired level of optimality. Researchers continue to explore and develop novel techniques to improve the efficiency and effectiveness of mobile robot path planning in various practical scenarios.

Advertisement

3. Performance metrics

Performance metrics of path-planning approaches of mobile robots in solving path-planning problems can be evaluated quantitatively. Figure 7 is the representation of a path-planning problem.

Figure 7.

Path planning problem [12].

Figure 6 is the graphical representation of a path-planning problem where the red square is the start location and the green diamond is the goal location. The obstacles were represented with blue rectangles of different sizes, randomly generated and positioned in the environment. The task of the mobile robot is to reach the goal location via a collision-free optimal path using one or a combination of the following performance metrics in evaluating the paths:

3.1 Time

This is the time taken by a robot to move from the start to the goal location. For simulation MATLAB, it is recorded by the difference between the value of the MATLAB command tic and toc, which respectively record the start and end time of a running program. The time taken is then displayed in the command line interface.

3.2 Obstacle avoidance efficiency

This deals with the efficiency of the robot in avoiding obstacle(s) in an environment.

3.3 Path length

Path Length (PL) is the total distance covered by the robot from the start location xsysto the goal location xgyg. The PL of the trajectory in an x-y plane is computed as:

PL=i=1n1xi+1xi2+yi+1yi2E6

3.4 Energy consumption

This is the amount of energy used by the robot in moving from the start location to the goal location. The size of the environment, onboard equipment, weight of the robot, air drag, nature of the road surface, and motion of the actuators are some of the factors that determine the amount of consumed energy.

3.5 Smoothness

This is the measure of time and energy requirement for the motion of a robot. The smoothness of UGV’s movement is computed as a function of curvature (k) using bending energy (BE). The curvature of curves at any point, say xiyi,across a trajectory in an x-y plane is computed as

kxiyi=fxi1+fyi232E7

The BE is computed mathematically as presented as:

BE=1ni1nk2xiyiE8

The distribution of the performance metrics based on some selected literatures is presented in Table 1.

AuthorWhat was donePerformance metrics
[1]Developed an obstacle avoidance scheme-based elite opposition bat algorithm for unmanned ground vehiclesPath length and time
[2]Developed optimal path-planning technique using elite opposition-based bat algorithm for mobile robotsElapsed time
[3]A directed artificial bee colony to solve the problem of path planning by using the present direction of the fittest bee to move other bees toward the optimal positionShortest distance
[6]Developed a dynamic path planning technique for autonomous navigation of mobile robot in an unknown static environmentElapsed time
[7]Developed an evolutionary approach for mobile robot path planning in a complex environmentSuccess rate
[8]A new ant–based path planning approach that considers unmanned ground vehicle energy consumption in its planning strategyEnergy, time, travel length, and computational time
[10]A path-planning algorithm of mobile robots using bacteria foraging optimization techniqueMinimum time
[11]Developed a graphical user interface for the path planning of mobile robots using a modified bat algorithm in a 2D environment containing rectangular static obstaclesMinimum time
[12]Developed a dynamic planning algorithm-based modified bat algorithm for mobile robots in an unknown static environmentElapsed time
[13]A global path planning using modified firefly algorithmShortest distance
[14]A global real-time optimal path planning of mobile robots in an environment with a moving target based on artificial immune approachShortest distance and minimum time
[15]A smooth local path planning algorithm based on modified visibility graphPath length, time, planning time
[16]A safe path planning using cell decomposition approximationSafety
[18]Developed an optimal path planning for unmanned ground vehicles using potential field method and optimal control methodTime
[21]Developed a visibility-polygon search and Euclidean shortest pathsTime
[22]A fast-global flight path-planning algorithm based on space circumscription and sparse visibility graph for unmanned aerial vehiclePath length and time
[27]Feasibility study: Sub-goal graphs on state latticesTime
[28]Application of the Dijkstra algorithm in robot path planningPath length
[29]Global path planning for mobile robots based on artificial bee colony and Dijkstra’s algorithmsPath length
[30]Comparison of BAT with PSO for path-planning problemsPath length and Time
[31]Mobile robot path-planning algorithm based on improved A starPath length and smooth path
[32]Path-planning algorithm using D* heuristic method based on PSO in a dynamic environmentPath length
[36]An improved genetic algorithm-based path-planning approach for autonomous robotsNumber of turns and minimum time
[37]A path-planning technique using a modified genetic algorithm for a mobile robotShortest distance and safety
[55]A global mobile robot path planning in a dynamic environment with obstacles of different shapes and sizesShortest distance and minimum time
[56]An ant colony optimization path planning of an autonomous robot in a dynamic environment with rectangular obstaclesMinimum time
[57]A metaheuristic optimization-based algorithm to solve path-planning problems of mobile robots in an unknown environmentMinimum time
[58]Compared bat algorithm with cuckoo search for mobile robot path planning in an environment with static obstaclesShortest distance and minimum time
[59]Applied cuckoo search algorithm for solving path planning of mobile robots in different environments with static obstacles.Distance and time
[60]A modified particle swarm optimization for time optimal path planning of unmanned ground vehicle with solar power schedulesMinimum time
[61]A lane-level path-guiding method for unmanned ground vehicles in a structured road environmentTraffic rules
[62]An image processing and reinforcement learning-based path planning technique for mobile robotsShortest distance
[63]A path-planning technique for mobile robots using a set of surrounding points and path improvementShortest and smoothest path
[64]A novel path-planning technique of mobile robots using fuzzy image processing in a 2D map containing obstaclescomputational time
[65]A modified ant colony optimization algorithm-based path-planning software tool for 2D environments containing obstaclesMinimum time
[66]Developed a path-planning technique for mobile robots’ obstacle avoidanceShortest distance
[67]Developed a hybrid planning algorithm by fusing A* algorithm with Voronoi diagram for non-holonomic autonomous vehiclesTime
[68]Developed a hybrid algorithm for path planning of mobile robots in static and dynamic environments.smoothness, path length and safety
[69]Developed a hybrid optimization path-planning algorithm for autonomous mobile robots in static and dynamic environments.Traveling distance
[70]A dynamic path-planning technique for autonomous driving with the mission of avoiding obstacles on various roadsShortest distance
[71]Comparison between two meta-heuristic algorithms for path planning in roboticsTime

Table 1.

Distribution of performance metrics.

The summary of the performance metrics as reported in Table 1 is shown in Table 2:

S/NPerformance metricPaper(s)
1Time[2, 6, 8, 10, 11, 12, 14, 15, 18, 21, 22, 27, 30, 36, 55, 56, 57, 58, 59, 60, 64, 65, 67, 71]
2Distance[1, 3, 8, 13, 14, 15, 22, 28, 29, 30, 31, 32, 37, 55, 58, 59, 62, 63, 66, 68, 69, 70]
3Energy[8]
4Safety[16, 37, 68]
5Smooth path[31, 63, 68]

Table 2.

Summary of the performance metrics.

Figure 8 presents a pictorial representation of the highest- and lowest-used performance metrics for different path planning approaches in the reviewed literature. The performance metrics depicted in the figure encompass various aspects, such as path length, computation time, energy consumption, and other relevant criteria.

Figure 8.

Performance metrics distribution.

It can be seen from Figure 8 that distance (path length) and time are the most commonly used performance evaluation criteria for path-planning approaches, while energy consumption is the least-used criterion.

Advertisement

4. Literature review

The review in this section is focused on the use path-planning approaches on mobile robots. Different research has been investigated and reported as follows:

In Ref. [55], a global mobile robot path planning in a dynamic environment with obstacles of different shapes and sizes. The path-planning algorithm was developed using the direction concept, which is capable of handling static obstacles, and the waiting time concept, which is capable of handling moving obstacles.

In Ref. [56], an ant colony optimization path planning of an autonomous robot in a dynamic environment with 20 rectangular obstacles randomly generated. In the experiment, a robot of asterisk structure was assumed, where the source was of a square shape and the target was of a diamond shape in a moving space of 160*160 cm2.

In Ref. [14], a global real-time optimal path planning of mobile robot in an environment with a moving target based on artificial immune approach. A MAKLINK simulation environment was developed, and Dijkstra is then applied to determine the suboptimal path of the mobile robot.

In Ref. [57], a metaheuristic optimization-based algorithm to solve path planning problem of mobile in an unknown environment consisting of 20 randomly generated obstacles. The path-planning algorithm was based on ant colony optimization, and its performance was compared with that of a particle swarm optimization algorithm.

In Ref. [3], a directed artificial bee colony to solve the problem of path planning by using the present direction of fittest bee to move other bees toward the optimal position.

In Ref. [10], a path-planning algorithm of mobile robots using the bacteria foraging optimization (BFO) technique. The developed technique was used to determine an obstacle-free motion path for a robot moving toward the target in a dynamic environment.

In Ref. [58], the bat algorithm was compared with cuckoo search for mobile robot path planning an environment with 20 static obstacles. Simulation was done using MATLAB; the algorithms were compared by increasing the number of populations.

In Ref. [30] showed the growth of path planning by comparing two algorithms of initial and recent phases, in which one is the particle swarm optimization (PSO) algorithm, while the other is the bat algorithm.

In Ref. [59] applied the cuckoo search algorithm for solving path planning of mobile robots in different environments with static obstacles. Based on the behavior of robots with respect to obstacle avoidance and goal seeking, a new objective function was formulated.

In Ref. [71] compared the performance of two path-planning algorithm-based ABC and PSO in a static environment containing obstacles. The performance of the planning algorithms was evaluated by varying the number of populations, and the time taken by the robot to reach the target is recorded.

In Ref. [60], a modified particle swarm optimization for time optimal path planning. The path planning algorithm was applied to an unmanned ground vehicle with solar power schedules. The electrical component of the unmanned ground vehicle was driven by its power, while the solar energy harvested by the unmanned ground vehicle was strictly used for the mission’s energy constraints.

In Ref. [37] presented a path-planning technique using a modified genetic algorithm for a mobile robot. The square map simulation environment was modeled so as to reflect a real environment.

In Ref. [61] presented a lane-level path-guiding method for unmanned ground vehicles (UGV) in a structured road environment. A lane-level digital map was built to present lanes and segments of a road with respect to traffic rules.

In Ref. [62] presented an image processing and reinforcement learning-based path-planning technique for mobile robots. The algorithm and image processing were implemented in MATLAB and transferred to the mobile robot.

In Ref. [63] presented a path-planning technique for mobile robots using a set of surrounding points and path improvements. The developed technique was tested on 10 maps with different starting points, target points, and number of obstacles.

In Ref. [8] proposed a new ant-based path-planning approach that considers unmanned ground vehicle energy consumption in its planning strategy. In the work, the energy prediction model was incorporated into an ant-based algorithm to reach the target goal by providing the collision-free shortest path with low power consumption.

In Ref. [64] presented a novel path planning technique of mobile robot using fuzzy image processing in a 2D map containing obstacles. The fuzzy rules and membership functions were optimized using bacterial. A modified genetic algorithm with enhanced A* algorithm was used to obtain energy consumption, security, minimum traveling time, and safety for the mobile robot.

In Ref. [36] presented an improved genetic algorithm (GA)-based path-planning approach for autonomous robots. The developed path-planning approach was implemented on a 2D grid simulation environment.

In Ref. [65] presented a modified ant colony optimization (ACO) algorithm-based path-planning software tool for 2D environments containing obstacles.

In Ref. [64] presented a dynamic path-planning technique for autonomous driving with the mission of avoiding obstacles on various roads. The developed technique also obtains appropriate vehicle speed and acceleration to enable maneuvering around obstacles.

In Ref. [2] developed an optimal path-planning algorithm using elite opposition-based bat algorithm (EOBA) for mobile robots. The EOBA was developed by diversifying the exploration phase of the bat algorithm so as to increase the diversity of the solutions in the search space. The inertia weight was introduced at the local search phase to balance the exploration and exploitation.

In Ref. [66] developed a path-planning technique for mobile robots’ obstacle avoidance. The technique was developed by modifying the artificial potential field algorithm so as to avoid been trapped in local minima. The modified algorithm can guide the robot to the target location through an optimal path without colliding with obstacles.

In Ref. [6] developed a dynamic path-planning technique for autonomous navigation of mobile robots in an unknown static environment. An objective function was modeled in the form of distance function using the coordinate of the start and goal locations. A dynamic path-planning algorithm was then applied to solve the optimization problem, which generates an optimal collision-free motion path for autonomous navigation of the mobile robot.

In Ref. [67] fused A* algorithm with Voronoi diagram for solving path planning of non-holonomic autonomous vehicles. The Voronoi diagram generates guiding waypoints that were optimized by the A* algorithm to generate the shortest path for the autonomous vehicles regardless of the constraints.

In Ref. [68] developed a hybrid algorithm for path planning of mobile robots. Membrane-inspired algorithm, pseudo bacteria genetic algorithm, and artificial potential field were hybridized to form a membrane pseudo bacterial potential field algorithm.

In Ref. [11] developed a graphical user interface for path planning of mobile robots using a modified bat algorithm in a 2D environment containing rectangular static obstacles. The modified bat algorithm was utilized as the navigational guidance controller that guided the mobile robot based on the echolocation behavior of bats. The development of the GUI software makes it easier to implement path planning of mobile robots as the user is provided with the opportunity to define environment variables without having any knowledge of programming.

In Ref. [12] developed a dynamic planning algorithm-based modified bat algorithm for mobile robots. An objective function was modeled based on the distance of the robot to the goal location and to the nearest obstacles. The dynamic planning algorithm optimized the paths of the mobile robots based on this function in others to generate a collision-free optimal path.

In Ref. [69] developed hybrid optimization path-planning algorithm for a mobile robot in static and dynamic environments. The hybrid algorithm is a combination of PSO and modified frequency BA. A multi-objective optimization problem was formulated based on the shortest distance and path smoothness, which was optimized by the developed path planning algorithm to generate an optimal collision path.

In Ref. [48] developed an obstacle avoidance scheme-based elite opposition bat algorithm for unmanned ground vehicles. The obstacle avoidance system comprises a simulation map, a perception system for obstacle detection, and implementation of EOBA for generating an optimal collision-free path that led the UGV to the goal location. Three distance thresholds of 0.1 m, 0.2 m, and 0.3 m were used in the obstacle detection stage, while 0.3 m was determined as the optimal distance threshold for obstacle avoidance.

Table 3 presents the summary of the path-planning approaches based on the literatures reviewed.

ClassificationPath planning approachReference
ClassicalCell decomposition[16]
Visibility graph[15, 21, 22]
Dijkstra algorithm[28, 29]
Artificial Potential Field[18, 66]
Subgoal graphs[27]
set of surrounding point and path improvement algorithm[63]
HeuristicsGenetic algorithm[7, 36, 37]
A* algorithm[31]
D* algorithm[32]
Artificial intelligenceBat algorithm[1, 2, 6, 11, 12, 30, 58]
Particle swarm optimization algorithm[30, 32, 57, 60, 71]
Ant colony optimization[8, 56, 57, 65]
Artificial bee colony[3, 29, 71]
Firefly algorithm[13]
Bacteria foraging[10]
Cuckoo search algorithm[58, 59]
Artificial immune algorithm[14]
Fuzzy logic controller[64]
Reinforcement learning[62]
Hybrid methodsHybrid A* algorithm with Voronoi diagram[67]
Hybrid pseudo-bacterial potential field algorithm[68]
Hybridized particle swarm optimization-modified frequency bat algorithm[69]

Table 3.

Distribution of path planning approaches.

Figure 9 presents a clear distribution of the path-planning approaches based on the reviewed literature.

Figure 9.

Distribution of path planning approaches.

It can be seen from Figure 9 that the artificial intelligence-based path planning approach emerges as the most frequently used technique, guiding mobile robots to their target destinations while effectively avoiding collisions with obstacles.

This prominence of artificial intelligence-based approaches can be attributed to their versatility and robustness in addressing various path-planning challenges. Leveraging learning capabilities and intelligent decision-making, these techniques enable mobile robots to adapt to dynamic environments, learn from past experiences, and efficiently navigate through complex terrains.

Out of the 44 reviewed literatures, 26 (59%) studies employed artificial intelligence-based path planning, showcasing its widespread acceptance and effectiveness in the field.

The dominance of artificial intelligence-based approaches underscores their potential to revolutionize mobile robot navigation, driving advancements in autonomous robotics and expanding the scope of practical applications in industries such as logistics, transportation, search and rescue, surveillance, and service robotics.

Advertisement

5. Conclusion

This review investigated the applications of different path-planning approaches for a mobile robot operating in a known or partially known environment with obstacles and defined start and goal locations. The path-planning problem aims to find an optimal or feasible path that allows the mobile robot to navigate from its starting position to the target destination while avoiding collisions with obstacles. It is evident from the reviewed literatures that considerable research attention has been given to the field of path planning for mobile robots. Researchers have developed various approaches to generate optimal paths, considering criteria such as path length, cost, time, and energy consumption. Among the classes of the path-planning approaches reported in the literature, artificial intelligence-based techniques stand out as the most frequently used method for generating collision-free motion paths, owing to their promising performance and adaptability.

It is also evident that the artificial intelligence-based approaches have utilized to enhance classical and heuristic-based methods, improving the overall efficiency and effectiveness of mobile robot path planning. By leveraging learning capabilities and intelligent decision-making, these techniques have paved the way for more advanced and autonomous robot navigation.

Despite the significant progress made in the field of path planning of mobile robots, it is clear that the current approaches do not give sufficient consideration to cost and energy consumption of mobile robots in path optimization. As mobile robots become more prevalent in various applications, optimizing cost and energy efficiency becomes increasingly critical.

Therefore, there is a clear need for the development of new path-planning approaches that place a strong emphasis on generating optimal paths while minimizing cost and energy consumption. Future research efforts should focus on exploring novel techniques that integrate these performance criteria into the path-planning process.

By addressing these challenges and advancing the field of mobile robot path planning, we can unlock the full potential of mobile robots, enabling them to navigate efficiently and safely in diverse and dynamic environments.

References

  1. 1. Haruna Z, Mu’azu MB, Sha’aban YA, Adedokun EA. Obstacle avoidance scheme based elite opposition bat algorithm for unmanned ground vehicles. Covenant Journal of Information and Communication Technology. 2021;9(1):1-15
  2. 2. Haruna Z, Mu’azu MB, Oyibo P, Tijani SA. Development of an optimal path planning using elite opposition based bat algorithm for a mobile robot. Yanbu Journal of Engineering and Science. 2021;16(1):1-9
  3. 3. Abbas NH, Ali FM. Path planning of an autonomous mobile robot using directed artificial bee colony algorithm. International Journal of Computers and Applications. 2014;96(11):11-16
  4. 4. Alanezi MA, Haruna Z, Sha’aban YA, Bouchekara HREH, Nahas M, Shahriar MS. Obstacle avoidance-based autonomous navigation of a quadrotor system. Drones. 2022;6(10):288
  5. 5. Ali ZA, Zhangang H. Multi-unmanned aerial vehicle swarm formation control using hybrid strategy. Transactions of the Institute of Measurement and Control. 2021;43(12):2689-2701
  6. 6. Haruna Z, Musa U, Mu’azu MB, Umar A. A dynamic path planning technique for autonomous mobile robot in unkwown static environment. In: IEEE 1st International Conference on Mechatronics, Automation & Cyber-Physical Computer Systems (MAC 2019). Owerri, Nigeria: IEEE; 2019. pp. 36-41
  7. 7. Hosseinzadeh A, Izadkhah H. Evolutionary approach for mobile robot path planning in complex environment. International Journal of Computational Science and Engineering. 2010;7(4):1
  8. 8. Jabbarpour MR, Zarrabi H, Jung JJ, Kim P. A green ant-based method for path planning of unmanned ground vehicles. IEEE Access. 2017;5:1820-1832
  9. 9. Reshamwala A, Vinchurkar DP. Robot path planning using an ant colony optimization approach: A survey. International Journal of Advanced Research in Artificial Intelligence. 2013;2(3):65-71
  10. 10. Hossain MA, Ferdous I. Autonomous robot path planning in dynamic environment using a new optimization technique inspired by bacterial foraging technique. Robotics and Autonomous Systems. 2015;64:137-141
  11. 11. Haruna Z, Abdurrazaq MB, Umar A, Musa U. A Graphical User Interface for Path Planning of Mobile Robot. Ife Journal of Science and Technology. 2019;3(1):60-73. Available from: www.ifejost.org
  12. 12. Haruna Z, Musa U, Mu’azu MB, Umar A. A path planning technique for autonomous mobile robot. International Journal of Mechatronics, Electrical and Computer Technology. 2020;10(35):4483-4492. Available from: https://www.aeuso.org/
  13. 13. Chen X, Zhou M, Huang J, Luo Z. Global path planning using modified firefly algorithm. In: 2017 International Symposium on Micro-NanoMechatronics and Human Science (MHS). Nagoya, Japan: IEEE; 2017. pp. 1-7
  14. 14. Eslami A, Asadi S, Soleymani GR, Azimirad V. A real-time global optimal path planning for mobile robot in dynamic environment based on artificial immune approach. GSTF Journal on Computing. 2014;2(1):104-109
  15. 15. Lv T, Feng M. A smooth local path planning algorithm based on modified visibility graph. Modern Physics Letters B. 2017;31(19–21):1740091
  16. 16. Abbadi A, Přenosil V. Safe path planning using cell decomposition approximation. Distance Learning, Simulation and Communication. 2015;8:1-6
  17. 17. Khatib O. Real-time obstacle avoidance for manipulators and mobile robots. International Journal of Robotics Research. 1986;5(1):90-98
  18. 18. Mohamed A, Ren J, Sharaf AM, EI-Gindy M. Optimal path planning for unmanned ground vehicles using potential field method and optimal control method. International Journal of Vehicle Performance. 2018;4(1):1-14
  19. 19. Ali ZA, Han Z. Path planning of hovercraft using an adaptive ant colony with an artificial potential field algorithm. International Journal of Modelling, Identification and Control. 2021;39(4):350-356
  20. 20. Subramanian S, George T, Thondiyath A. Obstacle avoidance using multi-point potential field approach for an underactuated flat-fish type AUV in dynamic environment. In: Trends in Intelligent Robotics, Automation, and Manufacturing: First International Conference, IRAM 2012, Kuala Lumpur, Malaysia, November 28-30, 2012. Proceedings. Kuala Lumpur, Malaysia: Springer; 2012. pp. 20-27
  21. 21. Asano T, Asano T, Guibas L, Hershberger J, Imai H. Visibility-polygon search and euclidean shortest paths. In: 26th Annual Symposium on Foundations of Computer Science (SFCS 1985). Portland, OR, USA: IEEE; 1985. pp. 155-164
  22. 22. Majeed A, Lee S. A fast global flight path planning algorithm based on space circumscription and sparse visibility graph for unmanned aerial vehicle. Electronics. 2018;7(12):375
  23. 23. Canny J. A Voronoi method for the piano-movers problem. In: Proceedings. 1985 IEEE International Conference on Robotics and Automation. Vol. 2. MDPI; 1985. pp. 530-535
  24. 24. Canny J, Reif J. New lower bound techniques for robot motion planning problems. In: 28th Annual Symposium on Foundations of Computer Science (sfcs 1987). Los Angeles, CA, USA: IEEE; 1987. pp. 49-60
  25. 25. Canny J. The Complexity of Robot Motion Planning. London, England: The MIT Press; 1988
  26. 26. Faverjon B, Tournassoud P. A local based approach for path planning of manipulators with a high number of degrees of freedom. In: Proceedings. 1987 IEEE International Conference on Robotics and Automation. Vol. 4. Raleigh, NC, USA; IEEE; 1987. pp. 1152-1159
  27. 27. Uras T, Koenig S. Feasibility study: Subgoal graphs on state lattices. Proceedings of the International Symposium on Combinatorial Search. 2017;8(1):100-108
  28. 28. Wang H, Yu Y, Yuan Q. Application of Dijkstra algorithm in robot path-planning. In: 2011 Second International Conference on Mechanic Automation and Control Engineering. Hohhot: IEEE; 2011. pp. 1067-1069
  29. 29. Szczepanski R, Tarczewski T. Global path planning for mobile robot based on Artificial Bee Colony and Dijkstra’s algorithms. In: 2021 IEEE 19th International Power Electronics and Motion Control Conference (PEMC). Gliwice, Poland: IEEE; 2021. pp. 724-730
  30. 30. Gigras Y, Vasishth O. Comparison of BAT with PSO for path planning problems. International Journal of Engineering Research and Development. 2015;3(2):590-595
  31. 31. Zhang L, Li Y. Mobile robot path planning algorithm based on improved a star. Journal of Physics: Conference Series. 2021;1848(1):12013
  32. 32. Raheem FA, Hameed UI. Path planning algorithm using D* heuristic method based on PSO in dynamic environment. American Scientific Research Journal for Engineering, Technology and Sciences. 2018;49(1):257-271
  33. 33. Stentz A. The D* Algorithm for Real-Time Planning of Optimal Traverses. Pittsburgh, Pennsylvania: Carnegie Mellon University, the Robotics Institute; 1994
  34. 34. Holland JH. Adaptation in Natural and Artificial Systems: An Introductory Analysis with Applications to Biology, Control, and Artificial Intelligence. London, England: The MIT Press; 1992
  35. 35. Eberhart R, Kennedy J. A new optimizer using particle swarm theory. In: MHS’95. Proceedings of the Sixth International Symposium on Micro Machine and Human Science. Nagoya, Japan: IEEE; 1995. pp. 39-43
  36. 36. Lamini C, Benhlima S, Elbekri A. Genetic algorithm based approach for autonomous mobile robot path planning. Procedia Computer Science. 2018;127:180-189
  37. 37. Sahu D, Mishra AK. Mobile robot path planning by genetic algorithm with safety parameter. International Journal of Engineering and Computer Science. 2017;7(8):14723-14727
  38. 38. Haruna Z, Mu’azu MB, Abubilal KA, Tijani SA. Development of a modified bat algorithm using elite opposition—Based learning. In: 2017 IEEE 3rd International Conference on Electro-Technology for National Development (NIGERCON). Owerri, Nigeria: IEEE; 2017. pp. 144-151
  39. 39. Ali ZA, Han Z, Masood RJ. Collective motion and self-organization of a swarm of UAVs: A cluster-based architecture. Sensors. 2021;21(11):3820
  40. 40. Garba I, Sha’aban YA, Mu’azu MB, Haruna Z. Crone controller based speed control of permanent magnet direct current motor. In: 2019 2nd International Conference of the IEEE Nigeria Computer Chapter (NigeriaComputConf). Zaria, Nigeria: IEEE; 2019. pp. 1-8
  41. 41. Vallade B, Nakashima T. Improving particle swarm optimization algorithm and its application to physical travelling salesman problems with a dynamic search space. Applied Computing & Information Technology. 2014;553:105-119
  42. 42. Dorigo M, Blum C. Ant colony optimization theory: A survey. Theoretical Computer Science. 2005;344(2–3):243-278
  43. 43. Ali ZA, Zhangang H, Hang WB. Cooperative path planning of multiple UAVs by using max–min ant colony optimization along with cauchy mutant operator. Fluctuations and Noise Letters. 2021;20(01):2150002
  44. 44. Tian J, Yu W, Xie S. An ant colony optimization algorithm for image edge detection. In: 2008 IEEE Congress on Evolutionary Computation (IEEE World Congress on Computational Intelligence). Vol. 2008. Hong Kong, China: IEEE; 2008. pp. 751-756
  45. 45. Yang X-S, Deb S. Cuckoo search via Lévy flights. In: 2009 World Congress on Nature & Biologically Inspired Computing (NaBIC). Coimbatore, India: IEEE; 2009. pp. 210-214
  46. 46. Audee SY, Mu’azu MB, Sani M-Y, Haruna Z, Salawudeen AT, Prosper O. Development of a dynamic cuckoo search algorithm. Covenant Journal of Informatics and Communication Technology. 2019;7(2):66-83
  47. 47. Yang X-S. A new metaheuristic bat-inspired algorithm. In: Nature Inspired Cooperative Strategies for Optimization (NICSO 2010). Vol. 2010. Berlin, Heidelberg: Springer; 2010. pp. 65-74
  48. 48. Haruna Z, Mu’azu MB, Abubakar YS, Adedokun EA. Path tracking control of four wheel unmanned ground vehicle using optimized FOPID controller. In: 2021 International Conference on Electrical, Communication, and Computer Engineering (ICECCE). Kuala Lumpur, Malaysia: IEEE; 2021. pp. 1-6
  49. 49. Bassil Y. Neural network model for path-planning of robotic rover systems. arXiv Prepr. arXiv1204.0183. Vol. 2. 2012. pp. 94-100
  50. 50. Lippmann R. Book review: Neural networks, a comprehensive foundation, by simon haykin. International Journal of Neural Systems. 1994;5(04):363-364
  51. 51. Jin L, Li S, Yu J, He J. Robot manipulator control using neural networks: A survey. Neurocomputing. 2018;285:23-34
  52. 52. Abdessemed F, Benmahammed K, Monacelli E. A fuzzy-based reactive controller for a non-holonomic mobile robot. Robotics and Autonomous Systems. 2004;47(1):31-46
  53. 53. Das T, Kar IN. Design and implementation of an adaptive fuzzy logic-based controller for wheeled mobile robots. IEEE Transactions on Control Systems Technology. 2006;14(3):501-510
  54. 54. Teymournezhad M, Sahingoz OK. Fuzzy logic-based trajectory planning for mobile robots in an uncertain and complex environment. In: 2023 2nd International Conference on Computational Systems and Communication (ICCSC). Thiruvananthapuram, India: IEEE; 2023. pp. 1-6
  55. 55. Raja P, Pugazhenthi S. Optimal path planning of mobile robots: A review. International Journal of Physical Sciences. 2012;7(9):1314-1320
  56. 56. Gigras Y, Gupta K. Ant colony based path planning algorithm for autonomous robotic vehicles. International Journal of Artificial Intelligence and its Applications. 2012;3(6):31
  57. 57. Gigras Y, Gupta K. Metaheuristic algorithm for robotic path planning. International Journal of Computers and Applications. 2014;85(3):26-29
  58. 58. Gigras Y, Gupta K, Choudhury K. A comparison between bat algorithm and cuckoo search for path planning. The International Journal of Innovative Research in Computer and Communication Engineering. 2015;3(5):4459-4466
  59. 59. Mohanty PK, Parhi DR. Optimal path planning for a mobile robot using cuckoo search algorithm. Journal of Experimental & Theoretical Artificial Intelligence. 2016;28(1–2):35-52
  60. 60. Kaplan A, Kingry N, Uhing P, Dai R. Time-optimal path planning with power schedules for a solar-powered ground robot. IEEE Transactions on Automation Science and Engineering. 2016;14(2):1235-1244
  61. 61. Yang Q, Hu J, Wang M, Yu H, Peng Q. Lane-level path guiding method for unmanned ground vehicle. In: 2017 5th International Conference on Computer, Automation and Power Electronics (CAPE). UK: Francis Academic Press; 2017. pp. 175-181
  62. 62. Roy N, Chattopadhay R, Mukherjee A, Bhuiya A, Student BT. Implementation of image processing and reinforcement learning in path planning of mobile robots. International Journal of Engineering Science. 2017;15211:15211-15213
  63. 63. Han J, Seo Y. Mobile robot path planning with surrounding point set and path improvement. Applied Soft Computing. 2017;57:35-47
  64. 64. Al-Jarrah R, Al-Jarrah M, Roth H. A novel edge detection algorithm for mobile robot path planning. Journal of Robotics. 2018;2018:1-12
  65. 65. Neydorf R, Yarakhmedov O, Polyakh V, Chernogorov I, Vucinic D. Robot path planning based on ant colony optimization algorithm for environments with obstacles. Improved Performance of Materials. 2018;72:175-184
  66. 66. Rostami SMH, Sangaiah AK, Wang J, Liu X. Obstacle avoidance of mobile robots using modified artificial potential field algorithm. EURASIP Journal on Wireless Communications and Networking. Auckland, New Zealand: IEEE: 2019;2019(1):1-19
  67. 67. Sedighi S, Nguyen D-V, Kapsalas P, Kuhnert K-D. Implementing voronoi-based guided hybrid a in global path planning for autonomous vehicles. In: 2019 IEEE Intelligent Transportation Systems Conference (ITSC). Auckland, New Zealand: IEEE; 2019. pp. 3845-3852
  68. 68. Orozco-Rosas U, Picos K, Montiel O. Hybrid path planning algorithm based on membrane pseudo-bacterial potential field for autonomous mobile robots. IEEE Access. 2019;7:156787-156803
  69. 69. Ajeil FH, Ibraheem IK, Sahib MA, Humaidi AJ. Multi-objective path planning of an autonomous mobile robot using hybrid PSO-MFB optimization algorithm. Applied Soft Computing. 2020;89:106076
  70. 70. 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. Mechanical Systems and Signal Processing. 2018;100:482-500
  71. 71. Gigras Y, Jora N, Dhull A. Comparison between different meta-heuristic algorithms for path planning in robotics. International Journal of Computers and Applications. 2016;142(3):6-10

Written By

Zaharuddeen Haruna, Muhammed Bashir Mu’azu, Abubakar Umar and Glory Okpowodu Ufuoma

Submitted: 30 July 2023 Reviewed: 31 July 2023 Published: 26 November 2023