Next Article in Journal
Multi-CC: A New Baseline for Faster and Better Deep Clustering
Next Article in Special Issue
Fault-Tolerant Safety-Critical Control for Nonlinear Affine System by Using High-Order Control Barrier Function
Previous Article in Journal
Accuracy Analysis of Visual Odometer for Unmanned Rollers in Tunnels
Previous Article in Special Issue
Graph U-Shaped Network with Mapping-Aware Local Enhancement for Single-Frame 3D Human Pose Estimation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Automatic Vertical Parking Path-Planning Algorithms for Narrow Parking Spaces

1
College of Vehicle and Transportation Engineering, Henan University of Science and Technology, Luoyang 471003, China
2
College of Mechatronics Engineering, Henan University of Science and Technology, Luoyang 471003, China
*
Author to whom correspondence should be addressed.
Electronics 2023, 12(20), 4203; https://doi.org/10.3390/electronics12204203
Submission received: 16 August 2023 / Revised: 28 September 2023 / Accepted: 3 October 2023 / Published: 10 October 2023

Abstract

:
Narrow parking spaces pose difficulties in path planning and spot turning caused by sudden changes and discontinuities in path curvature. To address these problems, this paper investigates the performance of three path-planning algorithms and proposes a path-optimization algorithm. First, a narrow parking space is defined based on single-step parking using the arc-line combination parking algorithm. Second, to compare the arc-line combination algorithm, Hybrid A* algorithm, and particle swarm optimization parking algorithm with respect to different narrow parking spaces, a multi-objective evaluation function is proposed, including three evaluation indicators, namely, the path length, the number of positive and negative conversions of vehicle speed, and the smoothness of the path. Their performance is compared using a simulation conducted in MATLAB. With the same starting point and different parking space widths, the three algorithms are simulated to generate different planned paths. Then, the evaluation indices are obtained to compare the performance of the algorithms based on the multi-objective function, the values of which indicate the fitness of the algorithm in a narrow parking environment. The results show that the Hybrid A* algorithm is better than the others for narrow parking spaces. Third, to smooth the planning path, a path optimization algorithm based on the cubic B-spline curve and gradient descent is proposed. Finally, the results of a simulation conducted on the proposed algorithm and the Hybrid A* algorithm are provided: the average minimum curvature of the path was reduced by 0.005 m−1, and the path meets the requirements of the minimum turning radius constraint of the analyzed vehicle. The results show that the proposed algorithm can effectively eliminate the curvature mutation point and constrain the path curvature to meet the requirements of a smooth path.

1. Introduction

With the continuous rise in car ownership, the availability of parking spaces is decreasing, leading to increasingly narrow parking areas and thus rendering parking difficult and inefficient for drivers, even resulting in collisions between a vehicle and surrounding objects. Additionally, this can also cause traffic jams and even traffic accidents. Therefore, automatic parking technology for narrow parking spaces has gradually become a research focus [1].
Automatic parking systems use vehicle sensors to measure the relative distance, speed, and angle between a vehicle and surrounding objects. These measurements are processed either on-board or on a cloud-computing platform. Based on this information, the system controls the vehicle’s steering, acceleration, and deceleration to achieve automatic parking. The parking process can be divided into four steps, namely, environmental perception, parking space detection and recognition, parking path planning, and parking path following control. Among them, path planning consists of planning a path avoiding collision under vehicle dynamics constraints based on environment and location information, and it is executed on the vehicle [2,3].
At present, there are three kinds of vertical parking path-planning algorithms commonly used for traditional standard parking spaces [4]. One is the geometric algorithm. Zhao, B et al. [5] used arc lines as transition paths in local path planning to park a vehicle, including arcs and line segments based on the optimal parking starting point node. Although the parking path was shortened, this method is only suitable for single-step parking. Jiang, M et al. [6] proposed a vertical parking path-planning algorithm based on polynomial curve optimization to improve the safety and success rate of automatic vertical parking in complex environments. Although it can solve the problem of not being able to perform single-step parking, this algorithm requires a wider parking space. Zhang, J et al. [7] proposed a vertical parking trajectory-planning algorithm based on a cycloid curve, decoupling the vertical parking trajectory-planning problem into a path-planning problem and a velocity-planning problem, but it can only be used in slightly narrow parking spaces. The arc–line combination algorithm in the geometric algorithm has accurate characteristics, allowing it to accurately calculate the driving trajectory of a vehicle in the parking process so that the vehicle can accurately park in a specified parking space.
The second is a random search algorithm. Yu, L et al. [8] used a particle swarm optimization algorithm to solve equality constraints based on parking boundaries and inequality constraints based on curvature, collision avoidance, and parking space reduction. It yielded optimized, smooth, and curvature-continuous programmed path curve expressions by taking the weighted sum of the maximum curvature and the absolute value of the horizontal coordinate of the starting position of parking as the objective function. However, due to the large number of parameters involved, its path search efficiency is low. Kim, M et al. [9] proposed a Target Tree RRT* algorithm for complex environments that uses the clothoid path to design a target tree to deal with curvature discontinuity. To further reduce the planning time, a cost function was defined to initialize an appropriate target tree considering obstacles. Combining the optimal variable RRT and searching for the shortest path, the Target Tree RRT* algorithm obtains an approximately optimal path as the sampling time increases. Although the path search time is shortened, the smoothness of the path cannot be guaranteed. Zhang, J et al. [10] proposed a parallel parking path-planning algorithm based on improved particle swarm optimization; comprehensively considered the non-holonomic kinematic constraints of a 4 WS by-wire vehicle, the process constraints and boundary constraints of the power and steering subsystems, obstacle avoidance constraints, the initial parking posture, and target parking posture constraints; and established a parallel parking path-planning constraint optimization problem to minimize the total duration of the parking process. The particle swarm optimization algorithm, which can deal with equality constraints and inequality constraints, was used to solve the problem and determine the optimal parallel parking path. Although it can solve the problem of non-smooth paths, it is not suitable for narrow parking spaces. The search process of the particle swarm optimization algorithm in the random search algorithm is a parallel search. Its computational efficiency is high, and the parking path that meets the conditions can be found in a short time. The principle of the particle swarm optimization algorithm is simple, and the parameter adjustment procedure is relatively simple. For different parking scenarios, only a few parameters need to be adjusted.
The third type is the graph search algorithm. Sedighi, S et al. [11] proposed an efficient computational algorithm that combines the Hybrid A* search algorithm with visibility graph planning to find the shortest non-holonomic path in a mixed (continuous–discrete) environment for automatic parking; although it allows for a relatively short path to be searched for, the search time is increased. Bai, J et al. [12] proposed a directed Hybrid A* global path-planning algorithm based on the generalized Vinor map for the path-planning problem of autonomous valet parking systems. It accurately and effectively generates a collision-free path from the entrance of a parking lot to the starting point of parking. Xiong, L et al. [13] improved the Hybrid A* by adding a penalty term for obstacle distance on the Reeds–Shepp (RS) curve, which ameliorated the problem of the RS curve being too close to obstacles and improved the effectiveness of parking. The Hybrid A* algorithm in the graph search algorithm conducts a heuristic search in a continuous coordinate system, which can ensure that the generated trajectory satisfies a vehicle’s non-integrity constraint (kinematic constraint). It can deal with non-smooth obstacles and find the optimal global solution. By combining the discrete node network with the exploration of continuous space, the calculation amount and search time can be reduced.
These three algorithms can improve parking efficiency, reduce searching time, and adapt to conventional standard parking spaces. However, their applications in automatic vertical parking in narrow spaces are rare, and their performance is uncertain. In addition, there are no standards for narrow parking spaces and no evaluation index for automatic parking in narrow spaces.
For the reasons mentioned above, the contributions of this study are summarized as follows.
1.
A narrow parking space is defined based on the single-step parking limitation of the arc–line combination parking algorithm. A narrow parking space is defined as having a width between 1.25 and 1.35 times the vehicle width.
2.
A multi-objective evaluation function for narrow parking spaces is proposed. The parking path-planning algorithms of three various types (arc–line combination, particle swarm optimization, and Hybrid A*) are simulated and examined using the function under different narrow degrees. The simulated parking path curve and curvature are evaluated, and the advantages and disadvantages of the three algorithms in narrow parking space parking planning are analyzed.
3.
A path optimization algorithm based on a cubic B-spline curve and gradient descent is proposed to optimize the path planned by the parking algorithm.
The remainder of this paper is organized as follows. The vehicle kinematics model is established in Section 2. Section 3 introduces the principle of three parking algorithms and proposes the multi-objective function for parking path planning. In Section 4, the simulation of three algorithms in different narrow parking spaces is conducted and their performances are compared. In Section 5, a parking path optimization algorithm based on a cubic B-spline curve and gradient descent is proposed, and the results of a simulation conducted on the proposed algorithm are provided. The conclusion is drawn in the last section.

