1. Introduction
Motion planning, as a crucial part of autonomous driving systems (ADS), has received a good deal of interest from the academic community [
1,
2]. Specifically, creating a safe route free of collisions is the main goal. Despite extensive research on obstacle avoidance algorithms in autonomous ground vehicles (AGV), it is inappropriate to apply these algorithms to traffic scenarios without taking into account vehicle dynamics and road regulations. In order to better suit the traffic environment, the conventional algorithm should be modified to cope with the actual driving scenarios.
Many strategies for addressing trajectory planning have been studied over time by researchers: graph search [
3,
4], random sampling [
5,
6], artificial potential field (APF) [
7,
8,
9], numerical optimization [
10,
11], and AI-based techniques [
12]. For example, the two-way A-star method is used in [
3] to increase the planning algorithm’s computational efficiency. In order to solve the problem that the traditional A-star algorithm has many inflection points and a long path, the study [
4] proposed an improved A-star algorithm that increases the number of search directions. In [
6], a novel approach using the Dijkstra optimization-based rapidly exploring random tree algorithm (APSD-RRT) is suggested; it has customizable probability and sample area, and experiments are carried out to show that the proposed approach can achieve significantly better performance in terms of balancing the computation cost and performance compared to original RRT. The work [
11] developed a unified path planning system based on the model predictive controller (MPC) that selects the maneuvers’ mode automatically instead of utilizing explicit rules; it implemented a system of limitations in MPC that mandates avoiding collisions between the ego car and neighboring vehicles to guarantee safety. The study [
12] solved local-minimum-point issues by combining reinforcement learning with an enhanced black-hole potential field; the method learned how to jump out of local-minimum-point instantly without any prior knowledge.
Even though the efforts mentioned before have been successful, most of them operate assuming that an autonomous vehicle drives in fixed driving circumstances and avoids static obstacles. Rather than finding a feasible path from the starting point to the destination under mostly static conditions, trajectory planning modules of ADSs are actually required to be able to handle a variety of driving situations caused by traffic laws, obstacles, and other road users in a dynamically changing environment. This means that the planner needs to take obstacle motion into account in order to actively handle both static and dynamic traffic obstacles for a range of on-road driving scenarios. Compared to other planning methods that have been proposed, the APF method offers advantages in managing a dynamic environment with low computational costs, even with complex PFs for obstacles and road constructions.
Some studies have been carried out in this field [
13,
14,
15,
16,
17,
18,
19,
20,
21,
22]. In [
13], a controller-based approach for path planning and tracking collision avoidance is suggested, and the safety distance is added to the APF by creating a safe route in a traffic simulation. The work [
15] offered an improved APF method that uses the conventional A* method for time computation while addressing the issue of local minima. The study [
18] developed a motion planning strategy that combines an APF-based fuzzy system with a parameter scheduler for auto-mated car collision avoidance systems. In [
17] aims to address the limitations of the local minimum and the unsolvable issue of the conventional APF approach; the method is able to quantify the robot’s tendency to become trapped in the mechanical equilibrium condition in APF by detecting variations in the distance between the robot and the target over a specific time period. In [
20], an algorithm for energy-efficient local path planning is proposed; they make it possible for AGV to anticipate obstacles by incorporating future movement prediction into the APF method. An enhanced APF approach in [
22] is presented to achieve higher accuracy and efficiency by merging the fuzzy control idea to boost stability and adding an angle function to fit with the original force field function.
Despite the success of APF-based techniques, there remain several crucial issues that require solutions. Traditional APF methods, originally designed for addressing trajectory planning issues in mobile robots, exhibit slow response times and tend to produce unachievable trajectories in the presence of steering objects. In addition, APF-based techniques generally prefer to change lanes rather than follow the car, making them inappropriate for on-road driving scenarios. During the planning phase, the host vehicle in the potential field (PF) algorithm is often considered more as a particle rather than an automobile. In order to ensure the safety and practicality of APF-based path planning and collision avoidance methods for ADSs, it is imperative to address these issues.
Hence, to address the local minimum problem and enable the APF method with the ability to follow the obstacle vehicle, this study introduces a novel, improved artificial potential field-based trajectory planning method for real-time planning of autonomous ground vehicles in dynamic environments. The primary contribution of this study is outlined below: An efficient trajectory planning approach using improved APF for AGV is proposed. The APF is able to handle different kinds of obstacles, including static, deaccelerating, and moving at constant speed. By incorporating the future prediction and temporary goal mechanism, the vehicle is able to predict whether the vehicle will enter a local minimum point in advance. Then, the temporary goal will guide the vehicle toward the right lane to avoid any infeasible trajectory. Particularly, we proposed a new way to consider the velocity in the APF method; by combining vehicle velocity, the vehicle is able to perform car-following and move more like a human-driven car. Compared to the traditional APF approach method, the proposed method can plan a smoother, more feasible and collision-free trajectory while adding acceptable computation cost.
The remainder of this article is as follows:
Section 2 illustrates the construction of all kinds of potential fields (PFs) for the environment model. The planning method using PFs is described in
Section 3. Simulation results are given in
Section 4.
Section 5 offers a conclusion.
3. Trajectory Generation
In this section, the potential fields are used to plan the collision-free, smooth and feasible trajectory. In contrast to the traditional APF method, the velocity is introduced into the planning process to plan the trajectory. The planning process is made up of three parts: virtual force generation, local minimum detection, and movement calculation.
As
Figure 6 shows, after initialization, the algorithm will first determine if the vehicle is within the influence range. If the vehicle is within the influence range, the obstacle potential field is subsequently generated using the data from additional sensors. If not, the goal attraction and road boundary fields will be the entire field. The virtual force is obtained in the next step using the total potential field. Next, the velocity is updated based on the virtual force. Lastly, the position point will be calculated using the virtual force and the velocity. In the meantime, we introduce a future prediction process and temporary goal to solve the local minimum problem. The following section shows illustrations showing the specifics of the local minimum and velocity updates.
3.1. Virtual Force Generation
Figure 7 shows the virtual forces are generated using the potential field. The negative gradient of the current position is the virtual force of the potential field. Mathematically, the direction of the negative gradient is the direction where the potential field declines fastest. The expression is as follows:
where
UTotal is the sum of all potential fields;
FX and
FY are the
X and
Y components of virtual force, respectively.
In programming practices, the virtual force can be computed directly without building the environment’s potential field, which can shorten the method’s computation time. Using (4)–(13), the following functions are derived:
For the force along the
x-axis:
The only variable is the obstacle; the derivative of the obstacle potential field is:
For the lateral force in the
Y-direction:
By adding the derivatives, the calculation can be minimized, which helps the algorithm to be calculated in real-time speed.
Using the virtual force, the expected heading angle
φE is calculated in the following equation:
The position point of the next time step will be updated using the equation as follows:
In (21),
Xn and
Yn are the position coordinate values of the current step;
Xn+1 and
Yn+1 are the position coordinate values of the next step;
vc is the velocity after the velocity update process. The velocity update process will be discussed in
Section 3.3.
3.2. Future Prediction Mechanism to Solve Local Minimum
In the traditional APF method, the vehicle will come to a halt and remain stationary in the environment when a local minimum point is reached, where the combined virtual force acting on it is zero. It is a limitation of the APF method due to its design theory.
The definition of local minimum in traditional APF is where the sum of virtual forces equals zero:
As a result, in the traditional APF approach, which does not take the velocity into consideration, the host vehicle will stop at the local minimum point.
During the planning phase of this article, this approach considers the fact that the vehicle will maintain a consistently high velocity throughout the driving process. As a result, the vehicle’s speed prevents it from consistently remaining stationary at the local minimum position. However, the local minimum point will still attract the host vehicle and lead to an infeasible trajectory. As
Figure 8 shows, the predicted trajectory shows how the local minimum drags the vehicle to the road boundary. In real-world driving practice, it is unacceptable to plan a trajectory that hits the road boundary and then go back to the lane.
To address this issue, the proposed method introduces a future prediction process that predicts thefuture movement of the host vehicle using the motion statew. At each time step, the algorithm will calculate the movement in the future in low resolution. The future prediction result can be utilized to judge whether the vehicle will be trapped into the local minimum point:
where
ynb,
ylc is the
Y-axis coordinate of the nearest road boundary of the vehicle and the center of the current lane. Equation (24) shows how the Algorithm 1 decides whether the vehicle will be trapped in a local minimum. Specifically, the algorithm counts all points that are stuck between the obstacle and the road boundary. If the
LocalFuture is larger than the predefined sensitivity parameter
Cf, the vehicle will be judged that it will be trapped in the local minimum in the future.
Algorithm 1. Local minimum calculation |
Input: Current state of the vehicle (x, y, v, φ), road geometry (ynb, ylc), obstacle (x, y, v, φ) |
Output: Temporary goal Ygoal, Flag indicates whether the vehicle will enter the local minimum Step 1: Calculate the future movement of the obstacle and vehicle in low resolution. Step 2: Step 3: If LocalFuture > Cf, Flag =1, otherwise Flag =0. Step 4: If Flag =1, , Tg =t; otherwise continue. Step 5: Calculate goal attraction force by the effect of temporary goal Step 6: If t= Tg +Tc1, Flag = 0. |
1Tc is the predefined time that the temporary goal lasts. |
As
Figure 9 shows, when a local minimum is detected, the algorithm will generate a temporary goal to place an attractive force on the vehicle to drive out of the local minimum. The temporary goal will exist for a limited time to ensure that it will not affect the movement of vehicles later. When a temporary goal exists, the upper lane’s PF value is much larger than the lower one. According to (8), the PF value will decline smoothly to guide the vehicle to the goal lane.
3.3. Velocity Update
During the algorithm initialization step of the planning process, the cruise velocity Vc is determined. In essence, the vehicle obeys the following rules: when there are no other cars nearby, maintain the cruise speed, accelerate when passing, and decelerate to the speed of the obstacle when following.
The velocity update mechanism is introduced to enable the vehicle to follow the obstacle car. In detail, the velocity update step using the part of Fsum in x direction Fox to guide the calculation of acceleration.
The following is how the velocity updates:
where
vb is the velocity of the step before, and
vc is the velocity of the current step. Vc is the cruising speed set at the initialization. The granularity of the result is determined by the planning time step of the entire algorithm. The host vehicle’s mass is represented by
m. The force magnitude is controlled by the parameter
η1. The parameter that regulates the vehicle’s return to its cruising speed is
η2.
After introducing the acceleration and velocity update mechanism, the improved APF method is able to accelerate when passing and decelerate to the speed of the obstacle when following. In the end, the method will plan a trajectory that is more like human-driving logic.
It is obvious that the future calculation mechanism and velocity update will add extra calculation burden to the improved APF.
Table 1 gives the results that after adding this mechanism, the algorithm indeed takes more time to finish the whole planning task, but the maximum heading angle is decreasing, which indicates that the trajectory planned by improved APF is smoother than the traditional APF method. At the same time, the velocity is able to change based on the actual driving situation.
4. Simulation and Result Analysis
4.1. Simulation Environment
In this section, the simulations are performed in MATLAB R2020a environment using a computer with Intel Xeon W-2245 CPU and 64 GB RAM. First, a long driving scenario, which can be divided into three cases on a standard city road, is given to verify the effectiveness of the proposed method. In time sequence, the cases are static obstacle avoidance, dynamic obstacle with the local minimum, and car following. Then, a complex and challenging scenario is given to prove the ability of the algorithm to handle heavy traffic.
The road geometry is the standard one-way road with two lanes. It is worth noting that the speed is generally limited to below 40 km/h on urban roads in China’s traffic regulations and traffic environment. Hence, the speed of the host vehicle is assigned as 36 km/h.
In the first long-driving scenario, there are three obstacle vehicles in this scenario. Obstacle 1 starts with 18 km/h and decelerates at t = 0 s; Obstacle 2 also starts with 18 km/h; Obstacle 3 starts with 28.8 km/h and accelerates at t = 16 s with a = 2 m/s2. The whole simulation ends at t = 20 s.
In the second complex scenario, there are five obstacles in total. Horizontally, the velocities of the vehicles are 28.8 km/h, 32.4 km/h, 27 km/h, 28.8 km/h, and 25.2 km/h, respectively. All obstacle vehicles are moving at a constant speed. Obstacle 4 will take the lane change maneuver at t = 5.5 s to t = 8.3 s.
The detailed simulation parameters are given in
Table 1. Note that the parameters in
Table 1 are one possible expression based on our hyperparameter tuning through a number of simulations.
4.2. Simulation Result
4.2.1. Case A: Static Obstacle Avoidance
As
Figure 10 shows, at the beginning of this case, the host vehicle is driving along the road at the speed of 36 km/h. the obstacle vehicle is in the front of the host vehicle.
At the same time, the front vehicle starts to decelerate rapidly to 0 m/s. At the beginning, as
Figure 10b,c show, the host vehicle is trying to decelerate to follow the front vehicle. After deceleration, the host vehicle finds out it cannot follow the vehicle, and then it starts a lane change maneuver.
Figure 10d,e show how the vehicle changes lanes to avoid any potential collision. In
Figure 10f,g, the vehicle is accelerated to a cruising speed of 36 km/h. In summary, the proposed method is able to handle the static obstacle avoidance scenario.
4.2.2. Case B: Dynamic Obstacle with Local Minimum
After overtaking the static obstacle, the next obstacle moves in the road at 18 km/h. As
Figure 11b,c show, after approaching the obstacle, the future detection head is stuck into the local minimum. If you keep driving along the future prediction result, the vehicle will crash into the road boundary or the obstacle vehicle.
Figure 11d–f show the planning result of traditional APF which will cause crash accidents. As
Figure 11d–f show, when the local minimum is detected, the algorithm will generate a temporary goal point to place an attractive force to guide the movement of the host vehicle. It is obvious that
Figure 11d shows how the attractive force drags the vehicle to another lane. As a result, in
Figure 11f–h, the host vehicle drives out of the local minimum and cruises on the road.
4.2.3. Case C: Car following
In this case, the obstacle vehicle is moving at a speed of 28.8 km/h, which is close to the cruising speed of the host vehicle. Here, the host vehicle is decelerating to follow the front car, and as
Figure 12f shows, the host vehicle follows the car successfully and decelerates to 30.8 km/h.
Here, the red car in
Figure 12b–f shows how the traditional APF will react in the car in the following case. Due to the lack of a velocity update process, the traditional APF method will always try to avoid collision by lane-changing. The proposed method can decelerate to follow the obstacle vehicle.
4.2.4. Case D: Complex Scenario
For simplicity, the obstacles in this case are encoded based on the sequence in the X-axis. For example, in
Figure 13a, the obstacle vehicle in the back of the host vehicle is obstacle 1.
In this case, the host vehicle is driving in the heavy traffic. First, by the influence of the obstacle in the back, the host vehicle accelerates to keep a safe distance from the obstacle. Later, as shown in
Figure 13c, the host vehicle is decelerating owing to the influence of obstacle 3. At the same time, the future prediction mechanism detects a local minimum, which will potentially generate an infeasible trajectory. In
Figure 13d, a temporary goal is generated to guide the host vehicle to change the lane. As
Figure 13h shows, obstacle 4 is taking the lane change maneuver because of the slow obstacle 5. By the influence of the rotation factor, the vehicle instantly reacts to the obstacle 4′s behavior and starts to decelerate. At the end of the simulation, the host vehicle is cruising in the traffic stream.
4.3. Computation Time Cost Analysis
As shown in
Table 2, the computation time of improved APF and improved APF-without prediction is acceptably larger than the traditional APF in Case A. The future prediction will add extra computation cost to the proposed method. It is worth noting that the maximum time cost of improved APF (≈200 Hz) is efficient enough and can achieve real-time planning (>20 Hz).