Next Article in Journal
Balancing Data Acquisition Benefits and Ordering Costs for Predictive Supplier Selection and Order Allocation
Previous Article in Journal
Spectroscopy in Characterization of Materials—Developments
Previous Article in Special Issue
A Novel Zeroing Neural Network Control Scheme for Tracked Mobile Robot Based on an Extended State Observer
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Mobile Robot Path Planning Algorithm Based on NSGA-II

1
College of Electrical and Information Engineering, Beijing University of Civil Engineering and Architecture, Beijing 100044, China
2
Beijing Key Laboratory of Intelligent Processing for Building Big Data, Beijing 100044, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2024, 14(10), 4305; https://doi.org/10.3390/app14104305
Submission received: 7 April 2024 / Revised: 12 May 2024 / Accepted: 16 May 2024 / Published: 19 May 2024
(This article belongs to the Special Issue Intelligent Control and Robotics II)

Abstract

:
Path planning for mobile robots is a key technology in robotics. To address the issues of local optima trapping and non-smooth paths in mobile robot path planning, a novel algorithm based on the NSGA-II (Non-dominated Sorting Genetic Algorithm II) is proposed. The algorithm utilizes a search window approach for population initialization, which improves the quality of the initial population. An innovative fitness function is designed as the objective function for optimization iterations. A probability-based selection strategy is employed for population selection and optimization, enhancing the algorithm’s ability to escape local minima and preventing premature convergence to suboptimal solutions. Furthermore, a path smoothing algorithm is developed by incorporating Bézier curves. By connecting multiple segments of Bézier curves, the problem of the high computational complexity associated with high-degree Bézier curves is addressed, while simultaneously achieving smooth paths. Simulation results demonstrated that the proposed path planning algorithm exhibited fewer iterations, superior path quality, and path smoothness. Compared to other methods, the proposed approach demonstrated better overall performance and practical applicability.

1. Introduction

With the development of society, mobile robot technology is increasingly prevalent in our lives, and path planning for mobile robots is a key technology enabling them to function properly. Mobile robot path planning involves finding the optimal collision-free path according to specified constraints, which may include factors such as distance, safety, and smoothness [1]. Depending on whether the environment is known, path planning for mobile robots can be divided into global path planning [2] and local path planning [3].
Currently, the commonly used traditional path planning algorithms include the A* algorithm [4], RRT algorithm [5], Dijkstra’s algorithm [6], and artificial potential field method [7]. Intelligent path planning algorithms mainly include the ant colony algorithm [8], particle swarm algorithm [9], and genetic algorithm [10]. Intelligent algorithms are designed to mimic biological principles and are widely applied. However, they often suffer from issues such as a poor convergence precision and susceptibility to falling into local optima. Therefore, scholars both domestically and internationally have conducted extensive research on the application of intelligent algorithms. You Dazhang [11] proposed a grey wolf algorithm based on the grey wolf optimizer and grey wolf optimizer with a hybrid genetic algorithm and simulated annealing algorithm. The algorithm utilizes a nonlinear convergence factor that can be adjusted to balance the early and late stages of the algorithm. Additionally, the optimization algorithm employs an adaptive genetic crossover strategy to generate new individuals with a certain probability, thereby enhancing the diversity of the grey wolf population. In the later stages of iteration, the wolf is selected using a simulated annealing operation, to avoid the algorithm falling into local optimum. Hao Kun [12] proposed an adaptive particle swarm path planning method based on regional search to address premature convergence and local optima issues. This method preprocesses the original map using a regional search approach and adaptively adjusts the inertia weight factor and acceleration factor, allowing particles to quickly escape from adverse regions. Additionally, a dynamic obstacle avoidance strategy is employed to ensure safe navigation for the robot. Chang Jian [13] introduced an improved genetic algorithm by incorporating insertion and smoothing operators into the traditional genetic algorithm and by further integrating it with the niche method to prevent premature convergence. Davoodi [14] utilized NSGA-II to optimize the path length and clearance in grid environments, constructing both single and multi-objective optimization models for efficient path planning. Huang Zhifeng [15] proposed an enhanced lion algorithm to improve the quality of initial solutions and algorithm diversity. They employed a dual-population lion structure to enhance search capabilities and utilized fourth-order Bezier curves for path smoothing. Li [16] combined third-order Bezier curves with an improved artificial fish swarm algorithm. They initially performed morphological operations such as obstacle expansion and utilized a range of artificial fish movements based on a 16-direction, 24-field Dijkstra algorithm during the path planning process. This reduced the number of turning points, while enhancing the planning accuracy. Furthermore, they reduced the computational frequency of the fusion algorithms by incorporating a sharing mechanism and employed feedback visual fields to avoid oscillations resulting from overly large visual fields in the later stages of the algorithm. Finally, they used third-order Bezier curves to ensure directional and curvature continuity. Xue [17] used path length, path smoothness, and path safety as objective functions, and augmented the original NSGA-II algorithm with operators including an invalid solution operator and shortness operator. They systematically studied the parameters of the algorithm and compared it with an effective multi-objective evolutionary algorithm. The comparative results indicated that the improved NSGA-II generated non-dominated solutions with excellent characteristics in the solution space. Jia [18] proposed a new method for global time-varying path planning (GTVP). This method obtains center points based on the real-time shape and position information of obstacles, and extracts feature points representing obstacle information. Then, it scales up the obstacle surface to generate center points and Bezier curve feature points. Finally, it outputs curves corresponding to the real-time motion trajectory of the robotic arm. The Non-dominated Sorting Genetic Algorithms II (NSGA-II) [19] improves upon the limitations of traditional genetic algorithms, which are primarily designed for single-objective problems. Derived from genetic algorithms, NSGA-II introduces the concept of Pareto optimality and incorporates an elitist selection strategy, making it one of the most popular multi-objective genetic algorithms. It offers advantages such as a fast execution speed and good convergence of solutions, enabling it to compute better solution strategies for complex problems. As a result, this paper designed a path planning algorithm based on this method.
Bezier curves possess excellent geometric properties and find widespread application in computer graphics. They succinctly and accurately describe free-form curves and surfaces, serving as effective curve-fitting tools. Therefore, this paper proposed to utilize Bezier curves in designing a smooth path algorithm.
Addressing the challenges of mobile robot path planning, namely the tendency to fall into local optima and the issue of non-smooth paths. This study improved the NSGA-II algorithm and used this method to solve the mobile robot path planning problem. The contributions of this paper are as follows:
  • This paper presents a mobile robot path planning algorithm based on NSGA-II. The initialization of the population is improved by limiting the generation positions of path nodes using a search window, thereby enhancing the quality of the initial path population. Practical selection operators are proposed, and optimization is performed on two objective functions: path length and path smoothness. This optimization enhances the algorithm’s ability to escape local optima.
  • This study systematically investigated the conditions that smooth paths need to satisfy. It employed Bezier curves to smooth the planned paths, and the experimental results indicated that this approach could enhance the smoothness of the paths.
  • Experimental comparisons were conducted between the proposed algorithm and different algorithms. The results of the comparisons demonstrated that the paths obtained by the proposed algorithm were shorter and smoother.