2. Vehicle Kinematics Model

During the automatic parking process, a vehicle maintains a relatively low speed, typically around 2 km/h, and the lateral sliding generated during the parking process can be ignored [14]. The center of the vehicle’s rear axle is the base point, and the vehicle kinematics is modeled as shown in Figure 1.
By selecting the center of the equivalent vehicle rear axle as the reference point, because the speed of the whole parking process is less than 5 km/h, it can be assumed that the vehicle’s tires do not slide sideways during the parking process. The following differential equation can be obtained according to Figure 1.
x ˙ Q s i n θ y ˙ Q c o s θ = 0
The kinematics equation of the center point of the equivalent rear axle can be obtained from Equation (1) and expressed as follows.
x ˙ Q y ˙ Q θ ˙ = c o s θ s i n θ t a n φ / L v
where θ represents the heading angle of the vehicle, α represents the Ackermann angle of the vehicle, which corresponds to the front wheel steering angle of the vehicle, L represents the wheelbase of the vehicle, and v represents the speed at the center point of the rear axle of the vehicle.

3. Automatic Parking Path-Planning Method

3.1. Narrow Parking Spaces

The size of a standard parking space is regulated by considering factors such as the width of the vehicle, the minimum turning radius of the vehicle, and parking safety. Let the width of the standard parking space be W P 0 . Generally, any parking space narrower than W P 0 can be classified as a narrow parking space. However, the degrees of narrowness affect parking path planning. If the width of the parking space, denoted as W P , is slightly narrower than W P 0 , specifically within the range of W P 1 W P W P 0 , as shown in Figure 2, the vehicle can be parked in one step using the arc–line combination parking algorithm. When the width of the parking space falls within the range of W P 2 W P W P 1 , the vehicle cannot be parked in one step, and if W P W P 2 , the vehicle cannot be parked at all. In this study, we only consider multi-step parking, where a narrow parking space is defined as W P 2 W P W P 1 , which is approximately 1.25–1.35 times the width of the vehicle body, denoted as W V , namely, W P 1 1.35 W V and W P 2 1.25 W V .

3.2. Principles of the Arc–Line Combination Planning Algorithm

The arc–line combination vertical parking algorithm is a geometric algorithm, which is composed of multiple straight lines and arcs [15]. The radius of the arc corresponds to the minimum turning radius of the vehicle. An arc–line combination multi-step vertical parking path-planning diagram is shown in Figure 3. The parking path is composed of straight lines P0P1 and P4P5 as well as arcs P1P2, P2P3, and P3P4. The initial parking position is denoted as point P0, while the final parking position is denoted as point P5.
The first arc path is P1P2.
The vehicle reaches the initial parking position P0 and starts parking within a safety threshold ψ; when the left rear of the vehicle and the left side of the parking space reach the safety threshold, the first arc P1P2 parking is completed.
The arcs are obtained using their parameters. The angle parameter φ 0 , which represents the angle between the straight line OE and the straight line OD is obtained from Equation (3) and is shown in Figure 4.
φ 0 = a r c t a n D E O E
The parameter corresponding to the first arc P1P2 is φ 1 . When the vehicle starts reversing from the initial parking position P0, the left rear of the vehicle and the left side of the parking space reach the safety threshold. At this point, the left parking space vertex coordinates are denoted as D′ (XD′, YD′). Based on the horizontal coordinate value of D’ and the rear axle center coordinate, the angle of the first arc ( φ 1 ) can be determined.
φ 1 = a r c s i n X 1 X D O D φ 0
The second arc path is P2P3.
The parameters corresponding to the second arc path P2P3 are O2 and φ 2 . The coordinates of the circle’s center O2 (xo2, yo2) can be determined using the coordinates of the rear axle center Q2 of the vehicle and the vehicle’s heading angle. The relationship between the center O2 and center O3 can be obtained from the geometric relationship between the tangent of the second and third arcs.
x o 3 x o 2 2 + y o 3 y o 2 2 = 2 R m i n 2
The parameters corresponding to the third arc, P3P4, are O3 and φ 3 . As the arc P3P4 is tangent to the straight line P4P5, the coordinates of O3 (xo3, yo3) can be determined.
Based on the above analysis, the angle φ 2 corresponding to the second arc path, P2P3, can be obtained.
φ 3 = a r c t a n y o 2 y o 3 x o 3 x o 2
φ 2 = π 2 φ 3 φ 1

