Next Article in Journal
Space Debris In-Orbit Detection with Commercial Automotive LiDAR Sensors
Previous Article in Journal
Advanced Modulation Formats for 400 Gbps Optical Networks and AI-Based Format Recognition
Previous Article in Special Issue
Autonomous Lunar Rover Localization while Fully Scanning a Bounded Obstacle-Rich Workspace
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Collision Avoidance Path Planning for Automated Vehicles Using Prediction Information and Artificial Potential Field

1
Graduate School of Automotive Engineering, Kookmin University, Seoul 02707, Republic of Korea
2
Department of Automobile and IT Convergence, Kookmin University, Seoul 02707, Republic of Korea
*
Author to whom correspondence should be addressed.
Sensors 2024, 24(22), 7292; https://doi.org/10.3390/s24227292
Submission received: 15 October 2024 / Revised: 13 November 2024 / Accepted: 14 November 2024 / Published: 14 November 2024
(This article belongs to the Special Issue Intelligent Control and Robotic Technologies in Path Planning)

Abstract

:
With the advancement of autonomous driving systems, the need for effective emergency avoidance path planning has become increasingly important. To enhance safety, the predicted paths of surrounding vehicles anticipate risks and incorporate them into avoidance strategies, enabling more efficient and stable driving. Although the artificial potential field (APF) method is commonly employed for path planning due to its simplicity and effectiveness, it can suffer from the local minimum problem when using gradient descent, causing the vehicle to become stuck before reaching the target. To address this issue and improve the efficiency and stability of path planning, this study proposes integrating prediction data into the APF and optimizing the control points of the quintic Bézier curve using sequential quadratic planning. The validity of the proposed method was confirmed through simulation using IPG CarMaker 12.0.1 and MATLAB/Simulink 2022b.

1. Introduction

Autonomous driving technology has gained significant attention due to its potential to reduce traffic congestion, enhance driving safety, and provide greater convenience to drivers. As a result, numerous studies are actively exploring various aspects of this technology [1,2]. The rapid development of autonomous driving technology is driven by OEMs like Google Waymo, Tesla, and Uber, as well as academic researchers working in this field [3,4]. In response to these advancements, governments are preparing regulations and guidelines for the introduction of autonomous vehicles, while also enacting safety standards to ensure their safe deployment [5,6].
However, the rapid pace of autonomous driving also presents significant challenges. As self-driving cars enter commercialization, incidents involving collisions with human-driven vehicles have emerged, and these collisions continue to occur in notable numbers [7]. This has led to growing interest in autonomous driving systems capable of preventing potential collisions. Autonomous vehicles have demonstrated the ability to prevent collisions caused by human error in real-world traffic environments [8,9]. This capability is expected to significantly reduce accidents, improve road safety, and enhance traffic efficiency [10].
To prevent collisions, autonomous vehicles must be able to predict potential hazards and plan their movements accordingly. Collision prediction involves forecasting the future behavior of surrounding objects and assessing the risk of a collision with the autonomous vehicle [11]. Given the importance of utilizing predictive information about the behavior of nearby objects, numerous studies are focused on developing methods to accurately predict these behaviors [12,13,14,15]. While existing studies have primarily focused on improving the accuracy of behavior prediction, this research aims to overcome the limitations of traditional methods that rely on real-time assessment or short-term responses by utilizing predictive information directly in collision avoidance path planning. By proactively predicting potential collisions and, upon detection, integrating predictive data into an artificial potential field to identify safe positions, this approach enables the design of stable and efficient paths using Bézier curves. This method offers higher safety and reliability than real-time evaluation techniques such as Time-To-Collision (TTC). Also, this approach allows for effective collision avoidance even in complex road environments, contributing significantly to the driving safety of autonomous vehicles.
In summary, this paper proposes a path planning method that leverages prediction information about surrounding objects to avoid collisions. The proposed method integrates the IPG CarMaker simulation environment and the MATLAB/Simulink to perform real-time path planning, allowing the autonomous vehicle to avoid collisions efficiently. The approach combines artificial potential field (APF) with Bézier curve-based path generation and sequential quadratic programming (SQP) optimization to create an optimal, stable collision-avoidance path. Control inputs are seamlessly delivered from MATLAB/Simulink to the CarMaker simulation, enabling real-time execution.

2. Related Work

2.1. Traditional Path Planning Using Artificial Potential Field

The APF is a widely used path planning method originally developed in the field of mobile robotics. In APF-based path planning, a virtual potential field is created to guide a vehicle safely to its target point while avoiding obstacles [16]. The necessary data to construct this field come from sensors on autonomous vehicles, which perceive the surrounding environment. The potential field can be divided into three main categories: attractive potential field, repulsive potential field, and total potential field.
An attractive potential field generates a virtual force that pulls the vehicle toward the target point, while a repulsive potential field generates a force that pushes the vehicle away from obstacles or other vehicles. The repulsive potential field is calculated based on the position and speed of obstacles in the environment. The total potential field is the sum of the attractive and repulsive fields, guiding the vehicle along a path with the lowest potential value from its current location to the target point. However, the gradient descent method used for path planning in APF can lead to issues in complex driving environments. Specifically, the vehicle may encounter a local minimum where it gets stuck and cannot reach the target point, or experience oscillation in its trajectory. These limitations have prompted further research into improving APF-based path planning.
Several studies have addressed these issues [17,18,19,20,21]. Yanjun proposed a framework for autonomous vehicle path planning that utilizes a local electric comparison method to avoid collisions. In this approach, the driving area is divided into a mesh and repulsive values are assigned to each edge based on APF’s resistance approach, helping the vehicle find a collision-free path [22]. Lin introduced a waypoint tracking method that integrates collision avoidance using APF theory. In this method, the APF-generated path is optimized before and after collision avoidance to ensure a smooth connection with waypoints obtained via GPS, preventing sudden changes in the vehicle’s heading angle during collision maneuvers [23].
Additionally, research is being proposed that focuses not just on collision avoidance but also on mitigating the impact of collisions where avoidance is impossible. To address this, Xu Shang developed a safe controller using model predictive control, which enhances the APF method by incorporating the shape information of surrounding roads and vehicles. This approach provides a more practical solution for emergency scenarios and offers a methodology for reducing the severity of collisions, particularly in specific parts of the vehicle [24].

2.2. Bézier Curve Trajectory Generation

The Bézier Curve is a widely used technique in path planning, particularly in autonomous driving and robotics. Its ability to generate smooth and safe paths has made it an integral part of several path planning algorithms [25,26,27]. The Bézier Curve is defined by control points, with the shape of the curve determined by their positions. Mathematically, the Bézier Curve is based on the Bernstein polynomials, and the Nth Bézier Curve is defined by n + 1 control points. The equation for the Nth Bézier Curve is given by:
B t = 1 t i = 0 n b i , n t P i + t i = 0 n b i , n t P i = i = 0 n n + 1 i n + 1 b i , n + 1 t P i + i = 0 n i + 1 n + 1 b i + 1 , n + 1 t P i = i = 0 n + 1 i n + 1 P i 1 + n + 1 i n + 1 P i b i , n + 1 t = i = 0 n + 1 b i , n + 1 t P i , P i , = i n + 1 P i 1 + n + 1 i n + 1 P i , i = 0 , , n + 1
The starting and ending points of the curve are fixed by the first and last control points, while the shape of the curve changes based on the position of the control points. Bézier curves have the advantage of providing sufficient degrees of freedom while ensuring the creation of smooth and continuous paths. Paths based on cubic, quartic, and quintic Bézier curves are shown in Figure 1.
Given their advantages, Bézier curves have been employed in various studies for autonomous vehicle path planning. For instance, J. Chen proposed a continuous curvature path using a partial second-order Bézier curve that meets the requirements for smoothness. This was achieved by applying minimum lane change distance calculations and curvature constraints to the path planning [28].
J. Moreau, using a nonlinear dynamics vehicle model, constrained the Bézier curve to avoid obstacles in real time. In the case of unexpected events or obstacles, such as those encountered at intersections, the path is optimized using the quadratic programming (QP) method to generate the shortest avoidance path. This method produced smoother paths than those generated by gradient descent in APF while ensuring stable steering angles and faster computation times [29].
C. Chen proposed an algorithm to ensure continuous curvature and bounded curvature trajectories for autonomous vehicles from the initial to the target state. To achieve this, the quartic Bézier curve was adopted, with the Bézier curve’s parameters being continuous and bounded using the SQP method [30]. This algorithm not only ensures a continuous and smooth path but also provides a collision avoidance path planning approach through the optimization of control points.