The rest of this work is outlined below. Section 2 introduces the improved mobile robot path planning algorithm based on the NSGA-II algorithm. Section 3 introduces the path smoothing algorithm based on a Bessel curve. Section 4 details the simulations, and Section 5 summarizes this article.

2. Global Path Planning

The traditional NSGA-II algorithm exhibits strengths such as robustness and strong global optimization capabilities when addressing path planning problems. However, it also suffers from drawbacks such as a slow convergence speed, susceptibility to local optima, and the low quality of the initial population. In response to these issues, this paper proposed the following improvements:

2.1. Population Initialization

The process of population initialization aims to generate a set of initial paths, serving as the foundation for algorithm iteration. Improving the efficiency of initialization is beneficial for enhancing path planning efficiency and influencing algorithm convergence. The quality of the initial paths also impacts the calculation of optimal paths. Most scholars opt for a random method during population initialization. In this approach, random path nodes are initially generated within the feasible region of the map. Subsequently, the usefulness of these randomly generated path nodes is assessed based on whether they can form a feasible path. However, this process often results in numerous ineffective nodes and paths, significantly increasing the computational overheads and decreasing algorithm efficiency. Moreover, the random distribution of the generated paths may lead to uneven distribution. If the random solution set predominantly lies in local optimal positions, this may inadvertently steer the algorithm towards local optima. This is one of the reasons why the NSGA-II algorithm is prone to local optima.
To address these issues, this paper introduces the concept of a search window to constrain the generation of random points. The search window is a fixed-size square region, within which new nodes are generated. The position of the search window changes continuously based on the location of the generated nodes, always facing towards the target point. Specifically, when the target point is directly above the mobile robot, the robot should be positioned at the bottom center of the search window. When the target point is to the top right of the mobile robot, the robot should be positioned on the left side of the bottom of the search window. Similar adjustments are made for other target point positions relative to the robot. The search window continuously moves towards the target point direction based on the mobile robot’s position, until a complete path from the start point to the target point is generated. By constraining the range and orienting the search window towards the target point, this paper improves the efficiency of generating initial paths, reduces the number of redundant nodes, and avoids misguiding the initial path set. The specific steps of the improved population initialization method can be summarized as follows:
  • Generate a search window from the robot’s position towards the target point, using the robot’s position and the target point as reference points, as shown in Figure 1.
  • Generate a random path node within the feasible area in the search window where there is no robot present.
  • Determine whether the robot can move directly to the position of this path node. Since the mobile robot can move directly to the grid in eight directions adjacent to its position, the judgment condition expression is as follows:
    δ = max a b s ( x i + 1 x i ) , a b s ( y i + 1 y i ) ,
    where ( x i , y i ) represents the coordinates of the grid where the mobile robot is located, and ( x i + 1 , y i + 1 ) represents the coordinates of the generated path node.
         If δ takes the value 1, i.e., δ = 1 , this means the generated path node is located within the eight grids that the mobile robot can directly move to, so the node’s position is updated directly to the robot’s position. Otherwise, δ 1 , which indicates that the generated node position is not within the eight grids the mobile robot can directly move to, so intermediate nodes need to be supplemented. In this text, we use the method of interpolation to supplement the path nodes. The expression for selecting intermediate path nodes is as follows:
    x m i d d l e = i n t ( x i + 1 + x i 2 ) , y m i d d l e = i n t ( y i + 1 + y i 2 ) ,
    where int denotes rounding. After calculation, if the position is obstructed, it is necessary to choose another grid. When selecting a new grid, priority is given to the four grids surrounding the obstructed position, and they are traversed in the order up, down, left, and right. A grid belonging to the feasible area is selected as the intermediate path node and inserted into the path, updating the path node to the robot’s position. If it is not possible to insert an intermediate path node using the above method, the path is abandoned, and Step 2 is repeated to regenerate.
  • Check if the robot’s coordinates are the same as the target point’s coordinates. If they are, save the entire obstacle-free continuous path as a population individual. If not, repeat Step 2.
  • Calculate the number of individuals in the population. If the total number of individuals in the population equals the maximum value, end the iteration. If not, repeat Step 1 to continue the iteration.