3.3. Principles of the Particle Swarm Optimization Planning Algorithm

The particle swarm optimization (PSO) algorithm is a random search algorithm known for its high precision, fast convergence speed, few parameters, and ease of implementation. With cooperation, the population is optimized. Each potential solution of an optimization problem is considered a bird in the search space, called a “particle” [16,17]. Each particle possesses a position determined with an objective function and a velocity that determines the flight distance and direction. All particles follow the current optimal particle to search in the solution space, aiming to find the optimal solution with multiple iterations.
Assuming an optimization problem is defined in a d-dimensional space, the number of particles in the population is S k , and the position, velocity, and cost function values of the particles are X   i = ( x i 1 , x i 2 , ,   x i D ) , V i = ( v i 1 ,   v i 2 , ,   v i D ) , f ( X i ) , respectively. The optimal particle within the population is denoted as P i , which refers to the particle with the smallest cost function value of the current particle in all iterations. The global optimum is represented as P g , which refers to the particle with the smallest cost function value among all optimal particles.
The velocity and position update formulas for the particles are as follows.
v i d k + 1 = η v i d k + c 1 r 1 [ P i d x i d k ] + c 2 r 2 [ P g d x i d k ]
x i d k + 1 = x i d k + v i d k + 1 , 1 k k m a x , 1 i N P , 1 d D
η k = η i n i ω e n d k m a x k k m a x + η e n d
Among these formulas, N P represents the number of particles. Generally, a larger particle swarm size makes it easier to find the global optimal solution. k m a x denotes the maximum number of iterations. v i d k represents the d-dimensional velocity component of the i-th particle in the k-th iteration, while x i d k represents the d-dimensional position component of the i-th particle in the k-th iteration. P i d represents the d-dimensional position component of the optimal particle i , and P g d represents the d-dimensional position component of the global optimum. The variables r 1 and r 2 are random functions that generate random numbers between 0 and 1. The parameter η represents the inertia weight. Introducing an inertia weight provides the particle swarm with a more vital global search ability in the early stages and a more focused local optimization ability in the later stages. Increasing η can improve the global search ability, while reducing η can enhance the local search ability. Finding a reasonable value for η is the key to achieving an efficient search and avoiding falling into local optima. The parameters c 1 and c 2 are acceleration coefficients that determine the weights for particle and global optimization guidance. c 1 affects the optimal local value, while c 2 affects the optimal global value.
PSO stop criterion: the end of the particle swarm optimization algorithm is either when the number of iterations reaches the maximum value or when the optimization result reaches the error threshold.
The PSO algorithm must find an optimal parking position and angle in vertical parking. Therefore, the position and angle of the vehicle are used as parameters of the objective function; specifically, the position and angle of the vehicle are used as the state vectors of the particles, and the objective function is the path function of arc straight line planning. By determining the independent variable that minimizes the objective function and the starting point of parking, the parking point position information of the parking point can obtained based on the vehicle’s minimum turning radius and the objective function’s minimum value. The objective function is used to evaluate the position, and with continuous attempts and adjustments, the algorithm searches for the optimal solution, resulting in a fast and efficient vertical parking process.

3.4. Principles of the Hybrid A* Planning Algorithm

The Hybrid A* algorithm differs from the traditional A* algorithm in several ways. It is a state-space heuristic algorithm that incorporates heuristic information during the search process. This algorithm is specifically designed for vehicle kinematics and is suitable for gridded parking environments. In the Hybrid A* algorithm, each location in the gridded state space is evaluated to determine the best position. From this position, a subsequent search is performed toward the destination. This approach ensures that the search path adheres to the vehicle’s kinematics and allows for efficient navigation in the parking environment [18,19,20].
The Hybrid A* algorithm is commonly used in various path-planning applications, including automatic parking path planning [21]. It extends from the parent node with various steering operations (left turn, right turn, or no turn), and combines the vehicle kinematics model to determine new nodes, ensuring the continuity of motion between the child node and the parent node. As a result, the path generated using the Hybrid A* algorithm satisfies the requirements of vehicle driving, as shown in Figure 5.
In path planning, three-dimensional coordinates ( x ,   y ,   θ ) describe the vehicle’s posture. Where x represents the horizontal coordinate, y represents the vertical coordinate, and θ represents the heading angle of the vehicle. The node expansion process of the Hybrid A* algorithm is shown in Figure 6. In this process, N i 1 and N i represent the previous node and the current node, respectively. The basic principles of the algorithm are shown in Equations (11)–(15).
β = L a r c W v × t a n α
R i = L a r c β
x i = x i 1 + R i [ s i n ( θ i 1 + β ) s i n ( θ i 1 ) ]
y i = y i 1 R i [ c o s ( θ i 1 + β ) + c o s ( θ i 1 ) ]
θ i = θ i 1 + β
where L a r c represents the step size of each extension of the Hybrid A* algorithm, α represents the steering angle of the vehicle, and W v represents the track width. The angle of β , corresponding to the arc between the N i 1 and N i nodes, can also be directly set as the minimum turning radius of the vehicle during the expansion process.
The Hybrid A* algorithm considers the influence of the front wheel angle on node expansion, resulting in a three-dimensional coordinate representation ( x ,   y ,   θ ) . At the same time, two heuristic functions are considered: the unconstrained heuristic function and the constrained heuristic function. Among them, the unconstrained heuristic function ignores the non-holonomic constraints of the vehicle and considers the environmental obstacles. Therefore, it is not necessary to consider the kinematic constraints of the vehicle, such as the heading angle. On the other hand, the constrained heuristic function ignores environmental obstacles and considers vehicle non-integrity constraints. The unconstrained heuristic function value is used to calculate the constrained heuristic function value, and the Reeds–Shepp curve is used to calculate the size of the heuristic function value.

3.5. The Parking Path Evaluation Function