2.3. Autonomous Driving System Based on Vehicle Trajectory Prediction

An autonomous driving system that utilizes predicted trajectories can significantly enhance safety by detecting potential risks in advance and formulating appropriate driving strategies to mitigate them. The road environment encountered by autonomous vehicles is highly dynamic, making it challenging to respond to the movements and actions of other vehicles in real time. Unexpected situations, such as sudden lane changes, speed variations, or the sudden appearance of obstacles from surrounding vehicles, are common. To respond effectively in such situations, autonomous vehicles must predict the future paths of surrounding vehicles and plan their path accordingly, based on this predicted information [31,32,33,34].
A notable example of this approach is the work of D. Meng, who proposes a method for autonomous vehicles to predict the trajectories of surrounding vehicles in real time to identify potential risks. This approach gathers data on the current state of nearby vehicles, including location, speed, and acceleration, using various sensors and algorithms. It then predicts the future movement of these vehicles based on the collected data. Using the predicted path, the autonomous vehicle calculates the potential risk of collision using metrics like TTC and minimum distance margin. A methodology has been developed where the vehicle can decide whether to maintain its current lane or change lanes to avoid risk based on the calculated collision probability [35]. J. Kim further argued that previous algorithms relying on TTC often assumed constant conditions and inputs. To address this, an improved risk prediction algorithm is proposed that offers more accurate TTC predictions by forecasting the future trajectories of surrounding vehicles. This algorithm also proposes an inverse TTC map to enhance the prediction accuracy [36].
The primary advantage of autonomous driving systems based on predicted trajectories is enhanced safety. These systems are far more efficient than traditional reaction-based systems because they can recognize risk factors before unexpected events occur. This proactive approach allows the system to respond preemptively. For example, if an autonomous driving system predicts that the vehicle in front will suddenly change lanes, it can adjust speed or change lanes in advance, planning a safer path. Such preemptive responses can significantly reduce accidents caused by sudden braking or other reactive maneuvers in unexpected situations, helping to maintain a safe distance between vehicles.

3. Proposed Collision-Avoidance Path Planning Method

3.1. Overall Architecture of the Proposed Method

This study focuses on a path planning methodology that emphasizes the use of prediction information to avoid collisions with nearby vehicles. The study operates under the assumption that accurate prediction data is received, which is provided through pre-generated simulation data spanning approximately 2 s into the future with a time interval of 0.1 s. Although it is difficult to receive accurate prediction data in real-world without considering uncertainties, we believe that receiving the prediction data at the minimum time lengths makes it sufficiently understandable for the purpose of developing the path planning algorithm. This 2 s prediction horizon is commonly accepted as the minimum necessary time frame in trajectory prediction research, making it an ideal choice for our study. Architecture of the proposed methodology determines whether the avoidance path generation algorithm operates by conducting a collision assessment based on the predicted path of the surrounding vehicle and the planned path of the ego vehicle, as shown in Figure 2. When a collision with a surrounding vehicle is predicted, the APF identifies the point with the lowest potential value and designates it as the target point. A path for collision avoidance is then created using a quintic Bézier curve, optimized based on a cost function that considers factors such as curvature, total potential value, jerk, and the lateral offset from the current position to the target point.

3.2. Risk Assessment

When driving along the planned path of an autonomous vehicle, risk can be measured using a simplified kinematic formula that considers the time domain, distance, and acceleration domains. Key indicators such as TTC and time headway in the time domain, minimum safe distance in the distance domain, and steering threat number in the acceleration domain are used to assess risk [37,38,39,40]. However, these risk assessment methods are based on the current state of the vehicle, making it difficult to predict future states. As a result, these indicators may not provide sufficient response time during emergency avoidance maneuvers or urgent situations. If the future behavior of surrounding objects can be predicted, autonomous vehicles will have more time to react to potential risks in critical situations. To address this, this study employs risk assessment based on collision detection using circular boundaries, enabling faster response times by utilizing future prediction information of surrounding objects.
The collision assessment circle is designed to cover the body of the vehicle. For the ego vehicle, its specifications are known. However, for surrounding traffic, the sensor of the ego vehicle can only measure the overall width and length. Therefore, the collision assessment circle for a surrounding vehicle is defined accordingly, as shown in Figure 3. The points x E g o and y E g o represent the center points of the ego vehicle’s rear axle. For the ego vehicle, two collision assessment circles are defined, and their center positions and radii are calculated as follows:
R E g o = 1 2 L R + L w + L F 2 2 + L B 2 ,
x E g o _ f t = x E g o t + 1 4 3 L w + 3 L F L R c o s θ E g o t , y E g o _ f t = y E g o t + 1 4 3 L w + 3 L F L R s i n θ E g o t , x E g o _ r t = x E g o t + 1 4 L w + L F 3 L R c o s θ E g o t , y E g o _ r ( t ) = y E g o t + 1 4 L w + L F 3 L R s i n θ E g o ( t ) .
For surrounding traffic, three collision assessment circles are defined, with their center positions and radii determined as follows:
R t r f = W t r f 2 s i n π 4 ,
x t r f _ f t = x t r f t + L t r f c o s θ t R t r f cos π 4 c o s θ t r f t , y t r f _ f t = y t r f t + L t r f s i n θ t R t r f cos π 4 s i n θ t r f t , x t r f _ r t = x t r f t + R t r f cos π 4 c o s θ t r f t , y t r f _ r t = y t r f t + R t r f c o s π 4 s i n θ t r f t , x t r f _ c t = x t r f _ f t + x t r f _ r t 2 , y t r f _ c t = y t r f _ f t + y t r f _ r t 2 .
To check for collision between the defined circles of the ego vehicle and those of surrounding objects, the following method is used. In this study, collisions are assessed at each time step using the ego vehicle’s planned path and the predicted trajectories of surrounding vehicles for the next two seconds. The collision assessment is performed by comparing the center points and radii of the defined circles based on the following formula.
C j i C l i = x j i x l i 2 + y j i y l i 2 , i = 1 , 2 , , n Risk   =   1 ,         if   C j i C l i R ego + R trf
where C j i represents the center point of the circle at time step i on the ego vehicle’s planned path, j denotes either the front or rear of the vehicle, C l i represents the center point of the circle at the time step i on the predicted path of the surrounding vehicle, and l denotes the front, center, or rear of the vehicle. If the distance between the center points is smaller than the sum of the radii of the two circles, a collision is predicted. The parameters used to define the risk circle are provided in Table 1.

3.3. Artificial Potential Field with Prediction Information