2.2. Designing the Fitness Function

In the algorithm, the fitness function is primarily used to quantitatively describe individuals. Therefore, the design of the fitness function is crucial. If the fitness function is not appropriate, this may lead to deception phenomena. In the early stages of the algorithm, individual extraordinary individuals may emerge due to their outstanding fitness, leading to a strong competitiveness. This may result in the dominance of this individual in the selection process, thereby significantly affecting the global optimization of the algorithm. Alternatively, in the later stages of the algorithm, after multiple iterations, the fitness differences among individuals in the population are small, leading to a decrease in individual diversity and possibly causing the algorithm to fall into local optima.
In the path planning process of mobile robots, path length is an important consideration. Path length is directly related to the energy consumption of the mobile robot. Since the battery capacity of mobile robots is limited, efficiently completing tasks with limited energy is an important criterion for evaluating robot efficiency. Therefore, in feasible situations, shorter paths for mobile robots are preferred. In addition to path length, path smoothness is an important evaluation criterion for mobile robot path planning. Due to the constraints of kinematics and dynamics, and for safety reasons during robot motion, the turning angle of the robot should not be too large, and the number of turns should not be too high. Therefore, in this paper, path length and path smoothness are considered as the objective functions for path planning.
Considering a path L j , where j = 1 , 2 , , M and M represents the maximum number of individuals contained in the population, L j can be denoted as L j = O 1 , O 2 , , O m , where m signifies the number of nodes in path L j , O i represents a node within path L j , O 1 denotes the starting point of path L j , and O m signifies the target point.
The sum of distances between all adjacent nodes, including the starting point and the target point, constitutes the path length. The expression for the path length function  f 1 is
f 1 ( L ) = i = 1 m 1 l i ,
where O i represents the ith node in a path, m denotes the total number of nodes in that path, and l i signifies the distance between adjacent nodes in the path. The expression is as follows:
l i = O i O i + 1 = ( x i + 1 x i ) 2 + ( y i + 1 y i ) 2 , i = 1 , 2 , , m 1 ,
where x 1 and y i represent the horizontal and vertical coordinates of the nodes, respectively.
Path smoothness reflects the smoothness of the mobile robot’s trajectory. The path smoothness function f 2 is defined as
f 2 ( L ) = i = 1 m 2 e ( π θ i ) ( lg π lg θ i ) ,
where θ i represents the angle formed between the path segment from node O i to node O i + 1 and the path segment from node O i + 1 to node O i + 2 , as depicted in Figure 2, and m is the number of nodes in the path. When the path angle is right, the path is the smoothest, and f 2 is minimized. Conversely, when the path angle is acute, the path is the least smooth, and f 2 is maximized.
Therefore, in this paper, the objective function of path planning is
min f 1 ( L ) = i = 1 m 1 l i , f 2 ( L ) = i = 1 m 2 e π θ i ( lg π lg θ i ) .