The planned path length is commonly used as an indicator to measure the performance of standard spaces parking. However, it is not suitable for evaluating narrow-space parking due to the frequent changes in speed and direction. In this paper, we propose a multi-objective evaluation function for narrow parking space paths to evaluate the comprehensive performance of parking algorithms.
1.
The number of positive and negative transitions in vehicle speed, denoted as R, can be determined by examining the speed direction at previous and subsequent moments. Positive transitions occur when the vehicle speed changes from a lower value to a higher value, while negative transitions occur when the vehicle speed changes from a higher value to a lower value. By analyzing these transitions, we can gain insights into the dynamics and changes in the vehicle’s speed during the parking process.
2.
The total length of the path.
L = i = 1 N x i + 1 x i 2 + y i + 1 y i 2 1 2
3.
Path Smoothness.
The minimum curvature of the path curve can represent the smoothness of the path curve. The smaller the minimum curvature, the better the smoothness of the path curve. The average minimum curvature of the entire parking path curve can be compared.
ρ ¯ = m e a n ρ i 1 m i n , ρ i 2 m i n , ρ i 3 m i n
where ρ i 1 m i n represents the minimum curvature of the first path curve of the i-th path point; ρ i 2 m i n represents the minimum curvature of the second segment of the curve at the i-th path point; and ρ i 3 m i n represents the minimum curvature of the third segment of the curve at the i-th path point.
The multi-objective evaluation function value, denoted as S, for the planning path of these three planning algorithms is obtained by separately calculating the values of the above three evaluation indicators and then performing a weighted summation. The specific calculation of S depends on the weights assigned to each evaluation indicator. By combining the individual indicator values with their respective weights, the multi-objective evaluation function provides a comprehensive assessment of the planning path, as follows.
S = ω l L + ω r R + ω ρ ρ ¯
where ω l represents the weighted coefficient of the total path length; ω r represents the weighted coefficient of the number of positive and negative conversions of vehicle speed; and ω ρ represents the weighted coefficient of the planned path curvature.

4. Path-Planning Simulation

4.1. Parking Scene Settings

According to the “Specification for the Setting of Parking Spaces on Urban Roads,” (GA/T 850—2021 of China) the width of vertical parking spaces for small cars is 2.5–2.7 m. The width of the single-lane turning lane is not less than 3.5 m, while the width of the double lane is not less than 5 m. The turning section should meet the needs of one vehicle turning at a time. This paper selects a small sedan as the research object, with a width of 1.737 m, a length of 4.579 m, a minimum turning radius of 5.6 m, and a safety threshold between vehicle and parking space, ψ, ψ = 0.1 m. According to the above definition of narrow parking spaces, this paper sets the parameters for narrow parking spaces as shown in Table 1.

4.2. Simulation

To select a more suitable parking planning algorithm for narrow parking spaces, the arc–line combination, Hybrid A*, and particle swarm optimization algorithms are modeled and a narrow parking scene is established in MATLAB. Then, with the given starting point and different parking space widths, the three algorithms are used to generate different planned paths. The path length, the number of positive and negative conversions of vehicle speed, and the curvature are obtained to compare the performance of the algorithms based on the multi-objective function. The values obtained from the multi-objective function indicate the fitness of each algorithm in the narrow parking environment.
The following is a comparison of the paths planned with the three algorithms when the parking space width is a standard size of 2.5 m, as shown in Figure 7.
It can be seen that the path planned using the Hybrid A* algorithm consists of two arcs and a straight line, whereas the path planned with the arc–line combination and particle swarm optimization includes three arcs and a straight line. Moreover, the first arc in the Hybrid A* planning is significantly smaller compared with the arc–line combination and particle swarm optimization. As a result, to complete the parking operation, the path of the Hybrid A* planning needs to be adjusted once outside the parking space to enter it, while the arc straight line and the particle swarm optimization paths need to be adjusted twice outside the parking space. In the following simulation, we will compare the widths of different parking spaces.
The path curve can be discretized into numerous path points, each containing ( x ,   y ) coordinate values. Subsequently, according to the path length calculation formula in the parking path evaluation indicator in Section 3.5, the arc–line combination, Hybrid A*, and particle swarm optimization path lengths can be calculated. Based on each coordinate point, the curvature calculation formula can be used to obtain the curvature value corresponding to each arc segment.

4.2.1. The Arc–Line Combination

The path length and curvature for the arc–line combination planning algorithm were simulated using MATLAB for various parking space widths. The results of the simulation are presented below.
The curvature diagram below illustrates the simulated path using the arc–line planning algorithm in three narrow parking spaces with varying widths. Although the parking spaces have different widths, the curvature mutations remain consistent. From Figure 8, the curvature of the first arc has two mutation points, the second arc has two mutation points, and the third arc has two mutation points. The comparison information of path length and reverse times simulated using MATLAB for different parking space widths can be seen in Table 2.

4.2.2. Hybrid A*

The path length and curvature of the Hybrid A* planning algorithm were simulated using MATLAB for various parking space widths. The results of the simulation are presented below.
The diagram below illustrates the curvature map of the simulated path using the Hybrid A* planning algorithm in three narrow parking spaces with varying widths. Although the parking spaces have varying widths, the curvature mutations remain consistent. From Figure 9, the curvature of the first arc has two mutation points, the second arc has two mutation points, and the third arc has two mutation points. The comparison information of path length and reverse times simulated using MATLAB for different parking space widths can be seen in Table 3.

4.2.3. Particle Swarm Optimization