The APF is a path-planning algorithm that generates a virtual attractive potential field and a repulsive potential field to guide a vehicle to its target. In this study, we consider the surrounding environment by constructing a suitable potential function that creates a road potential field (considering the lanes boundaries) and an obstacle potential field (considering static or moving obstacles). Traditional APF designs an attractive potential field to lead the vehicle toward the goal, but in the proposed method, we eliminate the attractive potential field. Instead, we designate the point with the lowest potential value as the target point in APF. The road potential field is used to keep the vehicle in the center of the lane, preventing it from veering off-road, while the obstacle potential field ensures the vehicles avoid collisions with obstacles. The combined values of these two potential fields are represented as follows:
U t o t a l = U R o a d + U O b s t a c l e .
The road potential field is applied to represent a three-lane road, as illustrated in Figure 4a, using trigonometric functions. The potential field function is defined in Equation (8), and Figure 4b shows a 3D representation of the road potential field based on the following equation:
A Y = s g n Y Y c 1 + s g n Y Y c 3 1 p + 2 p 2 , U R o a d = A Y { cos 2 π Y w + 1 } 2 .
where w is the width of the road, Y c 1 and Y c 3 are the center positions of the first and third lanes, respectively, in the road’s transverse coordinate system, and p is the coefficient used to generate values between 0 and 1.
The obstacle potential field incorporates both static and moving obstacles and is designed to help autonomous vehicles maintain a safe distance from them. As the autonomous vehicle approaches an obstacle, the potential value increases gradually, preventing a collision. The obstacle potential field is expressed as follows:
U o b s t a c l e i = e 1 v e g o v o b s i + μ x x o b s i 2 δ x 2 y y o b s i 2 δ y 2 ,       i f   v e g o v o b s i   &   x x o b s i   o r   v e g o < v o b s i   &   x > x o b s i 0 ,           e l s e ,
where μ is a small constant added to prevent computational errors when the speed of a surrounding object is the same as that of the ego vehicle; δ x and δ y are standard deviations in the longitudinal (x) and lateral (y) directions, respectively, affecting the size of the potential field. Figure 5 shows how the obstacle potential field changes based on different values of δ x and δ y .
Figure 6 presents both 3D and top-down views of the combined road potential and obstacle potential fields. The ego vehicle is positioned at [0, −5.25] and is traveling at 80 km/h. The vehicle ahead is located at [40, −5.25] and is moving at 60 km/h, while the vehicle in the right-front position is located at [10, −8.75] and moving at 70 km/h. The front vehicle poses a greater threat, as indicated by its larger area, due to its higher relative velocity compared to the right-side vehicle. The parameters used for the potential fields are outlined in Table 2. These parameters used in this study were determined through a trial-and-error process to achieve optimal suitability within the experimental environment. In real-world scenarios, however, these parameters may not remain fixed.
In this study, when planning a collision-avoidance path, the point with the lowest potential value in the APF is identified and designated as the target point. If the future position of surrounding objects is not considered when determining the target point, additional collisions may occur during the avoidance maneuver. To address this, the future position and speed of surrounding vehicles are incorporated into the APF using prediction information of other surrounding objects. When considering prediction data for the next 2 s, it is impractical to use all time steps, as the intended target point may not be found, and integrating all information could also lead to increased computational burden, potentially reducing overall system performance. Therefore, the 2 s prediction data is divided into n time steps and incorporated into the APF. When reflecting the future obstacle potential field in the APF, the values of δ x and δ y are adjusted accordingly.
In this study, the future prediction is divided into five time steps, including the present and data from the next 2 s. Figure 7 shows an example of the top-down view and 3D visualization of the total potential field, combining both the obstacle and road potential fields, with the future position of the front vehicle located at [40, −5.25].

3.4. Path Generation and Optimisation Based on the Bézier Curve

The proposed collision-avoidance path planning algorithm is based on the Bézier curve. In this approach, the positions of the current start point and target point are fixed, while the path is generated by adjusting the positions of the remaining control points. The Bézier curve described in Section 2.2 follows Equation (1), where P i represents the position of the control points. The start and end points of the control point are defined as follows:
P 0 = x s t a r t   ,   y s t a r t , P n = [ x t a r g e t   ,   y t a r g e t ] .
Figure 8 illustrates the selection of a target point. The black line is selected based on the target longitudinal distance. In this study, x t a r g e t = v e g o × t , where t is set to 1.5 s. Once x t a r g e t is determined, the potential value at that target state in the APF is checked, and the point with the lowest potential value is selected as y t a r g e t .
In this algorithm, the path is planned based on the vehicle’s local coordinate system. The conversion from the global coordinate system to the vehicle’s local coordinate system is given as follows:
x l o c a l y l o c a l = c o s θ s i n θ s i n θ c o s θ x g l o b a l x e g o y g l o b a l y e g o .

3.4.1. Quartic Bézier Curve Modeling

In the case of the quartic Bézier curve, there are three adjustable control points, and the resulting curve is shown in Figure 9a. The first and last control points follow Equation (10), while the remaining three control points are defined as follows:
P 0 = 0 , 0 T , P 1 = l 1 , 0 T , P 2 = [ x 2 , 4 κ 0 l 1 2 3 ] T ,     κ 0 = 3 y 2 4 l 1 2 , P 3 = [ x 4 l 2 c o s φ T ,   y 4 l 2 s i n φ T ] T , P 4 = x 4 , y 4 T .
where P 1 is located at a distance of l 1 along the longitudinal direction from P 0 , P 2 is positioned considering the initial curvature value κ 0 , and P 3 is positioned using the distances l 2 and the angle φ T . The distance between P 3 and P 4 is modeled accordingly.

3.4.2. Quintic Bézier Curve Modeling

In the case of quintic Bézier curve, four control points are adjustable, and the modeling result is shown in Figure 9b. The first and last control points follow the same rule as in the quartic Bézier curve. The remaining four control points are defined as follows:
P 0 = 0 , 0 T , P 1 = l 1 , 0 T , P 2 = [ l 1 + l 2 , 0 ] T , P 3 = [ x 4 l 3 c o s φ T , y 4 l 2 s i n φ T ] T , P 4 = [ x 5 l 4 c o s φ T , y 5 l 4 s i n φ T ] T , P 5 = [ x 5 , y 5 ] T
where P 1 is located l 1 units in the longitudinal direction from P 0 , P 2 is located l 1 + l 2 units in the longitudinal direction, and P 3 and P 4 are calculated based on the distances l 3 , l 4 and the angle φ T relative to previous control points.

3.4.3. Path Optimization

To ensure that the designed Bézier curve model is collision-free, smooth, and continuous, an optimization technique is required to find valid parameters for each model. SQP converts nonlinear problems—incorporating objective functions and constraints—into QP problems by linearizing or approximating them. The QP problem is solved iteratively to obtain an approximate solution, with each iteration refining the approximation of the objective function while ensuring that the constraints are satisfied. SQP converges quickly since it utilizes the Hessian matrix, based on Newton’s method, and efficiently handles various constraints during path optimization [41,42,43,44].
In this study, the objective function is designed to balance driving convenience and safety while ensuring collision-free operation of autonomous vehicles. Path continuity and smoothness are critical factors in enhancing the comfort of vehicle occupants. A path that is not smooth or continuous can lead to discomfort and may affect the stability of the vehicle’s behavior. Moreover, the vehicle must avoid collisions with surrounding objects. The total potential field, as discussed earlier, ensures the safety of the planned path while also minimizing the lateral distance to the target point. This design considers situations where the autonomous vehicle must make rapid evasive maneuvers while following the planned path. The objective function J that considers these features is expressed as follows:
J = a 0 1 κ 2 τ d τ + b 0 1 U t o t a l τ d τ + c 0 1 J e r k τ d τ + d 0 1 D y τ d τ
subject   to   : κ τ m a x κ m a x l 1 , x 2 , l 2 > 0 ,   i f   B é zier   order = 4 l 1 , l 2 , l 3 , l 4 > 0 ,   i f   B é zier   order = 5  
where κ represents the curvature, and U t o t a l , J e r k , and D y represent the potential value of the planned path, jerk, and lateral offset from the target point, respectively. The objective function J, structured as described, optimizes the position of each control point through parameters such as l 1 , l 2 and others.
The term that minimizes the lateral distance from the point-of-view function to the target point enables rapid avoidance behavior during path optimization. To account for this, the TTC with potential obstacles is considered. TTC is a measure of the time remaining before a collision occurs between the ego vehicle and a potential obstacle. It is defined as the ratio of the relative distance to the target obstacle to the relative velocity towards the target obstacle. This metric helps to assess the urgency of collision avoidance and provides a basis for triggering avoidance actions. The definition of d, which represents coefficient of laterally offset term, is given by Equations (15) and (16):
TTC = R D t a r g e t R V t a r g e t ,
d = ε ,       i f   TTC < γ 0 ,       e l s e .
R D t a r g e t is the relative distance to target vehicle and R V t a r g e t is the relative velocity towards the target vehicle. The parameters used to construct the objective function are listed in Table 3.