2.3. Selection Operators

Selection operations are used to determine how individuals are chosen from the parent population according to a certain method, followed by crossover operations to generate new individuals. When designing selection operators, it is necessary to ensure that excellent individuals are retained, while also maintaining diversity and randomness among individuals. Therefore, this paper proposes a probability-based selection strategy. Initially, the probability of each individual being chosen is calculated based on its non-dominated rank and crowding distance. A higher probability of being chosen indicates a greater likelihood of the individual being an optimal solution, whereas a lower probability of being chosen suggests a smaller likelihood of the individual being an optimal solution.
When selecting individuals based on probability, it is necessary to calculate the probability of each individual being chosen. Let us denote the probability of each individual being selected as P j , where j = 1 , 2 , , M and M represents the maximum number of individuals in the population. The probability of each individual being chosen consists of two parts: one is calculated based on the crowding distance, denoted P d , and the other is calculated based on the non-dominated rank, denoted P r .
When computing the probability based on the crowding distance, the crowding distance values of individuals are normalized to obtain the probability P d calculated based on crowding distance, as follows:
P d ( j ) = d ( j ) k = 1 M d ( k ) , j = 1 , 2 , , M
where d ( j ) represents the crowding distance value of an individual j.
The probability P r calculated based on non-dominated rank is
P r ( j ) = λ r j 1 ( r j 1 ) ! e λ , j = 1 , 2 , , M
where r j is the non-dominated rank of an individual j, and λ is a calculation parameter.
Therefore, the probability of an individual being chosen is given by
P j = P d ( j ) · P r ( j ) ,
Based on the probabilities of individual selection, the entire population is divided into two sets: one suitable for entering the offspring population, and the other not suitable for entering the offspring population. Proportionally, individuals are selected from both sets. Randomly selecting a few individuals with lower selection probabilities can enhance the population diversity. When the algorithm is trapped in local optima, this provides opportunities for the algorithm to escape local optima and find better solutions, thus improving the algorithm’s ability to escape local optima.

2.4. Algorithm Workflow

To enhance the efficiency of path planning, increase population diversity, and avoid falling into local optima, this paper introduces the concept of a search window to improve population initialization, designs a new fitness function, and combines probabilistic methods to design a selection operator, proposing a global path planning algorithm. The specific steps of the path planning algorithm are as shown in Algorithm 1.
Algorithm 1 Global Path Planning Algorithm
1:
Input: G r i d , M, G m a x , G e n = 1 , P c , P m , λ ;
2:
Initialize the population;
3:
Calculate fitness;
4:
Calculate the non-dominant level and crowding degree value;
5:
for G < G m a x
6:
      Selection, crossover, mutation;
7:
      Merger of father and son populations;
8:
      Calculate non-dominant level and crowding degree;
9:
      Select M individuals into the offspring;
10:
     G e n = G e n + 1 ;
11:
end
11:
Output: PathD;

3. Smooth Path Planning

The optimal path generated by path planning algorithms is typically composed of polygons or polylines, which may include complex situations such as sharp turns. In such cases, to follow these paths, a mobile robot may need to switch between different motion states, such as “stop”, “rotate”, and “restart” [20]. In this scenario, the switching of motion states will undoubtedly lead to discontinuities in velocity and acceleration, resulting in slippage and overdriving of the mobile robot during high-speed motion [21]. This is a time-consuming and energy-consuming process, which not only reduces the efficiency but also shortens the lifespan of the mobile robot. Therefore, this paper proposes a path smoothing algorithm combined with Bézier curves.

3.1. Bézier Curve

In 1962, French mathematician Pierre Bézier was the first to study this method of vector drawing curves and provided detailed calculation formulas. Consequently, curves drawn according to such formulas are named after his surname and known as Bézier curves [22].
The nth degree parametric curve segment, known as a Bézier curve, is defined as follows, given n + 1 spatial vectors Q i ( i = 1 , 2 , , n ) :
q ( t ) = i = 0 n Q i B i , n ( t ) , 0 t 1 ,
where t represents the normalized time variable, ( x i , y i ) represents the coordinate vector of the ith control point Q i , and B i , n ( t ) are the Bernstein polynomials, serving as the basis functions in the expression of the Bézier curve.
B i , n ( t ) = C n i t i ( 1 t ) n i = n ! i ! ( n i ) ! t i ( 1 t ) n i , i = 0 , 1 , , n .

3.2. Path Smoothing Algorithm