The particle swarm parameters are set based on practical engineering experience to ensure reasonable optimization. The path length and curvature of the particle swarm optimization algorithm were simulated using MATLAB for different parking space widths. The results are presented below.
The diagram below illustrates the curvature of the simulation path using the particle swarm optimization algorithm in narrow parking spaces. From Figure 10, the curvature of the first arc has two mutation points, the second arc has two mutation points, and the third arc has two mutation points. The curvature map planned with the particle swarm optimization algorithm is similar to the arc–line planning algorithm. However, the segmented arcs in Figure 10 exhibit faster changes in curvature compared with the arc–line combination algorithm, resulting in a less smooth curvature profile. Additionally, the second mutation in the third arc appears to be more severe than the mutation in the straight arc. The comparison information of path length and reverse times simulated using MATLAB for different parking space widths can be seen in Table 4.
Based on the above simulation results, it can be found that the path needs to be adjusted multiple times to park smoothly due to the narrow space, regardless of whether the arc–line combination, Hybrid A*, or particle swarm optimization algorithms are used. From the three tables, it can be observed that the path planned with the arc–line combination algorithm has the longest length. Additionally, the three planning algorithms exhibit the same number of positive and negative vehicle speed conversions, indicating an equal number of reverse times. Analyzing the path length, the number of positive and negative vehicle speed transitions, and the number of vehicle position adjustments outside the depot in Figure 7, it can be concluded that the parking operation time of the path planned with the geometric algorithm is relatively long, and the efficiency is relatively low.
By analyzing the paths in Figure 7 and the information provided in the tables, it can be found that the Y values of the adjusted coordinates for the arc–line combination and particle swarm optimization planning paths outside the garage are relatively large. This indicates that the vehicle’s position is farther away from the garage compared with the Hybrid A* algorithm. Considering that the width of the driving lane is 5 m, being further away from the garage increases the risk of a vehicle coming into contact with the curb, opposite vehicles, or walls, which can result in parking failure.
The simulation results demonstrate that the Hybrid A* algorithm is particularly suitable for narrow parking spaces. It successfully parks a vehicle in a parking space with a width of 2.1 m, while both the arc–line combination and Hybrid A* algorithms achieve parking successfully at a width of 2.2 m. Furthermore, all three algorithms successfully park the vehicle in parking spaces with a width of 2.3 m. This indicates that the Hybrid A* algorithm is most suitable when dealing with a relatively narrow parking environment.
Based on the multi-objective evaluation function, a comparison of the results from three parking planning algorithms is presented in Table 5.
Based on comprehensive analysis, it can be observed that the arc–line combination planning algorithm has the longest path among the three evaluation indicators, while the particle swarm optimization has the shortest path. The number of positive and negative vehicle speed transitions is the same for all three algorithms. In terms of curvature, the Hybrid A* algorithm exhibits the smallest average minimum curvature among the three arcs, while the particle swarm optimization algorithm has the largest curvature. When considering the final evaluation function S, the Hybrid A* algorithm has the lowest score, indicating its suitability for narrow parking spaces. On the other hand, the arc–line combination algorithm has the highest score, significantly differing from the other two other planning algorithms. This suggests that the arc–line combination algorithm is not suitable for narrow parking spaces. Although the particle swarm optimization algorithm has the same evaluation score as Hybrid A* for a 2.3 m wide parking space and the shortest path, it is important to note that the path is not as smooth as the Hybrid A* algorithm and exhibits more significant curvature mutations. Therefore, the Hybrid A * algorithm is considered more suitable for narrow parking spaces.
Although the Hybrid A* algorithm is better overall, it also has the issue of curvature discontinuity in the path curve, leading to a spot turn. In order to solve the problem of curvature discontinuity of the planned path, it is necessary to incorporate path-smoothing techniques into the optimization process to ensure a more continuous and smoother path.

5. Path-Smoothing Optimization of the B-Spline Curve and Gradient Descent Algorithm

Gradient descent is a numerical optimization algorithm known for its small storage capacity and high stability. The gradient of the function (the tangent slope of the function at this point) can effectively determine the direction in which the function value decreases the fastest; this iterative process allows the algorithm to approach the optimal solution step by step [22,23]. The gradient descent algorithm can optimize the curvature of the smoother curve and adjust the curvature of the curve to meet the kinematic requirements of vehicle driving. However, it is important to note that if the curve is not smooth in certain areas, there may be no gradient available, rendering the gradient descent algorithm unable to optimize in those specific places.
The optimization of parking paths in narrow spaces involves selecting a series of control points, including the starting and ending points of the curve. To address the limitations of the gradient descent algorithm in handling non-smooth paths, the B-spline curve is utilized for path smoothing. The B-spline curve is known for its multi-order derivative continuity, which ensures a smooth and continuous path. In the case of narrow parking spaces, the parking paths consist of multiple segments of arcs and straight lines. To optimize each arc in the multi-step parking process, B-spline curves are used. By utilizing the optimized smooth curve, the gradient descent algorithm can effectively optimize the path curvature and ensure a smoother parking path.

5.1. Path Smoothing Optimization Based on the B-Spline Curve

The B-spline curve is an improved curve based on the Bézier curve [24]. It can not only change the order of the curve but also realize the local change in the curve. Assuming that there are n control vertices, the k-order B-spline curve function is expressed as follows.
P u = i = 0 n P i N i , k u
In the above formula, k = {   0 ,   1 ,   2 , ,   n   } and U = {   u 0 ,   u 1 ,   ,   u ( n + k + 1 )   } represents the node vector sequence. P i denotes the ith curve equation corresponding to the i-th point, and N ( i ,   k ) ( u ) is the k-th B-spline basis function. The recurrence formula is as follows.
d e f i n e 0 0 = 0                                                                                                                                                                                                 N i , 0 u = 1 ,     u i u u i + 1 0 ,         o t h e r                                                                                                                                                               N i , k u = ( u u i ) N i , k 1 u u i + k u i + ( u i + k + 1 u ) N i + 1 , k 1 u u i + k + 1 u i + 1 ,     u k u u n + 1
According to the structure of the B-spline curve, its shape is determined by the node vector and the control point of the piecewise mixed function. Then, according to the distribution of the midpoint of the node vector sequence U, the B-spline curve can be classified into four types [25]: uniform B-spline curve, quasi-uniform B-spline curve, piecewise Bézier curve, and non-uniform B-spline curve.
When optimizing the parking path, the starting point and the endpoint of parking cannot be ignored. The quasi-uniform B-spline curve is selected in this paper as it satisfies the requirements of passing through the starting points and endpoints. This curve closely resembles the original trajectory, allowing for the preservation of the original path’s shape to the maximum extent. Therefore, this paper chooses this curve to optimize the parking path. In the case where the value of k in Equation (21) is 3, the expression for the cubic quasi-uniform B-spline can be obtained.
P u = i = 0 3 P i N i , k u
Then, this paper uses the B-spline curve to fit each path arc to obtain a smooth path. The specific algorithm process is as follows: first, path planning is carried out to obtain the path point set, and the opposite change position of the vehicle movement direction is judged. Then, multiple arc path curves are obtained by segmenting the complete path, and B-spline curves are used to optimize each path curve. Finally, the final smooth path is obtained by stitching the optimized path curves.

5.2. Path Curvature Optimization Based on Gradient Descent