4. Simulation Results

The proposed methodology aims to use prediction information from surrounding traffic to efficiently and stably avoid collision. We evaluate this methodology by comparing scenario results with and without the prediction information, as well as using quartic and quintic Bézier curves. Four test scenarios are used to evaluate the methodology. Scenarios A to C are based on autonomous systems test scenarios defined by ISO DIS 34502 [45], as shown in Figure 10, and Scenario D is a test scenario for continuous avoidance behavior. Scenarios A to C run for 13 s, while Scenario D runs for 15 s. The specifications of each scenario will be described at the beginning of each experiment’s results section. The collision avoidance path algorithm is triggered based on a TTC threshold of less than 2 s when prediction information is not used in order to allow comparison with the system that utilizes prediction information.
To validate the proposed avoidance path generation methodology, an integrated environment, as shown in Figure 11, is set up using IPG’s software, CarMaker. The driving road information, surrounding vehicle data, and perception results used in the avoidance path generation algorithm are provided by CarMaker. When a collision is predicted during the ego vehicle’s driving, the proposed algorithm plans the optimal avoidance path. This planned path is then passed to the pure pursuit lateral controller, where the steering angle is calculated and subsequently transmitted to the CarMaker vehicle model. This integrated environment is configured using IPG CarMaker version 12.0.1 and MATLAB 2022b/Simulink, ensuring smooth integration and compatibility with other software.
This platform allows real-time monitoring of the vehicle’s behavior during testing and simulates realistic vehicle dynamics through parameterized components, such as steering, tires, brakes, powertrain, and chassis. The vehicles used in this study are those provided by IPG CarMaker. The ego vehicle is a Hyundai-IONIQ 5, and the traffic vehicle is an IPG_CompanyCar_2018. Simulation results support Simulink integration, and the driving results from each collision avoidance path planning system are evaluated using three methods.
  • Driving trajectory—to visualize the overall driving situation for each scenario.
  • Steering wheel angle, yaw rate, and lateral acceleration plots—to assess the vehicle’s lateral stability.
  • Maximum value analysis—to examine the system’s lateral stability during the avoidance maneuver.

4.1. Simulation Scenario A

In Scenario A, as shown in Figure 10a, the ego vehicle is driving in the second lane of a third-lane road at 80 km/h, while the traffic vehicle, 40 m in front in the same lane, is also driving at 80 km/h. At this point, if the traffic vehicle rapidly accelerates and decelerates at −6 m/s2, the ego vehicle must perform a collision avoidance maneuver by changing lanes safely and smoothly.
The simulation results are shown in Figure 12 and Figure 13, illustrating the driving situations at 0, 3, 6, 6.5, 9, 11, and 13 s, depending on whether the prediction is utilized and whether the quartic or quintic Bézier curve algorithm is applied. The results include changes in the ego vehicle’s steering wheel angle, yaw rate, and lateral acceleration over time. Figure 12 shows the driving trajectories at each time interval, confirming that the system utilizing prediction started avoidance earlier. At 6 s, the driving paths of the system with prediction, represented in red and blue, secured more lateral distance from the traffic vehicle compared to the paths of the system without prediction, shown in yellow and purple. Figure 12b illustrates the driving situation at 6.5 s in Scenario A, where the red trajectory represents the use of prediction with the quartic Bézier algorithm, while the yellow trajectory shows the result without prediction. At this point, using prediction allowed the system to begin avoidance earlier, achieving 0.363 m more lateral distance compared to the system without prediction. The quartic Bézier algorithm, without prediction, measured a lateral distance of 3.01 m from the traffic. Similarly, the blue path in Figure 12c represents the quintic Bézier algorithm with prediction, which achieved 0.235 m more lateral distance compared to the algorithm without prediction, which measured 2.96 m from the traffic.
The advantage of using prediction is that it enables early recognition of the surrounding environment, allowing for quicker preparation for potential dangers. This ultimately enhances vehicle stability. Figure 13 displays graphs representing the steering wheel angle, yaw rate, and lateral acceleration for each system in Scenario A. Upon examining the graphs, it is evident that the system utilizing prediction planned a smoother path, resulting in improved lateral stability. Additionally, the quintic Bézier curve provides more stable lateral behavior than the quartic Bézier curve. As shown in Table 4, when comparing the maximum values, the system using prediction recorded smaller maximum values than the system without prediction. Furthermore, the quintic Bézier algorithm achieved smaller maximum values compared to the quartic Bézier algorithm.

4.2. Simulation Scenario B

Scenario B, illustrated in Figure 10b, involves the ego vehicle driving at 80 km/h in the second lane of a three-lane road. A traffic vehicle in the left lane, located 15 m ahead, is driving at 75.6 km/h and begins a cut-in maneuver into the ego vehicle’s lane with a deceleration rate of −1.5 m/s2. This type of cut-in scenario is common in real-world driving and often occurs unexpectedly, making it an ideal situation to evaluate collision avoidance maneuvers. In this scenario, the ego vehicle must not only avoid a collision but also smoothly execute a lane change to the right while avoiding the traffic vehicle on the left.
The simulation results are shown in Figure 14 and Figure 15, depicting the driving situation of the vehicles at 0, 3, 6, 6.5, 9, 11, and 13 s, along with changes in the ego vehicle’s steering wheel angle, yaw rate, and lateral acceleration over time. Figure 14 shows the vehicle paths at each time interval, confirming that the system using prediction initiates avoidance maneuvers earlier. At 4.3 s, the driving paths for the system with prediction, represented by the red and blue trajectories, show a significantly greater lateral distance from the traffic compared to a system without prediction, depicted by yellow and purple trajectories. Figure 14b,c illustrate the driving situation at 5.2 s in Scenario A. The red path represents the use of prediction with the quartic Bézier algorithm, while the yellow path shows the outcome without prediction. With prediction, the system initiates the evasive maneuver 0.6 s earlier, achieving a greater lateral distance from the traffic vehicle. The red path, using prediction, maintained 1.26 m more lateral distance compared to the yellow path, which did not use prediction. The quartic Bézier algorithm without prediction resulted in a lateral distance of 2.42 m from the traffic vehicle. Similarly, the blue path in Figure 14c represents the quintic Bézier algorithm with prediction, which secured 1.53 m more lateral distance than the algorithm without prediction. The algorithm without prediction resulted in a lateral distance of 2.19 m from the traffic vehicle.
Figure 15 presents the graphs illustrating the steering wheel angle, yaw rate, and lateral acceleration for each system in Scenario B. From the graphs, it is clear that the system incorporating prediction generated a smoother path and achieved greater lateral stability. Additionally, the quintic Bézier curve demonstrated more stable lateral performance than the quartic Bézier curve. As detailed in Table 5, since Scenario B involves a more abrupt maneuver than Scenario A, the maximum values for lateral acceleration, yaw rate, and steering wheel angle are higher. However, the system with prediction consistently recorded smaller maximum values than the system without prediction. Furthermore, comparing the two algorithms, the quintic Bézier algorithm consistently resulted in smaller maximum values than the quartic Bézier algorithm. For instance, the highest recorded lateral acceleration in Scenario B was 0.5574 g, the yaw rate was 0.2429 deg/s, and the steering wheel angle pealed at 44.6627 deg, all of which occurred when using the quartic Bézier algorithm without prediction.