A key step in using Bézier curves to smooth path planning is selecting control points. During path planning, it is essential to ensure the continuity of the planned path, meaning that the curvature needs to be continuous when two segments of Bézier curves are concatenated. Simultaneously, it is crucial to avoid intersections between the planned path and obstacles, which would render the path invalid. The selection of control points directly affects the curvature and shape of the Bézier curve, making the position of control points critical.
The position of control points determines the curvature of the curve and the continuity of the fitted path. Using the path nodes directly from the planned path may result in the planned path overlapping with obstacles, leading to an invalid fitted path, as shown in Figure 3.
Therefore, the fitted path must meet the following three requirements:
  • The fitted path must not collide with obstacles, i.e.,
    | q ( t ) w | > 2 2 ,
    where | | represents the distance from the line segment to the nearest obstacle, and w represents the obstacle coordinates.
  • The fitted path must satisfy the smoothness requirement. To ensure the continuous smoothness of the path, it is necessary to ensure that the curvature is continuous at the junction of two Bézier curves. Due to the properties of Bézier curves, the tangent direction at the starting and ending points of the Bézier curve and the first and last edges of the characteristic polygon, respectively, are tangential. Therefore, it is only necessary to ensure that the first and last edges of the characteristic polygons of two Bézier curves lie on the same straight line.
  • The fitted path should be shorter, i.e., the fitted path should be as close as possible to the source path, i.e.,
    m i n | q ( t ) D | ,
    where D is the planned path.
To meet these three requirements, this paper combines geometric methods and optimization algorithms to design a point selection algorithm for selecting control points. Then, a third-order Bézier curve is used to fit the path, ultimately generating a collision-free smooth path. A flowchart of the path planning algorithm is shown in Figure 4. The specific steps of the path smoothing algorithm are as shown in Algorithm 2.
Algorithm 2 Path Smoothing Algorithm
1:
Input: D, G m a x , G e n ;
2:
Determine the start and end positions of all line segments in the path;
3:
Generate the initial control point position;
4:
for G e n < G m a x
5:
      Calculate gradient;
6:
      Update momentum;
7:
      Update control point location;
8:
       G e n = G e n + 1 ;
9:
end
10:
 Generate third-order Bezier curve;
11:
 Output: Smoothed path;

4. Experimental Simulation and Analysis

4.1. Environment Setup

In the path planning of mobile robots, map establishment is an important step. Commonly used map representation methods include grid representation, geometric representation, and topological map representation. This paper adopts the grid map representation method. Grid map representation has the advantage of a simple structure, which can simplify complex terrain and facilitate model establishment. In the grid map, and white areas represent feasible areas, while black areas represent infeasible areas, i.e., obstacles, as shown in Figure 5.
Let the map model be represented as
G r i d ( x , y ) = 1 , ( x , y ) = w 0 , e l s e
In grid maps, commonly used encoding methods include real number encoding, binary encoding, and floating-point encoding. Among them, real number encoding is simple to operate and easy to calculate. Therefore, in this experiment, real number encoding was used to encode each grid in the map. According to the 20 × 20 grid map used in the experiment, grids are encoded sequentially from left to right and from bottom to top as 0, 1, 2, …, 399. The relationship between the grid with the number O and its coordinates in the map is:
x = O mod G s i z e + 1 , y = O G s i z e + 1 ,
where denotes the floor function, mod denotes the modulo function, and G s i z e represents the number of grids per row.
To verify the correctness and effectiveness of the algorithm, two grid maps of different complexity levels were selected, as shown in Figure 6. Simulation tests were conducted using MATLAB R2016a and compared with the standard NSGA-II algorithm and genetic algorithm.

4.2. Parameter Settings

In the standard NSGA-II algorithm and GA algorithm, the initial population was randomly generated, and the selection operator adopted a tournament selection strategy. Specific parameters are shown in Table 1.

4.3. Global Path Planning Experiment and Analysis

To verify the effectiveness of the algorithms, each algorithm was independently run multiple times. Table 2 compares the results of multiple simulations on complex grid maps.
From Table 2, it can be seen that the average length of the optimal path of our algorithm was shorter than the other two algorithms, the path smoothness was better, and the number of times the optimal solution was found was higher. The stability of the algorithm was improved, indicating that our algorithm has a better global search capability in path planning.
To ensure the comprehensiveness of the simulation outcomes, the proposed algorithm, NSGA-II algorithm, and GA algorithm were each employed to address grid maps of differing complexity levels independently. The optimal paths and convergence curves derived by NSGA-II for the two maps are depicted in Figure 7. Similarly, the optimal paths and convergence curves yielded by GA for the two maps are illustrated in Figure 8. Additionally, the optimal paths and convergence curves attained by the proposed algorithm for the two maps are shown in Figure 9. The comparative experimental results of the simple map are detailed in Table 3, while those of the complex map are provided in Table 4.
The experimental results indicated that when using simple maps, both the NSGA-II algorithm and our algorithm yielded favorable outcomes. However, our algorithm exhibited significantly fewer iterations compared to the other two algorithms, and it also had fewer inflection points in the optimal path. Moreover, when dealing with maps in complex environments, the advantage of our algorithm became more pronounced. The paths planned by our algorithm were noticeably shorter than those generated by the other two algorithms. Moreover, both the iteration count and the number of inflection points in the optimal path were fewer than those of the other two algorithms. From the convergence curve graphs, it is evident that our algorithm was more stable and robust, demonstrating superior convergence and a better ability to escape local optima. Therefore, our path planning algorithm demonstrated superior overall performance and practical applicability.