To ensure that the curvature of the optimized path, denoted as X i = ( x i ,   y i ) , i [   i ,   N   ] , satisfies the minimum turning radius constraint of the vehicle, an objective function is designed for re-optimization. The goal is to control the planned path curvature so that it does not exceed the maximum turning curvature of the vehicle.
F = ω c i = 1 N 1 σ c i X i k m a x
where i represents the change in tangential angle at the vertex, ω c represents the weight of the curvature term, σ c is the penalty function, X i = X i X i 1 is the displacement at point X i , and i represents the angle change in the path at the point X i . Additionally, k m a x represents the maximum curvature of the vehicle during turning; among them,
i = t a n 1 y i + 1 x i + 1 + t a n 1 y i x i
The curvature is affected by the derivative of the three points X i , X i + 1 , and X i 1 and the curvature k i = i X i ; therefore,
i = c o s 1 X i T X i + 1 X i T X i + 1
The partial derivatives of curvature to X i , X i + 1 , and X i 1 are calculated, respectively, and the following results are obtained.
k i X i = 1 X i i c o s i c o s i X i i X i 2 X i X i
k i X i + 1 = 1 X i i c o s i c o s i X i + 1
k i X i 1 = 1 X i i c o s i c o s i X i 1 i X i 2 X i X i 1
The gradient formula of curvature is
F X i = ω c ω i 1 k i X i 1 + ω i k i X i + ω i + 1 k i X i + 1
For Equations (25)–(27), according to the curvature gradient formula, the following can be obtained
i c o s = c o s 1 c o s i c o s i = 1 1 c o s 2 i 1 / 2
In summary, the algorithm calculates curvature penalty term for each path point based on the current path sequence. These curvature terms are weighted and summed to form the overall objective function. In each iteration, the coordinate correction value for each point on the path is obtained using gradient derivation of the objective function. Then, the original coordinate values of each point are adjusted by adding the correction value, resulting in a new path optimized through one iteration of gradient descent. The algorithm continues this process for a set total number of iterations, M, until convergence to the final optimized path is achieved.
According to the same path information of the Hybrid A* algorithm in Section 4.2 and the MATLAB simulation, the following figure shows the curvature comparison after Hybrid A* path optimization.
Figure 11a shows a comparison of the curvature for the first arc parking path of the Hybrid A* algorithm before and after applying the B-spline curve and the gradient descent algorithm. Similarly, Figure 11b compares the curvature for the second arc parking path, and Figure 11c compares the curvature for the third arc parking path. In Figure 11a,b, the mean curvature becomes smaller after applying the B-spline curve and the gradient descent algorithm. Although the curvature in Figure 11c becomes more significant, the curvature of all three path curves remains continuous without mutation. This ensures that the curvature change in parking path planning is continuous and satisfies the minimum turning radius constraint of the vehicle.
The Hybrid A* path curve with a width of 2.3 m and the optimized path curve of 3.2 parking spaces are selected. The multi-objective evaluation function compares the multi-objective function S values before and after optimization. The simulation results can be seen in Table 6.
For a narrow space parking, the vehicle needs frequent small steering, which results in large path curvature and impacts the parking safety significantly; therefore, it should be given the maximum weight. It can be seen from the simulation results that the number of positive and negative conversions of the vehicle speed is the same in the narrow parking environment. Therefore, the path curvature, the path length, and the number of positive and negative conversions are weighted as 70%, 20%, and 10%, respectively. The three evaluation indicator values are normalized using the scale transformation method shown in (30).
X L = X L m i n X L i ,   X R = X R m i n X R i ,   X ρ = X ρ m i n X ρ i
Based on the comprehensive analysis, the curvature of the Hybrid A* path is effectively optimized using the B-spline curve and the gradient descent algorithm. The average value of the minimum curvature was reduced by 0.005 m−1 compared with the curvature before optimization. This value is also lower than the curvature of the arc–line combination and the particle swarm optimization algorithm. Although the optimized Hybrid A* algorithm results in a slightly longer path length, with an increase of 1.54 m, the function value after optimization is reduced by 0.07. As shown in Table 7, after the three evaluation indicator values are normalized, the multi-objective evaluation function value of the Hybrid A* algorithm is the largest. This finding indicates that the optimized Hybrid A* algorithm is more suitable for a narrow parking environment, aligning with the results presented in Table 6.
The simulation results show that in the narrow parking environment, the path of the Hybrid A* algorithm optimized with the B-spline curve and the gradient descent algorithm proposed in this paper is better overall. Compared with the Hybrid A* algorithm, the proposed algorithm can further improve the smoothness of the planned path. Compared with the arc–line combination, it can generate a trajectory with a smooth path and speed. Compared with the particle swarm optimization algorithm, the actual motion constraints of the object are considered, which makes it generate a more realistic path. However, the Reed–Shepp curve is used in the proposed algorithm for path generation, which leads to a higher calculation load.

6. Conclusions

This paper introduces the concept of a narrow parking space and provides a definition based on the standard when the arc–line combination parking algorithm fails to park the vehicle in a single step. The parking space is defined as a narrow parking space when the width of the parking space is approximately 1.25–1.35 times the width of the vehicle body, denoted as W P 1 1.35 W P and W P 2 1.25 W P . Aiming at the narrow parking space and narrow parking environment, a multi-objective function is proposed to evaluate the applicability of three planning algorithms, namely, the arc straight–line, Hybrid A*, and particle swarm optimization algorithms, in a narrow parking space.
The curvature of the parking path curve is discontinuous, and severe mutations result in spot turns according to the simulation results and the analysis of narrow parking environments. This paper proposes an algorithm based on the B-spline curve and gradient descent algorithm to optimize the path to solve the problem of discontinuous and abrupt curvature of the path curve. The optimized path curvature is smooth and satisfies the minimum turning radius constraint of the vehicle.
However, certain aspects such as speed planning, parking space detection and recognition, and parking path following control are not considered in this paper. In the future, variable speed planning and the recognition of narrow parking spaces by vehicles and the following control of vehicles will be considered.

Author Contributions

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

Funding

This research was funded by the National Natural Science Foundation of China, grant number U22A2069.

Data Availability Statement