4.3. Simulation Scenario C

Scenario C, illustrated in Figure 10c, involves the ego vehicle driving in the second lane of a three-lane road at 80 km/h. Ahead in the same lane, there are two vehicles: Traffic1, positioned 20 m ahead, driving at 82.8 km/h, and Traffic2, 40 m ahead, driving at 72 km/h. At this point, Traffic1 initiates a cut-out maneuver into the right lane with a deceleration rate of −1.5 m/s2. While Traffic1 is cutting out, the Traffic2 vehicle decelerates at a rate of −3 m/s2. This scenario simulates a situation where, as the lead vehicle (Traffic1) moves to another lane, a new vehicle (Traffic2) appears and begins decelerating. In this case, the ego vehicle must quickly reassess the updated surroundings, select an appropriate lane to avoid the potential hazard, and execute a safe maneuver.
The simulation results are presented in Figure 16 and Figure 17, showing the positions of the vehicles at 0, 2.5, 5.2, 5.6, 7.5, 9, 11, and 13 s, along with the changes in the ego vehicle’s steering wheel angle, yaw rate, and lateral acceleration over time. Figure 16 illustrates the vehicle trajectories at each time point, confirming that the system using prediction initiated the avoidance maneuver first. At 5.2 s, Traffic2 can be seen stopped in its original lane, and the trajectories of the system with prediction (red and blue) show a much greater lateral distance from the traffic compared to the system without prediction (yellow and purple). Figure 16b,c display the evasive driving trajectories at 5.6 s in Scenario C for each algorithm. The red and yellow trajectories represent the quartic Bézier algorithm with and without prediction, respectively. Using prediction, the system was able to predict the collision and initiate the avoidance maneuver 0.5 s earlier than the system without prediction, achieving a greater lateral distance from Traffic2. The red trajectory with prediction secured 0.73 m more lateral distance compared to the yellow trajectory without prediction, which showed a lateral distance of 2.59 m from Traffic2. Similarly, the blue trajectory in Figure 16c represents the quintic Bézier algorithm with prediction, which secured 0.7 m more lateral distance than the system without prediction, which had a lateral distance of 2.54 m from Traffic2.
Figure 17 displays the graphs of the steering wheel angle, yaw rate, and lateral acceleration for each system in Scenario C. The results indicate that the system utilizing prediction had more time for collision avoidance, allowing for a smoother path and greater lateral stability compared to the system without prediction. Additionally, the quintic Bézier curve ensures a more stable lateral motion than the quartic Bézier curve. As shown in Table 6, since Scenario C involves smoother maneuvers than Scenario A, lower maximum values were recorded. Consistent with previous scenarios, the system using prediction recorded smaller maximum values than the system without prediction. Moreover, the quintic Bézier algorithm resulted in smaller maximum values than the quartic Bézier algorithm, both with and without prediction.

4.4. Simulation Scenario D

Scenario D, illustrated in Figure 10d, involves the ego vehicle driving at 80 km/h in the second lane of a three-lane road. Ahead of the ego vehicle, Traffic2 is driving at 72 km/h, positioned 40 m ahead. In the left lane, Traffic1 is driving at 80 km/h, and in the right lane, Traffic3 is also driving at 80 km/h. Throughout this scenario, Traffic3 maintains constant velocity. Traffic2 begins to decelerate at a rate of −3 m/s2, forcing the ego vehicle to initiate an evasive maneuver by changing to the left lane, as it offers the most stable position relative to the surrounding traffic. The ego vehicle must safely and efficiently execute this lane change to avoid a potential collision. Following the successful completion of the first evasive maneuver, Traffic1 suddenly decelerates at a sharper rate of –6 m/s2, prompting the ego vehicle to quickly plan another lane change to the right lane. The ego vehicle must execute this second evasive maneuver promptly and safely, ultimately returning to the second lane. This scenario is designed to test the vehicle’s ability to perform continuous collision avoidance maneuvers and evaluate whether the system can carry out these successive maneuvers both stably and efficiently. It aims to validate the system’s ability to manage consecutive evasive maneuvers while maintaining safety and operational effectiveness.
The simulation results are presented in Figure 18 and Figure 19, showing the driving situations of the vehicles at 0, 3, 5, 5.85, 11, 13, and 15 s, along with the changes in the ego vehicle’s steering wheel angle, yaw rate, and lateral acceleration over time. In Figure 18, the vehicle positions at each time step are displayed, and it is evident that for both collision avoidance maneuvers, the system using prediction initiates the evasive actions earlier than the system without prediction. At 5 and 11 s, the system with prediction anticipates the potential collision sooner, resulting in earlier avoidance maneuvers. The red and blue trajectories (representing the predicted system) maintain a greater lateral distance from Traffic2 compared to the yellow and purple trajectories (representing the non-predicted system). This demonstrates the benefit of prediction in enabling earlier and more effective collision avoidance.
Figure 18b,c illustrate the evasive maneuvers at 5.85 and 11.25 s, respectively, in Scenario D. The system with prediction starts both evasive maneuvers 0.7 s earlier than the system without prediction, leading to a greater lateral distance from Traffic2. At 5.85 s, the red (predicted) trajectory achieves 0.92 m more lateral distance than the yellow (non-predicted) trajectory, which measures a distance of 2.47 m from Traffic2. In Figure 18b, the blue (predicted) trajectory secures 1 m more lateral distance than the purple (non-predicted) trajectory, which measures 2.25 m from Traffic2. Following the first evasive maneuver, Figure 18c shows that the system using prediction also achieves a greater lateral distance from Traffic1 during the second evasive maneuver, further demonstrating the advantage of prediction in collision avoidance.
Figure 19 shows graphs depicting steering wheel angle, yaw rate, and lateral acceleration for each system in Scenario D. Upon reviewing the graphs, it becomes evident that in both evasive maneuvers, the system utilizing prediction initiates the evasive actions earlier, allowing for more time to perform the maneuvers. This leads to more efficient path planning and improved lateral stability compared to the system without prediction. Table 7 demonstrates that the maximum values recorded in Scenario D were the highest among all previous scenarios. This is likely because, after the first collision avoidance maneuver, the vehicle did not fully stabilize before executing the subsequent evasive maneuvers, leading to larger recorded values. The results still show that, as with previous scenarios, the system using prediction achieved smaller maximum values than the system without prediction. Furthermore, when comparing both algorithms, the quintic Bézier algorithm consistently demonstrated smaller maximum values, indicating superior stability in generating safer paths.

5. Conclusions

This study proposes a collision avoidance path planning method that incorporates the predicted information from surrounding vehicles into the generation of avoidance paths. The methodology is grounded in the potential field approach used in the APF, where the ego vehicle selects the target point deemed safest for collision avoidance maneuvers. This process is divided into three stages to achieve effective collision avoidance.
In the first stage, the predicted information of surrounding vehicles, along with the ego vehicle’s planned path, is used to assess potential collisions by checking for intersections between the predefined risk circles of the ego and surrounding vehicles at each timestep. This predicted information includes the position, yaw, and velocity for the next 2 s from the current time. In the second stage, based on APF theory, the road potential field is constructed using environmental information, while the obstacle potential field is generated by considering the relative distance and velocity between the ego vehicle and other objects. To avoid additional collisions during the avoidance maneuver, future obstacle information is also factored in to create a future obstacle potential field. The road and obstacle potential fields are then combined to form the total potential field. The ego vehicle selects the point with the lowest potential value within the total potential field as the target point. In the final stage, the designated target point, along with the ego vehicle’s current position, is used as a control point to form an objective function that considers factors such as curvature, jerk, the sum of potential values along the generated trajectory, and the lateral distance to the target point. The positions of the control points are then optimized using the SQP algorithm to generate the optimal path.
A comparative analysis was conducted across four scenarios, validated using an integrated simulation environment of IPG CarMaker and MATLAB/Simulink. The comparison focused on the presence or absence of predicted information and the use of quartic and quintic Bézier algorithms. The results revealed that the combination of predicted information and the quintic Bézier algorithm produced the most stable and efficient paths, as indicated by metrics such as yaw rate, lateral acceleration, and steering wheel angle, which serve as indicators of lateral stability.
The proposed method leverages predicted information from surrounding vehicles to enhance collision avoidance and demonstrate that stable behavior can be maintained even in complex environments. However, there are situations where collision avoidance cannot be achieved through path planning alone. Therefore, future research should focus on integrating path and velocity planning based on predicted information, as the ego vehicle’s velocity also plays a critical role in ensuring safety.