4.4. Path Smoothing Experiments and Analysis

The simulation experiment results for path smoothing on maps of two different complexities are depicted in Figure 10. The smoothed paths conform to the principles of mobile robot motion, devoid of abrupt corners. The paths exhibit smooth curves overall, enabling the mobile robot to travel smoothly without the need to stop, turn, and restart at corner points. This is crucial for reducing wear and tear on the robot due to turning, thus extending its lifespan.

5. Conclusions

To address the issues of local optima and non-smooth paths in mobile robot path planning, this paper proposed a path planning method based on NSGA-II. In the path planning algorithm designed in this paper, the concept of a search window was introduced to optimize the population initialization process. This ensures that during population initialization, the algorithm avoids unnecessary nodes and excessive paths, thereby reducing the computational overheads and improving the path planning efficiency. Additionally, this prevents randomly generated paths from being concentrated near local optima, thus guiding the algorithm away from local optimal solutions. Furthermore, a selection operator was designed using a probability-based approach, to optimize the selection process. This enables the algorithm to select a diverse range of individuals during the selection process, thereby increasing the population diversity and positively impacting the subsequent crossover and mutation operations. The path planning algorithm designed in this paper demonstrated robustness and convergence. By simultaneously selecting individuals with both high and low selection probabilities during the selection process, the algorithm maintains good diversity within the population, while ensuring that excellent individuals smoothly transition to the next generation, thus possessing the ability to escape local optima effectively.
Moreover, a path smoothing algorithm was developed in this paper, which utilizes multi-segment Bézier curves to fit the optimal path. This approach ensures that the fitted path is free from abrupt corners, thereby guaranteeing path smoothness. The extensive experimental simulations conducted using the proposed algorithm demonstrated its effectiveness in addressing the problem of easily falling into local optima in path planning. The planned paths were smooth and continuous, indicating the practical applicability of the proposed method in real-world scenarios.
The research in this paper focused on studying the path planning problem for mobile robots; however, there are still some shortcomings. Therefore, there is room for improvement in this work, and the future directions for this research are outlined as follows: (1) Consideration of Multi-Robot Coordination or Swarm Robotics: Future research will explore the path planning problem for multiple robots operating collaboratively or in formation. This involves developing algorithms that enable coordination among multiple robots, to achieve collective objectives efficiently. (2) Extension to Dynamic Environments: While this paper primarily addressed path planning in static environments, real-world scenarios often involve dynamic elements such as moving obstacles, humans, or other robots. Therefore, future work will focus on studying path planning for mobile robots in dynamic environments, where the environment is subject to changes over time.

Author Contributions

Conceptualization, S.L. and Q.T.; methodology, S.L.; software, S.L.; validation, S.L., Q.T. and C.T.; formal analysis, S.L.; investigation, S.L.; resources, S.L.; data curation, S.L.; writing—original draft preparation, S.L.; writing—review and editing, S.L.; visualization, S.L.; supervision, S.L.; project administration, S.L.; funding acquisition, Q.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Beijing University of Civil Engineering and Architecture Science Research Foundation under Grant No.00331614021, the BUCEA Post Graduate Innovation Project, and the Practical Training Plan of Beijing College High Level Talents Cross Developing Project.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The original contributions presented in the study are included in the article, further inquiries can be directed to the corresponding authors.

Conflicts of Interest

The authors declare that they have no conflicts of interest.