The data and models that support the results of this study are included in this article. The code generated or used during the study is available from the corresponding author upon request.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Al-Smadi, A.; Msallam, M. Vehicle Auto Parking System. In Proceedings of the 2022 9th International Conference on Electrical and Electronics Engineering (ICEEE), Alanya, Turkey, 29–31 March 2022. [Google Scholar] [CrossRef]
  2. Das, S.; Sheerin, M.R.; Nair, S.R.P.; Vora, P.B.; Dey, R.; Sheta, M.A. Path Tracking and Control for Parallel Parking. In Proceedings of the 2020 International Conference on Image Processing and Robotics (ICIP), Negombo, Sri Lanka, 6–8 March 2020. [Google Scholar] [CrossRef]
  3. Cai, L.; Guan, H.; Zhang, H.; Jia, X.; Zhan, J. Multi-maneuver vertical parking path planning and control in a narrow space. Robot. Auton. Syst. 2021, 149, 103964. [Google Scholar] [CrossRef]
  4. Zheng, Y.; Wang, Z.; Li, L.; Zhang, L. Hierarchical Trajectory Planning for Narrow-Space Automated Parking with Deep Reinforcement Learning: A Federated Learning Scheme. Sensors 2023, 23, 4087. [Google Scholar] [CrossRef]
  5. Zhao, B.Q.; Xin, C.; Man, J.H.; Liang, C.; Fang, J.J. A novel Path Planning Methodology for Automated Valet Parking Based on Directional Graph Search and Geometry Curve. Robot. Auton. Syst. 2020, 132, 103606. [Google Scholar] [CrossRef]
  6. Jiang, M.; Peng, Y.; Huang, W.; Xu, D. Polynomial Curve-optimized Vertical Parking Path Planning and Tracking. J. F. Univ. (Nat. Sci. Ed.) 2023, 51, 76–82. [Google Scholar] [CrossRef]
  7. Zhang, J.; Shi, Z.; Yang, X.; Zhao, J. Trajectory planning and tracking control for autonomous parallel parking of a non-holonomic vehicle. Meas. Control. 2020, 53, 1800–1816. [Google Scholar] [CrossRef]
  8. Yu, L.; Wang, X.; Wu, B.; Hou, Z.; Wu, Y. Path Planning Optimization and Tracking of Parallel Parking for Driverless Vehicles. J. J Univ. (Nat. Sci. Ed.) 2022, 43, 519–523. [Google Scholar] [CrossRef]
  9. Ahn, J.; Kim, M.; Park, J. Biased Target-tree* Algorithm with RRT* for Reducing Parking Planning Time. In Proceedings of the IEEE Intelligent Vehicles Symposium (IV), Anchorage, AK, USA, 4–7 June 2023. [Google Scholar] [CrossRef]
  10. Zhang, J.; Bu, C.; Wang, C.; Zhao, J. Parallel Parking Path Planning and Tracking Control for Wire-four-wheel Steering Vehicle. J. H. Univ. (Nat. Sci. Ed.) 2021, 48, 44–50. [Google Scholar] [CrossRef]
  11. Sedighi, S.; Nguyen, D.-V.; Kuhnert, K.-D. Guided Hybrid A-star Path Planning Algorithm for Valet Parking Applications. In Proceedings of the 2019 5th International Conference on Control, Automation and Robotics, Beijing, China, 19–22 April 2019. [Google Scholar] [CrossRef]
  12. Bai, J.; Xu, Y.; Ji, J.; Chen, Y.; Zhang, Y. Path Planning for Automated Valet Parking Based on Graph Search and Geometry Curve. J. C. Univ. Technol. (Nat. Sci. Ed.) 2022, 36, 115–125. [Google Scholar] [CrossRef]
  13. Xiong, L.; Gao, J.; Fu, Z.; Xiao, K. Path Planning for Automatic Parking Based on Improved Hybrid A* Algorithm. In Proceedings of the 2021 5th CAA International Conference on Vehicular Control and Intelligence, Tianjin, China, 29–31 October 2021. [Google Scholar] [CrossRef]
  14. Cai, L.; Guan, H.; Zhou, Z.; Xu, F.; Jia, X.; Zhan, J. Parking Planning Under Limited Parking Corridor Space. IEEE TITS 2023, 24, 1962–1981. [Google Scholar] [CrossRef]
  15. Zhou, R.; Liu, X.; Cai, G. A New Geometry-Based Secondary Path Planning for Automatic Parking. Int. J. Adv. Robot. Syst. 2020, 17, 1–17. [Google Scholar] [CrossRef]
  16. Van Nguyen, L.; Phung, M.D.; Ha, Q.P. Game Theory-Based Optimal Cooperative Path Planning for Multiple UAVs. IEEE Access 2022, 10, 108034–108045. [Google Scholar] [CrossRef]
  17. Daniali, S.M.; Khosravi, A.; Sarhadi, P.; Tavakkoli, F. An Automatic Parking Algorithm Design Using Multi-Objective Particle Swarm Optimization. IEEE Access 2023, 11, 49611–49624. [Google Scholar] [CrossRef]
  18. YZhao, Y.; Zhu, Y.; Zhang, P.; Gao, Q.; Han, X. A Hybrid A* Path Planning Algorithm Based on Multi-objective Constraints. In Proceedings of the 2022 Asia Conference on Advanced Robotics, Automation, and Control Engineering (ARACE), Qingdao, China, 26–28 August 2022. [Google Scholar] [CrossRef]
  19. Lian, J.; Ren, W.; Yang, D.; Li, L.; Yu, F. Trajectory Planning for Autonomous Valet Parking in Narrow Environments with Enhanced Hybrid A* Search and Nonlinear Optimization. IEEE TIV 2023, 8, 3723–3734. [Google Scholar] [CrossRef]
  20. Huang, J.; Liu, Z.; Xue, M.; Feng, H.; Hong, Y. Search-Based Path Planning Algorithm for Autonomous Parking: Multi-Heuristic Hybrid A*. In Proceedings of the 2022 34th Chinese Control and Decision Conference, Hefei, China, 15–17 August 2022. [Google Scholar] [CrossRef]
  21. Zhao, L.; Mao, R.; Bai, Y. Local Path Planning for Unmanned Surface Vehicles based on Hybrid A* and B-spline. In Proceedings of the 2022 IEEE International Conference on Unmanned Systems, Guangzhou, China, 28–30 October 2022. [Google Scholar] [CrossRef]
  22. Luo, S.; Li, X.; Sun, Z. An Optimization-based Motion Planning Method for Autonomous Driving Vehicle. In Proceedings of the 2020 3rd International Conference on Unmanned Systems (ICUS), Harbin, China, 27–28 November 2020. [Google Scholar] [CrossRef]
  23. Zhang, S.; Yao, J.; Wang, R.; Tian, Y.; Wang, J.; Zhao, Y. Selection of inspection path optimization scheme based on analytic hierarchy process and inspection experimental study. J. Mech. Sci. Technol. 2023, 37, 355–366. [Google Scholar] [CrossRef]
  24. Wang, D.; Zheng, S.; Ren, Y.; Du, D. Path Planning Based on the Improved RRT* Algorithm for the Mining Truck. Comput. Mater. Contin. 2022, 71, 3571–3587. [Google Scholar] [CrossRef]
  25. Song, J.; Zhang, W.; Wu, X.; Cao, H.; Gao, Q.; Luo, S. Laser-based SLAM automatic parallel parking path planning and tracking for passenger vehicle. IET Intell. Transp. Syst. 2019, 13, 1557–1568. [Google Scholar] [CrossRef]