Author Contributions

Conceptualization and formal analysis, S.A. (Sumin Ahn); investigation and validation, T.O. (Taeyoung Oh); methodology and software J.Y.; software and writing, J.Y.; All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the Ministry of Trade, Industry and Energy (MOTIE), KOREA, through the Autonomous Driving Development Innovation Program (20014476, Development of Mixed Reality-based Autonomous Driving Parts and System Evaluation Technology).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Ma, Y.; Wang, Z.; Yang, H.; Yang, L. Artificial intelligence applications in the development of autonomous vehicles: A survey. IEEE/CAA J. Autom. Sin. 2020, 7, 315–329. [Google Scholar] [CrossRef]
  2. Schwarting, W.; Alonso-Mora, J.; Rus, D. Planning and decision-making for autonomous vehicles. Annu. Rev. Control. Robot. Auton. Syst. 2018, 1, 187–210. [Google Scholar] [CrossRef]
  3. Chan, C.-Y. Advancements, prospects, and impacts of automated driving systems. Int. J. Transp. Sci. Technol. 2017, 6, 208–216. [Google Scholar] [CrossRef]
  4. Chen, L.; Li, Y.; Huang, C.; Li, B.; Xing, Y.; Tian, D.; Li, L.; Hu, Z.; Na, X.; Li, Z.; et al. Milestones in autonomous driving and intelligent vehicles: Survey of surveys. IEEE Trans. Intell. Veh. 2023, 8, 1046–1056. [Google Scholar] [CrossRef]
  5. ISO 26262-10:2018; Road Vehicles—Functional Safety—Part 10: Guideline on ISO 26262. ISO: Geneva, Switzerland, 2018.
  6. ISO 39003-:2023; Road Traffic Safety—Guidance on Ethical Considerations Relating to Safety for Autonomous Vehicles. ISO: Geneva, Switzerland, 2023.
  7. Autonomous Vehicle Collision Reports. Available online: https://www.dmv.ca.gov/portal/vehicle-industry-services/autonomous-vehicles/autonomous-vehicle-collision-reports/ (accessed on 4 October 2024).
  8. Katrakazas, C.; Quddus, M.; Chen, W.-H.; Deka, L. Real-time motion planning methods for autonomous on-road driving: State-of-the-art and future research directions. Transp. Res. C 2015, 60, 416–442. [Google Scholar] [CrossRef]
  9. Favarò, F.M.; Nader, N.; Eurich, S.O.; Tripp, M.; Varadaraju, N. Examining accident reports involving autonomous vehicles in California. PLoS ONE 2017, 12, e0184952. [Google Scholar] [CrossRef]
  10. González, D.; Pérez, J.; Milanés, V.; Nashashibi, F. A review of motion planning techniques for automated vehicles. IEEE Trans. Intell. Transp. Syst. 2015, 17, 1135–1145. [Google Scholar] [CrossRef]
  11. Candela, E.; Feng, Y.; Mead, D.; Demiris, Y.; Angeloudis, P. Fast collision prediction for autonomous vehicles using a stochastic dynamics model. In Proceedings of the IEEE International Intelligent Transportation Systems Conference (ITSC), Indianapolis, IN, USA, 19–22 September 2021; Volume 2021, pp. 211–216. [Google Scholar]
  12. Huang, R.; Zhuo, G.; Xiong, L.; Lu, S.; Tian, W. A Review of Deep Learning-Based Vehicle Motion Prediction for Autonomous Driving. Sustainability 2023, 15, 14716. [Google Scholar] [CrossRef]
  13. Fang, L.; Jiang, Q.; Shi, J.; Zhou, B. TPNet: Trajectory Proposal Network for Motion Prediction. In Proceedings of the 2020 IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR), Seattle, WA, USA, 13–19 June 2020; pp. 6796–6805. [Google Scholar]
  14. Polychronopoulos, A.; Tsogas, M.; Amditis, A.J.; Andreone, L. Sensor Fusion for Predicting Vehicles’ Path for Collision Avoidance Systems. IEEE Trans. Intell. Transp. Syst. 2007, 8, 549–562. [Google Scholar] [CrossRef]
  15. Da, F.; Zhang, Y. Path-Aware Graph Attention for HD Maps in Motion Prediction. In Proceedings of the International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; pp. 6430–6436. [Google Scholar]
  16. Khatib, O. The Potential Field Approach and Operational Space Formulation in Robot Control, Adaptive and Learning Systems; Springer: Boston, MA, USA, 1986; pp. 367–377. [Google Scholar]
  17. Tran, H.N.; Shin, J.-H.; Jee, K.-S.; Moon, H.-G. Oscillation reduction for artificial potential field using vector projections for robotic manipulators. J. Mech. Sci. Technol. 2023, 37, 3273–3280. [Google Scholar] [CrossRef]
  18. Matoui, F.; Boussaid, B.; Abdelkrim, M.N. Local minimum solution for the potential field method in multiple robot motion planning task. In Proceedings of the 16th International Conference on Sciences and Techniques of Automatic Control and Computer Engineering (STA), Monastir, Tunisia, 21–23 December 2015; pp. 452–457. [Google Scholar]
  19. Rasekhipour, Y.; Khajepour, A.; Chen, S.-K.; Litkouhi, B. A potential field-based model predictive path-planning controller for autonomous road vehicles. IEEE Trans. Intell. Transp. Syst. 2017, 18, 1255–1267. [Google Scholar] [CrossRef]
  20. Wahid, N.; Zamzuri, H.; Amer, N.H.; Dwijotomo, A.; Saruchi, S.A.; Mazlan, S.A. Vehicle collision avoidance motion planning strategy using artificial potential field with adaptive multi-speed scheduler. IET Intell. Transp. Syst. 2020, 14, 1200–1209. [Google Scholar] [CrossRef]
  21. Ma, Q.; Li, M.; Huang, G.; Ullah, S. Overtaking Path Planning for CAV based on Improved Artificial Potential Field. IEEE Trans. Veh. Technol. 2023, 9, 1–13. [Google Scholar] [CrossRef]
  22. Huang, Y.; Ding, H.; Zhang, Y.; Wang, H.; Cao, D.; Xu, N.; Hu, C. A motion planning and tracking framework for autonomous vehicles based on artificial potential field elaborated resistance network approach. IEEE Trans. Ind. Electron. 2020, 67, 1376–1386. [Google Scholar] [CrossRef]
  23. Lin, P.; Choi, W.Y.; Ho Yang, J.H.; Chung, C.C. Waypoint tracking for collision avoidance using artificial potential field. In Proceedings of the 39th Chinese Control. Conference, Shenyang, China, 27–29 July 2020; Volume CCC, pp. 5455–5460. [Google Scholar]
  24. Shang, X.; Eskandarian, A. Emergency collision avoidance and mitigation using model predictive control and artificial potential function. IEEE Trans. Intell. Veh. 2023, 8, 3458–3472. [Google Scholar] [CrossRef]
  25. Choi, J.-W.; Curry, R.; Elkaim, G. Path Planning Based on Bézier Curve for Autonomous Ground Vehicles, Advances in Electrical and Electronics Engineering—IAENG; Special ed. of the World Congress on Engineering and Computer Science; IEEE: San Francisco, CA, USA, 2008; pp. 158–166. [Google Scholar]
  26. Han, L.; Yashiro, H.; Tehrani Nik Nejad, H.; Do, Q.H.; Mita, S. Bézier Curve Based Path Planning for Autonomous Vehicle in Urban Environment; IEEE Intelligent Vehicles Symposium: La Jolla, CA, USA, 2010; pp. 1036–1042. [Google Scholar]
  27. Li, H.; Luo, Y.; Wu, J. Collision-Free Path Planning for intelligent vehicles based on Bézier curve. IEEE Access 2019, 7, 123334–123340. [Google Scholar] [CrossRef]
  28. Chen, J.; Zhao, P.; Mei, T.; Liang, H. Lane change path planning based on piecewise Bézier curve for autonomous vehicle. In Proceedings of the 2013 IEEE International Conference on Vehicular Electronics and Safety, Dongguan, China, 28–30 July 2013; pp. 17–22. [Google Scholar]
  29. Moreau, J.; Melchior, P.; Victor, S.; Cassany, L.; Moze, M.; Aioun, F.; Guillemard, F. Reactive path planning in intersection for autonomous vehicle. IFAC PapersOnLine 2019, 52, 109–114. [Google Scholar] [CrossRef]
  30. Chen, C.; He, Y.; Bu, C.; Han, J.; Zhang, X. Quartic Bézier curve based trajectory generation for autonomous vehicles with curvature and velocity constraints. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 6108–6113. [Google Scholar]
  31. Zhang, L.; Xiao, W.; Zhang, Z.; Meng, D. Surrounding vehicles motion prediction for risk assessment and motion planning of autonomous vehicle in highway scenarios. IEEE Access 2020, 8, 209356–209376. [Google Scholar] [CrossRef]
  32. Yildirim, M.; Mozaffari, S.; McCutcheon, L.; Dianati, M.; Tamaddoni-Nezhad, A.; Fallah, S. Prediction based decision making for autonomous highway driving. In Proceedings of the IEEE 25th International Conference on Intelligent Transportation Systems (ITSC), Macau, China, 8–12 October 2022; Volume 2022, pp. 138–145. [Google Scholar]
  33. Yoon, Y.; Kim, C.; Lee, J.; Yi, K. Interaction-aware probabilistic trajectory prediction of cut-in vehicles using Gaussian process for proactive control of autonomous vehicles. IEEE Access 2021, 9, 63440–63455. [Google Scholar] [CrossRef]
  34. Wang, X.; Hu, J.; Wei, C.; Li, L.; Li, Y.; Du, M. A novel lane-change decision-making with long-time trajectory prediction for autonomous vehicle. IEEE Access 2023, 11, 137437–137449. [Google Scholar] [CrossRef]
  35. Meng, D.; Xiao, W.; Zhang, L.; Zhang, Z.; Liu, Z. Vehicle Trajectory Prediction based Predictive Collision Risk Assessment for Autonomous Driving in Highway Scenarios. arXiv 2023, arXiv:2304.05610. [Google Scholar]
  36. Kim, J.-H.; Kum, D.-S. Threat prediction algorithm based on local path candidates and surrounding vehicle trajectory predictions for automated driving vehicles. In Proceedings of the IEEE Intelligent Vehicles Symposium, Seoul, Republic of Korea, 28 June–1 July 2015; Volume IV, pp. 1220–1225. [Google Scholar]
  37. Kang, T.W.; Yang, J.H.; Choi, W.Y.; Chung, C.C. Time Headway for Overtaking Control of Autonomous Driving Vehicle. In Proceedings of the KSAE Spring Conference, Proceedings, Pyeongchang, Republic of Korea, 22 May 2019; pp. 810–815. [Google Scholar]
  38. Yimer, T.H.; Wen, C.; Yu, X.; Jiang, C. A Study of the Minimum Safe Distance Between Human Driven and Driverless Cars Using Safe Distance Model. arXiv 2020, arXiv:2006.07022. [Google Scholar]
  39. Tang, X.; Yan, Y.; Wang, B. Trajectory tracking control of autonomous vehicles combining ACT-R cognitive framework and preview tracking theory. IEEE Access 2023, 11, 137067–137082. [Google Scholar] [CrossRef]
  40. Tyagi, I. Threat Assessment for avoiding collsions with perpendicular vehicles at Intersections. In Proceedings of the IEEE International Conference on Electro Information Technology (EIT), Mt. Pleasant, MI, USA, 14–15 May 2021; Volume 2021, pp. 184–187. [Google Scholar]
  41. Diachuk, M.; Easa, S.M. Motion planning for autonomous vehicles based on sequential optimization. Vehicles 2022, 4, 344–374. [Google Scholar] [CrossRef]
  42. Li, B.; Acarman, T.; Zhang, Y.; Ouyang, Y.; Yaman, C.; Kong, Q.; Zhong, X.; Peng, X. Optimization-based trajectory planning for autonomous parking with irregularly placed obstacles: A lightweight iterative framework. IEEE Trans. Intell. Transp. Syst. 2022, 23, 11970–11981. [Google Scholar] [CrossRef]
  43. Jiang, Y.; Liu, Z.; Qian, D.; Zuo, H.; He, W.; Wang, J. Robust online path planning for autonomous vehicle using sequential quadratic programming. In Proceedings of the IEEE Intelligent Vehicles Symposium, Aachen, Germany, 4–9 June 2022; Volume IV, pp. 175–182. [Google Scholar]
  44. Wei, Y.; Xu, H. Path planning of autonomous driving based on quadratic. In Proceedings of the Optimization 9th International Conference on Control, Automation and Robotics (ICCAR), Beijing, China, 21–23 April 2023; Volume 2023, pp. 308–312. [Google Scholar]
  45. ISO 34502-:2022; Road Vehicles—Test Scenarios for Automated Driving Systems—Scenario Based Safety Evaluation Framework. ISO: Geneva, Switzerland, 2022.