References

  1. Bai, X.L.; Zhou, W.Q.; Zhang, Z.P.; Yuan, Z. Smooth path planning of wheeled robot based on heuristic particle swarm spotimization algorithm. Modul. Mach. Tool Autom. Manuf. Tech. 2022, 8, 44–47+52. [Google Scholar] [CrossRef]
  2. Wang, Z.Q.; Hu, X.G.; Li, X.X.; Du, Z.Q. Overview of global path planning algorithms for mobile robots. Comput. Sci. 2021, 48, 19–29. [Google Scholar] [CrossRef]
  3. Lai, X.; Wu, D.; Wu, D.; Jia, H.L.; Hang, Y. Enhanced DWA algorithm for local path planning of mobile robot. Ind. Robot 2023, 50, 186–194. [Google Scholar] [CrossRef]
  4. Xiong, X.Y.; Min, H.T.; Yu, Y.B.; Wang, P.Y. Application improvement of A* algorithm in intelligent vehicle trajectory planning. Math. Biosci. Eng. MBE 2020, 18, 21. [Google Scholar] [CrossRef] [PubMed]
  5. Shi, W.B.; Wang, K.; Zhao, C.; Tian, M.Q. Obstacle Avoidance Path Planning for the Dual-Arm Robot Based on an Improved RRT Algorithm. Appl. Sci. 2022, 12, 4087. [Google Scholar] [CrossRef]
  6. Zhang, K.F.; Huang, Y.Z.; Li, L.M.; Qin, J.; Liu, C. Planning method of freight ropeway path based on Dijkstra algorithm. J. Shandong Univ. (Eng. Sci.) 2022, 52, 176–182. [Google Scholar] [CrossRef]
  7. Shi, Z.G.; Mei, S.; Shao, Y.F.; Wan, R.; Song, Z.Y.; Xie, M.L.; Li, Y. Research status and prospect of path planning for mobile robot based on artificial potential field method. J. Chin. Agric. Mech. 2021, 42, 182–188. [Google Scholar] [CrossRef]
  8. Wu, M.Y.; Zhang, Y.L.; Liu, N.; Dai, L. 3D PathPlanning of RobotFishBased on ImprovedAntColonyAlgorithm. J. Phys. Conf. Ser. 2022, 2400, 012052. [Google Scholar] [CrossRef]
  9. Li, W.; Tan, M.; Wang, L.; Wang, Q.Z.; He, B.; Wang, S.; Liu, Y.J.; Zhang, L.J.; Hu, R.Q.; Yi, W.M.; et al. A cubic spline method combing improved particle swarm optimization for robot path planning in dynamic uncertain environment. Int. J. Adv. Robot. Syst. 2020, 17, 1729881419891661. [Google Scholar] [CrossRef]
  10. Li, S.B.; Song, Q.S.; Li, Z.A.; Zhang, X.X.; Zhe, L.X. Review of genetic algorithm in robot path planning. Sci. Technol. Eng. 2020, 20, 423–431. [Google Scholar] [CrossRef]
  11. You, D.Z.; Ma, L.; Zhang, Y.P.; Cai, S. Path planning of mobile robot based on hybrid annealing grey wolf algorithm. Electron. Meas. Tech. 2020, 46, 54–60. [Google Scholar] [CrossRef]
  12. Hao, K.; Deng, C.S.; Zhao, L.; Liu, Y.L. Robot path planning based on region search particle swarm optimization. J. Electron. Meas. Instrum. 2022, 36, 126–135. [Google Scholar] [CrossRef]
  13. Chang, J.; Ren, Y. Robot path planning based on improved genetic algorithm. Modul. Mach. Tool Autom. Manuf. Tech. 2023, 2, 23–27. [Google Scholar] [CrossRef]
  14. Davoodi, M.; Panahi, F.; Mohades, A.; Hashemi, S.N. Multi-objective path planning in discrete space. Appl. Soft Comput. 2013, 13, 709–720. [Google Scholar] [CrossRef]
  15. Huang, Z.F.; Liu, Y.H. Solving path planning problem based on the fourth-order Bezier curve and improved lion swarm optimization algorithm. Inf. Control 2023, 52, 176–189. [Google Scholar] [CrossRef]
  16. Li, F.F.; Du, Y.; Jia, K.J. Path planning and smoothing of mobile robot based on improved artificial fish swarm algorithm. Sci. Rep. 2022, 12, 659. [Google Scholar] [CrossRef]
  17. Xue, Y. Mobile Robot Path Planning with a Non-Dominated Sorting Genetic Algorithm. Appl. Sci. 2018, 8, 2253. [Google Scholar] [CrossRef]
  18. Jia, L.; Zeng, S.; Feng, L.; Lv, B.; Yu, Z.; Huang, Y. Global Time-Varying Path Planning Method Based on Tunable Bezier Curves. Appl. Sci. 2023, 13, 13334. [Google Scholar] [CrossRef]
  19. Hao, J.; Yang, X.; Wang, C.; Tu, R.; Zhang, T. An Improved NSGA-II Algorithm Based on Adaptive Weighting and Searching Strategy. Appl. Sci. 2022, 12, 11573. [Google Scholar] [CrossRef]
  20. Song, B.Y.; Wang, Z.D.; Zou, L. An improved PSO algorithm for smooth path planning of mobile robots using continuous high-degree Bezier curve. Appl. Soft Comput. J. 2021, 100, 106960. [Google Scholar] [CrossRef]
  21. Elhosenyl, M.; Tharwa, A.; Hassanien, E.A. Bezier Curve Based Path Planning in a Dynamic Field using Modified Genetic Algorithm. J. Comput. Sci. 2018, 25, 350–399. [Google Scholar] [CrossRef]
  22. Șomîtcă, I.A.; Brad, S.; Florian, V.; Deaconu, Ș. Improving path accuracy of mobile robots in uncertain environments by adapted bézier curves. Electronics 2022, 11, 3568. [Google Scholar] [CrossRef]