Figure 1. The simplified vehicle kinematics model.
Figure 1. The simplified vehicle kinematics model.
Electronics 12 04203 g001
Figure 2. Vehicle parking position diagram and a narrow parking space diagram.
Figure 2. Vehicle parking position diagram and a narrow parking space diagram.
Electronics 12 04203 g002
Figure 3. Multi-step path planning.
Figure 3. Multi-step path planning.
Electronics 12 04203 g003
Figure 4. The first arc path P1P2.
Figure 4. The first arc path P1P2.
Electronics 12 04203 g004
Figure 5. Hybrid A* extended node diagram.
Figure 5. Hybrid A* extended node diagram.
Electronics 12 04203 g005
Figure 6. New nodes generation principle of Hybrid A*.
Figure 6. New nodes generation principle of Hybrid A*.
Electronics 12 04203 g006
Figure 7. Paths of the three algorithms.
Figure 7. Paths of the three algorithms.
Electronics 12 04203 g007
Figure 8. Three-segment arc path curvatures of the arc–line combination algorithm.
Figure 8. Three-segment arc path curvatures of the arc–line combination algorithm.
Electronics 12 04203 g008
Figure 9. Three-segment arc path curvature of the Hybrid A* algorithm.
Figure 9. Three-segment arc path curvature of the Hybrid A* algorithm.
Electronics 12 04203 g009
Figure 10. Three-segment arc path curvature of the particle swarm optimization algorithm.
Figure 10. Three-segment arc path curvature of the particle swarm optimization algorithm.
Electronics 12 04203 g010
Figure 11. Three arc path curvatures of the optimized Hybrid A* algorithm. (a) The curvatures of the first arc with and without optimization. (b) The curvatures of the second arc with and without optimization. (c) The curvatures of the third arc with and without optimization.
Figure 11. Three arc path curvatures of the optimized Hybrid A* algorithm. (a) The curvatures of the first arc with and without optimization. (b) The curvatures of the second arc with and without optimization. (c) The curvatures of the third arc with and without optimization.
Electronics 12 04203 g011
Table 1. Parameters of narrow parking scenarios.
Table 1. Parameters of narrow parking scenarios.
Scene
Parameters
Parking Space Width
SW/m
Parking Space Length
SL/m
Length of Driving
Passage L/m
Width of Driving
Passage W/m
Vehicle’s
Initial Heading Angle
θmin/(°)
Value2.3~2.15.09.05.0−10~10
Table 2. Planned paths of the arc–line combination algorithm for different parking spaces.
Table 2. Planned paths of the arc–line combination algorithm for different parking spaces.
Evaluation IndicatorsValues
W p = 2.3 W p = 2.2 W p = 2.1
Total path length/m11.3911.3711.21
Positive and negative speed conversion times/time222
Distance between vehicle and parking space/m0.20.10.09
Planned pathElectronics 12 04203 i001Electronics 12 04203 i002Electronics 12 04203 i003
Table 3. Planned paths of the Hybrid A* algorithm for different parking spaces.
Table 3. Planned paths of the Hybrid A* algorithm for different parking spaces.
Evaluation IndicatorsValues
W p = 2.3 W p = 2.2 W p = 2.1
Total path length/m9.489.509.53
Positive and negative speed conversion times/time222
Distance between vehicle and parking space/m0.20.10.09
Planned pathElectronics 12 04203 i004Electronics 12 04203 i005Electronics 12 04203 i006
Table 4. Planned paths of the particle swarm optimization algorithm for different parking spaces.
Table 4. Planned paths of the particle swarm optimization algorithm for different parking spaces.
Evaluation IndicatorsValues
W p = 2.3 W p = 2.2 W p = 2.1
Total path length/m9.479.489.50
Positive and negative speed conversion times/time222
Distance between vehicle and parking space/m0.10.090.08
Planned pathElectronics 12 04203 i007Electronics 12 04203 i008Electronics 12 04203 i009
Table 5. Performance of the three algorithms.
Table 5. Performance of the three algorithms.
AlgorithmTotal Path Length/mPositive and Negative Speed
Conversion Times/Time
ρ ¯ S
Arc–line
combination
11.3920.15979.84
Hybrid A*9.4820.15174.25
PSO9.4720.16178.24
Table 6. Performance comparison between optimized Hybrid A* algorithm and the other algorithms.
Table 6. Performance comparison between optimized Hybrid A* algorithm and the other algorithms.
AlgorithmTotal Path Length/mPositive and Negative Speed Conversion Times/Time ρ i ¯ S
Hybrid A* (without optimization)9.4820.15174.25
Hybrid A* (optimization)10.0220.14674.18
PSO9.4720.16178.24
Arc–line combination11.3920.15979.84
Table 7. Normalized performance comparison between the optimized Hybrid A* algorithm and the other algorithms.
Table 7. Normalized performance comparison between the optimized Hybrid A* algorithm and the other algorithms.
Algorithm X L /m X R /Time X ρ S
Hybrid A* (without optimization)0.99910.9670.887
Hybrid A* (optimization)0.945110.899
PSO110.9070.845
Arc–line combination0.83110.9180.819
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

Wu, Y.; Li, X.; Gao, J.; Yang, X. Research on Automatic Vertical Parking Path-Planning Algorithms for Narrow Parking Spaces. Electronics 2023, 12, 4203. https://doi.org/10.3390/electronics12204203

AMA Style

Wu Y, Li X, Gao J, Yang X. Research on Automatic Vertical Parking Path-Planning Algorithms for Narrow Parking Spaces. Electronics. 2023; 12(20):4203. https://doi.org/10.3390/electronics12204203

Chicago/Turabian Style

Wu, Yanfeng, Xuan Li, Jianping Gao, and Xinling Yang. 2023. "Research on Automatic Vertical Parking Path-Planning Algorithms for Narrow Parking Spaces" Electronics 12, no. 20: 4203. https://doi.org/10.3390/electronics12204203

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