Figure 1. Example paths based on cubic, quartic, and quintic Bézier curves.
Figure 1. Example paths based on cubic, quartic, and quintic Bézier curves.
Sensors 24 07292 g001
Figure 2. Architecture diagram of the collision-avoidance path planning system.
Figure 2. Architecture diagram of the collision-avoidance path planning system.
Sensors 24 07292 g002
Figure 3. Schematic diagram of risk assessment circles.
Figure 3. Schematic diagram of risk assessment circles.
Sensors 24 07292 g003
Figure 4. Illustration of the highway driving scenario and corresponding road potential field.
Figure 4. Illustration of the highway driving scenario and corresponding road potential field.
Sensors 24 07292 g004
Figure 5. Comparison of obstacle potential field distributions under different conditions.
Figure 5. Comparison of obstacle potential field distributions under different conditions.
Sensors 24 07292 g005
Figure 6. Visualization of the total potential field.
Figure 6. Visualization of the total potential field.
Sensors 24 07292 g006
Figure 7. Visualization of the total potential field combining prediction.
Figure 7. Visualization of the total potential field combining prediction.
Sensors 24 07292 g007
Figure 8. The total potential value of target positions.
Figure 8. The total potential value of target positions.
Sensors 24 07292 g008
Figure 9. Quartic and quintic Bézier curve modeling.
Figure 9. Quartic and quintic Bézier curve modeling.
Sensors 24 07292 g009
Figure 10. Scenarios used in the verification simulation.
Figure 10. Scenarios used in the verification simulation.
Sensors 24 07292 g010
Figure 11. CarMaker Simulation and MATLAB/Simulink integrated environment for the collision-avoidance path planning methodology.
Figure 11. CarMaker Simulation and MATLAB/Simulink integrated environment for the collision-avoidance path planning methodology.
Sensors 24 07292 g011
Figure 12. Simulation results for Scenario A. (a) Vehicle trajectories and time series vehicles position (0, 3, 6, 6.5, 9, 11, and 13 s). (b) Comparison of 6.5 s trajectories: Quartic w/prediction (red) vs. w/o prediction (yellow). (c) Comparison of 6.5 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Figure 12. Simulation results for Scenario A. (a) Vehicle trajectories and time series vehicles position (0, 3, 6, 6.5, 9, 11, and 13 s). (b) Comparison of 6.5 s trajectories: Quartic w/prediction (red) vs. w/o prediction (yellow). (c) Comparison of 6.5 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Sensors 24 07292 g012
Figure 13. Scenario A: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Figure 13. Scenario A: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Sensors 24 07292 g013
Figure 14. Simulation results for Scenario B. (a) Vehicle trajectories and time series vehicle positions (0, 2.5, 4.3, 5.2, 8, 10, and 13 s). (b) Comparison of 5.2 s trajectories: Quartic w/prediction (red) vs. w/o prediction (yellow). (c) Comparison of 5.2 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Figure 14. Simulation results for Scenario B. (a) Vehicle trajectories and time series vehicle positions (0, 2.5, 4.3, 5.2, 8, 10, and 13 s). (b) Comparison of 5.2 s trajectories: Quartic w/prediction (red) vs. w/o prediction (yellow). (c) Comparison of 5.2 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Sensors 24 07292 g014
Figure 15. Scenario B: comparison of steering wheel angle, yaw rate, and lateral acceleration.
Figure 15. Scenario B: comparison of steering wheel angle, yaw rate, and lateral acceleration.
Sensors 24 07292 g015
Figure 16. Simulation results for Scenario C. (a) Vehicle trajectories and time series vehicles position (0, 2.5, 5.2, 7.5, 9, 11, and 13 s). (b) Comparison of 5.6 s trajectories: Quartic /w prediction (red) vs. w/o prediction (yellow). (c) Comparison of 5.6 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Figure 16. Simulation results for Scenario C. (a) Vehicle trajectories and time series vehicles position (0, 2.5, 5.2, 7.5, 9, 11, and 13 s). (b) Comparison of 5.6 s trajectories: Quartic /w prediction (red) vs. w/o prediction (yellow). (c) Comparison of 5.6 s trajectories: Quintic w/prediction (blue) vs. w/o prediction (purple).
Sensors 24 07292 g016
Figure 17. Scenario C: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Figure 17. Scenario C: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Sensors 24 07292 g017
Figure 18. Simulation results of Scenario D. (a) Vehicle trajectories and time series vehicle position (0, 3, 5, 5.85, 11, 13, and 15 sec). (b) Comparison of 5.85 s trajectories: [Left] Quartic w/prediction (red) vs. w/o prediction (yellow), [Right] Quintic w/prediction (blue) vs. w/o prediction (purple). (c) Comparison of 11.25 s trajectories: [Left] Quartic w/prediction (red) vs. w/out prediction (yellow), [Right] Quintic w/prediction (blue) vs. w/o prediction (purple).
Figure 18. Simulation results of Scenario D. (a) Vehicle trajectories and time series vehicle position (0, 3, 5, 5.85, 11, 13, and 15 sec). (b) Comparison of 5.85 s trajectories: [Left] Quartic w/prediction (red) vs. w/o prediction (yellow), [Right] Quintic w/prediction (blue) vs. w/o prediction (purple). (c) Comparison of 11.25 s trajectories: [Left] Quartic w/prediction (red) vs. w/out prediction (yellow), [Right] Quintic w/prediction (blue) vs. w/o prediction (purple).
Sensors 24 07292 g018
Figure 19. Scenario D: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Figure 19. Scenario D: Comparison of steering wheel angle, yaw rate, and lateral acceleration.
Sensors 24 07292 g019
Table 1. Parameters settings for risk circles.
Table 1. Parameters settings for risk circles.
L F L w L R L B L t r f W t r f Unit
0.8452.970.821.894.471.97m
Table 2. Parameters settings for the road and obstacle potential fields.
Table 2. Parameters settings for the road and obstacle potential fields.
SymbolDescriptionValueUnit
w Width of each lane3.5m
Y c 1 Global lateral position of the first lane−1.75m
Y c 3 Global lateral position of the third lane−8.75m
p Parameter for the road potential field function0.1--
δ x Longitudinal deviation for obstacle potential field5--
δ y Lateral deviation for obstacle potential field0.5--
μParameter to prevent errors in the obstacle potential field1 × 10−5--
Table 3. Hyperparameters settings for the objective function.
Table 3. Hyperparameters settings for the objective function.
SymbolDescriptionValueUnit
a Coefficient of curvature term for objective function1--
b Coefficient of total potential value term for objective function1--
c Coefficient of jerk term for objective function1--
κ m a x Maximum curvature0.3 m 1
γ Threshold of TTC2s
ε Coefficient of the laterally offset term for objective function5--
Table 4. Scenario A: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Table 4. Scenario A: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Scenario AMaximum
Lateral Acceleration (g)
Maximum
Yaw Rate (deg/s)
Maximum
Steering Wheel Angle (deg)
Quartic w/prediction0.47580.211436.9478
Quintic w/prediction0.40300.179431.7464
Quartic w/o prediction0.55100.244944.6391
Quintic w/o prediction0.50080.222239.9116
Table 5. Scenario B: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Table 5. Scenario B: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Scenario BMaximum
Lateral Acceleration (g)
Maximum
Yaw Rate (deg/s)
Maximum
Steering Wheel Angle (deg)
Quartic w/prediction0.47160.209037.2937
Quintic w/prediction0.42130.186533.0276
Quartic w/o prediction0.55740.242944.6627
Quintic w/o prediction0.50540.224740.1564
Table 6. Scenario C: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Table 6. Scenario C: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Scenario CMaximum
Lateral Acceleration (g)
Maximum
Yaw Rate (deg/s)
Maximum
Steering Wheel Angle (deg)
Quartic w/prediction0.39140.173130.5570
Quintic w/prediction0.35390.156627.4941
Quartic w/o prediction0.51690.227140.7668
Quintic w/o prediction0.45700.203036.2411
Table 7. Scenario D: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Table 7. Scenario D: Comparison of lateral stability based on maximum lateral acceleration, maximum yaw rate, and maximum steering wheel angle.
Scenario DMaximum
Lateral Acceleration (g)
Maximum
Yaw Rate (deg/s)
Maximum
Steering Wheel Angle (deg)
Quartic w/prediction0.48020.211538.2716
Quintic w/prediction0.43000.190833.7257
Quartic w/o prediction0.59560.260146.2612
Quintic w/o prediction0.52420.232741.6060
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

Ahn, S.; Oh, T.; Yoo, J. Collision Avoidance Path Planning for Automated Vehicles Using Prediction Information and Artificial Potential Field. Sensors 2024, 24, 7292. https://doi.org/10.3390/s24227292

AMA Style

Ahn S, Oh T, Yoo J. Collision Avoidance Path Planning for Automated Vehicles Using Prediction Information and Artificial Potential Field. Sensors. 2024; 24(22):7292. https://doi.org/10.3390/s24227292

Chicago/Turabian Style

Ahn, Sumin, Taeyoung Oh, and Jinwoo Yoo. 2024. "Collision Avoidance Path Planning for Automated Vehicles Using Prediction Information and Artificial Potential Field" Sensors 24, no. 22: 7292. https://doi.org/10.3390/s24227292

APA Style

Ahn, S., Oh, T., & Yoo, J. (2024). Collision Avoidance Path Planning for Automated Vehicles Using Prediction Information and Artificial Potential Field. Sensors, 24(22), 7292. https://doi.org/10.3390/s24227292

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