Figure 1. Search window generation diagram.
Figure 1. Search window generation diagram.
Applsci 14 04305 g001
Figure 2. Path angle.
Figure 2. Path angle.
Applsci 14 04305 g002
Figure 3. The planned path coincides with the obstacle.
Figure 3. The planned path coincides with the obstacle.
Applsci 14 04305 g003
Figure 4. Path smoothing algorithm flow chart.
Figure 4. Path smoothing algorithm flow chart.
Applsci 14 04305 g004
Figure 5. Grid map.
Figure 5. Grid map.
Applsci 14 04305 g005
Figure 6. Two types of grid maps. (a) complex map; (b) simple map.
Figure 6. Two types of grid maps. (a) complex map; (b) simple map.
Applsci 14 04305 g006
Figure 7. Planned path and convergence curve of NSGA-II. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Figure 7. Planned path and convergence curve of NSGA-II. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Applsci 14 04305 g007aApplsci 14 04305 g007b
Figure 8. Planned path and convergence curve of GA. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Figure 8. Planned path and convergence curve of GA. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Applsci 14 04305 g008
Figure 9. Planned path and convergence curve in this paper. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Figure 9. Planned path and convergence curve in this paper. (a) Planned path of simple map; (b) convergence curve of simple map; (c) planned path of complex map; (d) convergence curve of complex map.
Applsci 14 04305 g009
Figure 10. Path of smoothing algorithm. (a) Smoothed path of simple map; (b) smoothed path of complex map.
Figure 10. Path of smoothing algorithm. (a) Smoothed path of simple map; (b) smoothed path of complex map.
Applsci 14 04305 g010
Table 1. Parameter setting.
Table 1. Parameter setting.
ParameterValue
Population size M200
Maximum iterations G m a x 50
Crossover rate P c 0.9
Mutation rate P m 0.1
Calculation Parameters λ 0.8
Table 2. Comparison of effectiveness results.
Table 2. Comparison of effectiveness results.
NumberAlgorithmNSGA-IIGAThe Algorithm Proposed in This Paper
1Length32.384832.142130.3848
Smoothness8.37677.47674.1104
2Length31.799031.213230.3848
Smoothness5.48054.65843.5623
3Length32.384831.799030.3848
Smoothness8.37675.75453.5623
4Length31.213232.142131.2132
Smoothness4.38446.57663.8364
5Length32.142132.384830.3848
Smoothness6.57668.37673.5623
6Length31.213231.213230.3848
Smoothness4.38444.65843.5623
7Length31.799031.799030.3848
Smoothness5.75455.48054.1104
MeanLength31.8480131.8133430.50314
Smoothness6.190546.140263.75806
VarianceLength0.250.210.09
Smoothness2.821.990.07
Coarsened text represents the optimal result.
Table 3. Comparison of effectiveness results of simple map.
Table 3. Comparison of effectiveness results of simple map.
AlgorithmShortest PathNumber of IterationsNumber of Turning Points
NSGA-II28.62741510
GA29.4558810
The algorithm proposed in this paper28.627455
Coarsened text represents the optimal result.
Table 4. Comparison of effectiveness results of complex map.
Table 4. Comparison of effectiveness results of complex map.
AlgorithmShortest PathNumber of IterationsNumber of Turning Points
NSGA-II31.21322712
GA31.21322313
The algorithm proposed in this paper30.3848114
Coarsened text represents the optimal result.
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Liu, S.; Tian, Q.; Tang, C. Mobile Robot Path Planning Algorithm Based on NSGA-II. Appl. Sci. 2024, 14, 4305. https://doi.org/10.3390/app14104305

AMA Style

Liu S, Tian Q, Tang C. Mobile Robot Path Planning Algorithm Based on NSGA-II. Applied Sciences. 2024; 14(10):4305. https://doi.org/10.3390/app14104305

Chicago/Turabian Style

Liu, Sitong, Qichuan Tian, and Chaolin Tang. 2024. "Mobile Robot Path Planning Algorithm Based on NSGA-II" Applied Sciences 14, no. 10: 4305. https://doi.org/10.3390/app14104305

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop